From 00e5c568604bf5cf1659907fcb69c71039273bd3 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 3 May 2024 15:33:22 -0400 Subject: [PATCH 001/147] WIP move files around and update CMakeLists.txt. --- CMakeLists.txt | 232 ++++-------------- examples/CMakeLists.txt | 12 +- examples/CV7/CV7_example.c | 2 +- examples/CV7_INS/ublox_device.hpp | 2 +- examples/GQ7/GQ7_example.c | 2 +- examples/GX5_45/GX5_45_example.c | 2 +- examples/example_utils.cpp | 2 +- examples/example_utils.hpp | 4 +- examples/watch_imu.c | 6 +- src/microstrain/CMakeLists.txt | 4 + src/microstrain/common/CMakeLists.txt | 26 ++ .../common}/descriptor_id.hpp | 2 +- .../common}/device_models.c | 0 .../common}/device_models.h | 0 .../extras => microstrain/common}/index.hpp | 0 src/{mip => microstrain/common}/mip_logging.c | 0 src/{mip => microstrain/common}/mip_logging.h | 22 +- src/microstrain/common/platform.h | 48 ++++ src/microstrain/connections/CMakeLists.txt | 14 ++ src/microstrain/connections/connection.hpp | 63 +++++ .../connections/serial/CMakeLists.txt | 15 ++ .../connections/serial}/serial_connection.cpp | 4 +- .../connections/serial}/serial_connection.hpp | 17 +- .../connections/serial}/serial_port.c | 2 +- .../connections/serial}/serial_port.h | 0 .../connections/tcp/CMakeLists.txt | 19 ++ .../connections/tcp}/tcp_connection.cpp | 0 .../connections/tcp}/tcp_connection.hpp | 4 +- .../connections/tcp}/tcp_socket.c | 2 +- .../connections/tcp}/tcp_socket.h | 0 src/microstrain/extras/CMakeLists.txt | 5 + .../extras/composite_result.hpp | 8 +- .../extras/recording_connection.cpp | 0 .../extras/recording_connection.hpp | 2 +- .../extras/scope_helper.cpp | 0 .../extras/scope_helper.hpp | 0 src/{mip => microstrain}/extras/version.cpp | 0 src/{mip => microstrain}/extras/version.hpp | 0 src/mip/CMakeLists.txt | 117 +++++++++ src/mip/mip_device.cpp | 46 ++-- src/mip/mip_device.hpp | 54 +--- test/CMakeLists.txt | 5 +- test/test_serial.cpp | 3 +- 43 files changed, 447 insertions(+), 299 deletions(-) create mode 100644 src/microstrain/CMakeLists.txt create mode 100644 src/microstrain/common/CMakeLists.txt rename src/{mip/extras => microstrain/common}/descriptor_id.hpp (97%) rename src/{mip/extras => microstrain/common}/device_models.c (100%) rename src/{mip/extras => microstrain/common}/device_models.h (100%) rename src/{mip/extras => microstrain/common}/index.hpp (100%) rename src/{mip => microstrain/common}/mip_logging.c (100%) rename src/{mip => microstrain/common}/mip_logging.h (91%) create mode 100644 src/microstrain/common/platform.h create mode 100644 src/microstrain/connections/CMakeLists.txt create mode 100644 src/microstrain/connections/connection.hpp create mode 100644 src/microstrain/connections/serial/CMakeLists.txt rename src/{mip/platform => microstrain/connections/serial}/serial_connection.cpp (94%) rename src/{mip/platform => microstrain/connections/serial}/serial_connection.hpp (79%) rename src/{mip/utils => microstrain/connections/serial}/serial_port.c (99%) rename src/{mip/utils => microstrain/connections/serial}/serial_port.h (100%) create mode 100644 src/microstrain/connections/tcp/CMakeLists.txt rename src/{mip/platform => microstrain/connections/tcp}/tcp_connection.cpp (100%) rename src/{mip/platform => microstrain/connections/tcp}/tcp_connection.hpp (95%) rename src/{mip/utils => microstrain/connections/tcp}/tcp_socket.c (99%) rename src/{mip/utils => microstrain/connections/tcp}/tcp_socket.h (100%) create mode 100644 src/microstrain/extras/CMakeLists.txt rename src/{mip => microstrain}/extras/composite_result.hpp (97%) rename src/{mip => microstrain}/extras/recording_connection.cpp (100%) rename src/{mip => microstrain}/extras/recording_connection.hpp (99%) rename src/{mip => microstrain}/extras/scope_helper.cpp (100%) rename src/{mip => microstrain}/extras/scope_helper.hpp (100%) rename src/{mip => microstrain}/extras/version.cpp (100%) rename src/{mip => microstrain}/extras/version.hpp (100%) create mode 100644 src/mip/CMakeLists.txt diff --git a/CMakeLists.txt b/CMakeLists.txt index c4ccb3f05..b579fa91b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,26 +1,21 @@ cmake_minimum_required(VERSION 3.10) -set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD 20) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_C_STANDARD 11) set(CMAKE_C_STANDARD_REQUIRED ON) project( "MIP SDK" - VERSION "0.0.01" + VERSION "2.0.00" DESCRIPTION "MicroStrain Communications Library for embedded systems" LANGUAGES C CXX ) set(SRC_DIR "${CMAKE_CURRENT_LIST_DIR}/src") -set(EXT_DIR "${CMAKE_CURRENT_LIST_DIR}/ext") set(MIP_CMAKE_DIR "${CMAKE_CURRENT_LIST_DIR}/cmake") -include_directories( - "${SRC_DIR}" -) - if(WITH_INTERNAL) if(NOT DEFINED MIP_INTERNAL_DIR) set(MIP_INTERNAL_DIR "int" CACHE PATH "") @@ -80,118 +75,16 @@ configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) # Build options # -option(MIP_USE_SERIAL "Build serial connection support into the library and examples" ON) -option(MIP_USE_TCP "Build TCP connection support into the library and exampels" ON) option(MIP_USE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) -option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) - -option(MIP_ENABLE_LOGGING "Build with logging functions enabled" ON) -set(MIP_LOGGING_MAX_LEVEL "" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") - -set(MIP_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") option(BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) -# -# Utils -# - -set(UTILS_DIR "${MIP_DIR}/utils") - -set(UTILS_SOURCES - "${UTILS_DIR}/byte_ring.c" - "${UTILS_DIR}/byte_ring.h" - "${UTILS_DIR}/serialization.c" - "${UTILS_DIR}/serialization.h" -) - -# -# MIP Control -# - -set(MIP_SOURCES - "${VERSION_OUT_FILE}" - "${MIP_DIR}/mip_cmdqueue.c" - "${MIP_DIR}/mip_cmdqueue.h" - "${MIP_DIR}/mip_dispatch.c" - "${MIP_DIR}/mip_dispatch.h" - "${MIP_DIR}/mip_field.c" - "${MIP_DIR}/mip_field.h" - "${MIP_DIR}/mip_offsets.h" - "${MIP_DIR}/mip_packet.c" - "${MIP_DIR}/mip_packet.h" - "${MIP_DIR}/mip_parser.c" - "${MIP_DIR}/mip_parser.h" - "${MIP_DIR}/mip_result.c" - "${MIP_DIR}/mip_result.h" - "${MIP_DIR}/mip_types.h" - "${MIP_DIR}/definitions/common.c" - "${MIP_DIR}/definitions/common.h" - "${MIP_DIR}/definitions/descriptors.c" - "${MIP_DIR}/definitions/descriptors.h" - "${MIP_DIR}/mip.hpp" - "${MIP_DIR}/mip_all.h" - "${MIP_DIR}/mip_all.hpp" -) -set(MIPDEV_SOURCES - "${MIP_DIR}/mip_interface.c" - "${MIP_DIR}/mip_interface.h" - "${MIP_DIR}/mip_device.cpp" - "${MIP_DIR}/mip_device.hpp" -) -set(MIPDEF_SOURCES - "${MIP_DIR}/definitions/commands_3dm.c" - "${MIP_DIR}/definitions/commands_3dm.h" - "${MIP_DIR}/definitions/commands_base.c" - "${MIP_DIR}/definitions/commands_base.h" - "${MIP_DIR}/definitions/commands_filter.c" - "${MIP_DIR}/definitions/commands_filter.h" - "${MIP_DIR}/definitions/commands_gnss.c" - "${MIP_DIR}/definitions/commands_gnss.h" - "${MIP_DIR}/definitions/commands_rtk.c" - "${MIP_DIR}/definitions/commands_rtk.h" - "${MIP_DIR}/definitions/commands_aiding.c" - "${MIP_DIR}/definitions/commands_aiding.h" - "${MIP_DIR}/definitions/commands_system.c" - "${MIP_DIR}/definitions/commands_system.h" - "${MIP_DIR}/definitions/data_filter.c" - "${MIP_DIR}/definitions/data_filter.h" - "${MIP_DIR}/definitions/data_gnss.c" - "${MIP_DIR}/definitions/data_gnss.h" - "${MIP_DIR}/definitions/data_sensor.c" - "${MIP_DIR}/definitions/data_sensor.h" - "${MIP_DIR}/definitions/data_shared.c" - "${MIP_DIR}/definitions/data_shared.h" - "${MIP_DIR}/definitions/data_system.c" - "${MIP_DIR}/definitions/data_system.h" - ${INTDEF_SOURCES} -) +add_subdirectory(src/microstrain) +add_subdirectory(src/mip) -string(REGEX REPLACE "\.h(;|$)" ".hpp\\1" MIPDEF_HPP_SOURCES "${MIPDEF_SOURCES}") -string(REGEX REPLACE "\.c(;|$)" ".cpp\\1" MIPDEF_CPP_SOURCES "${MIPDEF_HPP_SOURCES}") -if(MIP_USE_SERIAL) - list(APPEND UTILS_SOURCES - "${UTILS_DIR}/serial_port.c" - "${UTILS_DIR}/serial_port.h" - ) - list(APPEND MIP_INTERFACE_SOURCES - "${MIP_DIR}/platform/serial_connection.hpp" - "${MIP_DIR}/platform/serial_connection.cpp" - ) -endif() -if(MIP_USE_TCP) - list(APPEND UTILS_SOURCES - "${UTILS_DIR}/tcp_socket.c" - "${UTILS_DIR}/tcp_socket.h" - ) - list(APPEND MIP_INTERFACE_SOURCES - "${MIP_DIR}/platform/tcp_connection.hpp" - "${MIP_DIR}/platform/tcp_connection.cpp" - ) -endif() if(MIP_USE_EXTRAS) list(APPEND MIP_DEFINES "MIP_USE_EXTRAS") set(MIP_EXTRAS_DIR "${MIP_DIR}/extras") @@ -210,51 +103,14 @@ if(MIP_USE_EXTRAS) ) endif() -# Logging is a little weird since we need to install the header no matter what -list(APPEND MIP_SOURCES "${MIP_DIR}/mip_logging.h") -if(MIP_ENABLE_LOGGING) - list(APPEND MIP_SOURCES "${MIP_DIR}/mip_logging.c") - list(APPEND MIP_DEFINES "MIP_ENABLE_LOGGING") -endif() - -set(ALL_MIP_SOURCES - ${MIPDEF_SOURCES} - ${MIPDEF_CPP_SOURCES} - ${MIPDEV_SOURCES} - ${MIP_SOURCES} - ${UTILS_SOURCES} - ${MIP_CPP_HEADERS} - ${MIP_INTERFACE_SOURCES} - ${MIP_EXTRA_SOURCES} -) - -option(MIP_DISABLE_CPP "Excludes all C++ files from the project." OFF) -if(MIP_DISABLE_CPP) - list(FILTER ALL_MIP_SOURCES EXCLUDE REGEX "[c|h]pp$") -endif() - -add_library(mip ${ALL_MIP_SOURCES}) - # # Preprocessor definitions # -if(${MIP_LOGGING_MAX_LEVEL}) - list(APPEND MIP_DEFINES "MIP_LOGGING_MAX_LEVEL=${MIP_LOGGING_MAX_LEVEL}") -endif() - -if(${MIP_TIMESTAMP_TYPE}) - list(APPEND MIP_DEFINES "MIP_TIMESTAMP_TYPE=${MIP_TIMESTAMP_TYPE}") -endif() - -if(${MIP_ENABLE_DIAGNOSTICS}) - list(APPEND MIP_DEFINES "MIP_ENABLE_DIAGNOSTICS") -endif() - # Disable windows defined min/max # Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) if(WIN32) - list(APPEND MIP_DEFINES "NOMINMAX=1" "_WIN32_WINNT=0x0501") + compile_definitions("NOMINMAX=1" "_WIN32_WINNT=0x0501") endif() if(MSVC) @@ -263,14 +119,10 @@ else() target_compile_options(mip PRIVATE -Wall -Wextra) endif() -target_compile_definitions(mip PUBLIC "${MIP_DEFINES}") # # Libraries # -if(WIN32 AND MIP_USE_TCP) - target_link_libraries(mip PUBLIC "ws2_32") -endif() # # TESTING @@ -374,43 +226,43 @@ write_basic_package_version_file( # Installation # -# Only install headers that we build the source files for -set(ALL_MIP_HEADERS "${ALL_MIP_SOURCES}") -list(FILTER ALL_MIP_HEADERS INCLUDE REGEX "^.*\.(h|hpp)$") -foreach(MIP_HEADER ${ALL_MIP_HEADERS}) - string(REPLACE "${SRC_DIR}/" "" MIP_HEADER_RELATIVE "${MIP_HEADER}") - if(INT_DIR) - string(REPLACE "${INT_DIR}/" "" MIP_HEADER_RELATIVE "${MIP_HEADER_RELATIVE}") - endif() - set(MIP_HEADER_DESTINATION_FULL "${CMAKE_INSTALL_INCLUDEDIR}/${MIP_HEADER_RELATIVE}") - get_filename_component(MIP_HEADER_DESTINATION "${MIP_HEADER_DESTINATION_FULL}" DIRECTORY) - install( - FILES "${MIP_HEADER}" - DESTINATION "${MIP_HEADER_DESTINATION}" - COMPONENT mip - ) -endforeach() - -install(TARGETS - mip - EXPORT mip-targets - ARCHIVE - COMPONENT mip - DESTINATION "${CMAKE_INSTALL_LIBDIR}/" -) - -install(EXPORT - mip-targets - COMPONENT mip - DESTINATION "${CONFIG_EXPORT_DIR}" -) - -install(FILES - "${CMAKE_BINARY_DIR}/mip-config.cmake" - "${CMAKE_BINARY_DIR}/mip-config-version.cmake" - COMPONENT mip - DESTINATION "${CONFIG_EXPORT_DIR}" -) +## Only install headers that we build the source files for +#set(ALL_MIP_HEADERS "${ALL_MIP_SOURCES}") +#list(FILTER ALL_MIP_HEADERS INCLUDE REGEX "^.*\.(h|hpp)$") +#foreach(MIP_HEADER ${ALL_MIP_HEADERS}) +# string(REPLACE "${SRC_DIR}/" "" MIP_HEADER_RELATIVE "${MIP_HEADER}") +# if(INT_DIR) +# string(REPLACE "${INT_DIR}/" "" MIP_HEADER_RELATIVE "${MIP_HEADER_RELATIVE}") +# endif() +# set(MIP_HEADER_DESTINATION_FULL "${CMAKE_INSTALL_INCLUDEDIR}/${MIP_HEADER_RELATIVE}") +# get_filename_component(MIP_HEADER_DESTINATION "${MIP_HEADER_DESTINATION_FULL}" DIRECTORY) +# install( +# FILES "${MIP_HEADER}" +# DESTINATION "${MIP_HEADER_DESTINATION}" +# COMPONENT mip +# ) +#endforeach() +# +#install(TARGETS +# mip +# EXPORT mip-targets +# ARCHIVE +# COMPONENT mip +# DESTINATION "${CMAKE_INSTALL_LIBDIR}/" +#) +# +#install(EXPORT +# mip-targets +# COMPONENT mip +# DESTINATION "${CONFIG_EXPORT_DIR}" +#) +# +#install(FILES +# "${CMAKE_BINARY_DIR}/mip-config.cmake" +# "${CMAKE_BINARY_DIR}/mip-config-version.cmake" +# COMPONENT mip +# DESTINATION "${CONFIG_EXPORT_DIR}" +#) # Try to determine what architecture we are building for based on the compiler output if(MSVC) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 403976dfe..dfedda563 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -9,10 +9,12 @@ set(DEVICE_SOURCES if(MIP_USE_SERIAL) set(SERIAL_DEFS "MIP_USE_SERIAL") + set(SERIAL_LIB microstrain_serial) endif() if(MIP_USE_TCP) set(TCP_DEFS "MIP_USE_TCP") + set(SOCKET_LIB microstrain_socket) endif() if(MIP_USE_EXTRAS) @@ -29,35 +31,43 @@ if(MIP_USE_SERIAL OR MIP_USE_TCP) add_executable(DeviceInfo "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/device_info.cpp" ${DEVICE_SOURCES}) target_link_libraries(DeviceInfo mip "${SERIAL_LIB}" "${SOCKET_LIB}") target_compile_definitions(DeviceInfo PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(DeviceInfo PRIVATE ${SRC_DIR}) add_executable(WatchImu "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/watch_imu.cpp" ${DEVICE_SOURCES}) target_link_libraries(WatchImu mip "${SERIAL_LIB}" "${SOCKET_LIB}") target_compile_definitions(WatchImu PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(WatchImu PRIVATE ${SRC_DIR}) find_package(Threads REQUIRED) add_executable(ThreadingDemo "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/threading.cpp" ${DEVICE_SOURCES}) target_link_libraries(ThreadingDemo mip "${SERIAL_LIB}" "${SOCKET_LIB}" "${CMAKE_THREAD_LIBS_INIT}") target_compile_definitions(ThreadingDemo PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(ThreadingDemo PRIVATE ${SRC_DIR}) add_executable(GQ7_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/GQ7/GQ7_example.cpp" ${DEVICE_SOURCES}) target_link_libraries(GQ7_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") target_compile_definitions(GQ7_Example PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(GQ7_Example PRIVATE ${SRC_DIR}) add_executable(CV7_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/CV7/CV7_example.cpp" ${DEVICE_SOURCES}) target_link_libraries(CV7_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") target_compile_definitions(CV7_Example PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(CV7_Example PRIVATE ${SRC_DIR}) add_executable(CV7_INS_Simple_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_example.cpp" ${DEVICE_SOURCES}) target_link_libraries(CV7_INS_Simple_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") target_compile_definitions(CV7_INS_Simple_Example PUBLIC "${SERIAL_DEFS}" "${TCP_DEFS}") + target_include_directories(CV7_INS_Simple_Example PRIVATE ${SRC_DIR}) add_executable(CV7_INS_Simple_Ublox_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_ublox_example.cpp" ${DEVICE_SOURCES} CV7_INS/ublox_device.hpp CV7_INS/simple_ublox_parser.hpp) target_link_libraries(CV7_INS_Simple_Ublox_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") - target_compile_definitions(CV7_INS_Simple_Ublox_Example PUBLIC "${SERIAL_DEFS}" "${TCP_DEFS}") + target_compile_definitions(CV7_INS_Simple_Ublox_Example PUBLIC "${SERIAL_DEFS}" "${TCP_DEFS}") + target_include_directories(CV7_INS_Simple_Ublox_Example PRIVATE ${SRC_DIR}) add_executable(GX5_45_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/GX5_45/GX5_45_example.cpp" ${DEVICE_SOURCES}) target_link_libraries(GX5_45_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") target_compile_definitions(GX5_45_Example PUBLIC "${MIP_EXAMPLE_DEFS}") + target_include_directories(GX5_45_Example PRIVATE ${SRC_DIR}) endif() diff --git a/examples/CV7/CV7_example.c b/examples/CV7/CV7_example.c index d455ef6a5..96a55f03f 100644 --- a/examples/CV7/CV7_example.c +++ b/examples/CV7/CV7_example.c @@ -28,7 +28,7 @@ //////////////////////////////////////////////////////////////////////////////// #include -#include +#include "microstrain/connections/serial/serial_port.h" #include #include #include diff --git a/examples/CV7_INS/ublox_device.hpp b/examples/CV7_INS/ublox_device.hpp index 6ba8f5d6c..b861eec4b 100644 --- a/examples/CV7_INS/ublox_device.hpp +++ b/examples/CV7_INS/ublox_device.hpp @@ -24,7 +24,7 @@ #include "simple_ublox_parser.hpp" -#include "mip/platform/serial_connection.hpp" +#include "microstrain/connections/serial/serial_connection.hpp" #define PVT_PAYLOAD_SIZE 92 diff --git a/examples/GQ7/GQ7_example.c b/examples/GQ7/GQ7_example.c index cd257d080..d895d2866 100644 --- a/examples/GQ7/GQ7_example.c +++ b/examples/GQ7/GQ7_example.c @@ -28,7 +28,7 @@ //////////////////////////////////////////////////////////////////////////////// #include -#include +#include "microstrain/connections/serial/serial_port.h" #include #include #include diff --git a/examples/GX5_45/GX5_45_example.c b/examples/GX5_45/GX5_45_example.c index b895bc64e..426679da6 100644 --- a/examples/GX5_45/GX5_45_example.c +++ b/examples/GX5_45/GX5_45_example.c @@ -28,7 +28,7 @@ //////////////////////////////////////////////////////////////////////////////// #include -#include +#include "microstrain/connections/serial/serial_port.h" #include #include #include diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index c4bde773b..ca9231a2d 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -3,7 +3,7 @@ #include -#include +#include "microstrain/common/mip_logging.h" #include "example_utils.hpp" diff --git a/examples/example_utils.hpp b/examples/example_utils.hpp index a95376728..04afbafa6 100644 --- a/examples/example_utils.hpp +++ b/examples/example_utils.hpp @@ -2,10 +2,10 @@ #pragma once #ifdef MIP_USE_SERIAL - #include "mip/platform/serial_connection.hpp" + #include "microstrain/connections/serial/serial_connection.hpp" #endif #ifdef MIP_USE_TCP - #include "mip/platform/tcp_connection.hpp" + #include "microstrain/connections/tcp/tcp_connection.hpp" #endif #ifdef MIP_USE_EXTRAS #include "mip/extras/recording_connection.hpp" diff --git a/examples/watch_imu.c b/examples/watch_imu.c index 7fd76467d..7cc5fb3cd 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -4,7 +4,7 @@ #include #include #include -#include +#include "microstrain/common/mip_logging.h" #include #include @@ -12,9 +12,9 @@ #include #include -#include +#include "microstrain/connections/serial/serial_port.h" -#include +#include "microstrain/common/mip_logging.h" #include #include diff --git a/src/microstrain/CMakeLists.txt b/src/microstrain/CMakeLists.txt new file mode 100644 index 000000000..8b19364e5 --- /dev/null +++ b/src/microstrain/CMakeLists.txt @@ -0,0 +1,4 @@ + +add_subdirectory(common) +add_subdirectory(connections) +add_subdirectory(extras) diff --git a/src/microstrain/common/CMakeLists.txt b/src/microstrain/common/CMakeLists.txt new file mode 100644 index 000000000..d8ebbd658 --- /dev/null +++ b/src/microstrain/common/CMakeLists.txt @@ -0,0 +1,26 @@ + +option(MIP_ENABLE_LOGGING "Build with logging functions enabled" ON) +set(MIP_LOGGING_MAX_LEVEL "MIP_LOG_LEVEL_WARN" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") + + +set(SOURCES + platform.h + descriptor_id.hpp + index.hpp + mip_logging.h +) + + +add_library(microstrain_common ${SOURCES}) + + +# Logging is a little weird since we need to install the header no matter what +if(MIP_ENABLE_LOGGING) + if(MIP_LOGGING_LEVEL_MAX STREQUAL "") + message(FATAL_ERROR "MIP_LOGGING_MAX_LEVEL must be MIP_LOG_LEVEL_* or a number") + endif() + target_sources(microstrain_common PRIVATE "mip_logging.c") + target_compile_definitions(microstrain_common PUBLIC "MIP_ENABLE_LOGGING" "MIP_LOGGING_MAX_LEVEL=${MIP_LOGGING_MAX_LEVEL}") +endif() + +target_include_directories(microstrain_common PRIVATE ${SRC_DIR}) diff --git a/src/mip/extras/descriptor_id.hpp b/src/microstrain/common/descriptor_id.hpp similarity index 97% rename from src/mip/extras/descriptor_id.hpp rename to src/microstrain/common/descriptor_id.hpp index 768f97045..b43a0ed6a 100644 --- a/src/mip/extras/descriptor_id.hpp +++ b/src/microstrain/common/descriptor_id.hpp @@ -1,6 +1,6 @@ #pragma once -#include "../definitions/descriptors.h" +#include "mip/definitions/descriptors.h" #include diff --git a/src/mip/extras/device_models.c b/src/microstrain/common/device_models.c similarity index 100% rename from src/mip/extras/device_models.c rename to src/microstrain/common/device_models.c diff --git a/src/mip/extras/device_models.h b/src/microstrain/common/device_models.h similarity index 100% rename from src/mip/extras/device_models.h rename to src/microstrain/common/device_models.h diff --git a/src/mip/extras/index.hpp b/src/microstrain/common/index.hpp similarity index 100% rename from src/mip/extras/index.hpp rename to src/microstrain/common/index.hpp diff --git a/src/mip/mip_logging.c b/src/microstrain/common/mip_logging.c similarity index 100% rename from src/mip/mip_logging.c rename to src/microstrain/common/mip_logging.c diff --git a/src/mip/mip_logging.h b/src/microstrain/common/mip_logging.h similarity index 91% rename from src/mip/mip_logging.h rename to src/microstrain/common/mip_logging.h index b847b729a..dba5f0288 100644 --- a/src/mip/mip_logging.h +++ b/src/microstrain/common/mip_logging.h @@ -74,6 +74,16 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); #define MIP_LOG_LOG(level, ...) (void)0 #endif +#define XSTR(x) STR(x) +#define STR(x) #x + +#ifndef MIP_LOGGING_MAX_LEVEL +#define MIP_LOGGING_MAX_LEVEL MIP_LOG_LEVEL_WARN +#pragma message "NOT DEFINED" +#else +#pragma message "The value of ABC: " XSTR(MIP_LOGGING_MAX_LEVEL) +#endif + //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at fatal level /// @@ -81,7 +91,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); ///@param fmt printf style format string ///@param ... Variadic args used to populate the fmt string /// -#if !defined(MIP_LOGGING_MAX_LEVEL) || MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_FATAL +#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_FATAL #define MIP_LOG_FATAL(...) MIP_LOG_LOG(MIP_LOG_LEVEL_FATAL, __VA_ARGS__) #else #define MIP_LOG_FATAL(...) (void)0 @@ -90,7 +100,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at error level ///@copydetails mip::C::MIP_LOG_FATAL -#if !defined(MIP_LOGGING_MAX_LEVEL) || MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_ERROR +#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_ERROR #define MIP_LOG_ERROR(...) MIP_LOG_LOG(MIP_LOG_LEVEL_ERROR, __VA_ARGS__) #else #define MIP_LOG_ERROR(...) (void)0 @@ -99,7 +109,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at warn level ///@copydetails mip::C::MIP_LOG_FATAL -#if !defined(MIP_LOGGING_MAX_LEVEL) || MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_WARN +#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_WARN #define MIP_LOG_WARN(...) MIP_LOG_LOG(MIP_LOG_LEVEL_WARN, __VA_ARGS__) #else #define MIP_LOG_WARN(...) (void)0 @@ -108,7 +118,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at info level ///@copydetails mip::C::MIP_LOG_FATAL -#if !defined(MIP_LOGGING_MAX_LEVEL) || MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_INFO +#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_INFO #define MIP_LOG_INFO(...) MIP_LOG_LOG(MIP_LOG_LEVEL_INFO, __VA_ARGS__) #else #define MIP_LOG_INFO(...) (void)0 @@ -117,7 +127,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at debug level ///@copydetails mip::C::MIP_LOG_FATAL -#if !defined(MIP_LOGGING_MAX_LEVEL) || MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_DEBUG +#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_DEBUG #define MIP_LOG_DEBUG(...) MIP_LOG_LOG(MIP_LOG_LEVEL_DEBUG, __VA_ARGS__) #else #define MIP_LOG_DEBUG(...) (void)0 @@ -126,7 +136,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at trace level ///@copydetails mip::C::MIP_LOG_FATAL -#if !defined(MIP_LOGGING_MAX_LEVEL) || MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_TRACE +#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_TRACE #define MIP_LOG_TRACE(...) MIP_LOG_LOG(MIP_LOG_LEVEL_TRACE, __VA_ARGS__) #else #define MIP_LOG_TRACE(...) (void)0 diff --git a/src/microstrain/common/platform.h b/src/microstrain/common/platform.h new file mode 100644 index 000000000..243e2dbdb --- /dev/null +++ b/src/microstrain/common/platform.h @@ -0,0 +1,48 @@ +#pragma once + +#if defined _WIN32 +#define MICROSTRAIN_PLATFORM_WINDOWS +#elif defined __APPLE__ +#define MICROSTRAIN_PLATFORM_APPLE +#elif defined __linux__ +#define MICROSTRAIN_PLATFORM_LINUX +#else +#define MICROSTRAIN_PLATFORM_OTHER +#endif + +#include + + + +//#ifdef __cplusplus +//namespace microstrain { +//#endif +// +/////@brief Type used for packet timestamps and timeouts. +///// +///// Timestamps must be monotonic except for overflow at the maximum value back to 0. +///// The units can be anything, but typically are milliseconds. Choose a long enough +///// unit so that consecutive calls to the parser will not exceed half of the maximum +///// value for this type. For milliseconds, the time to overflow is approximately 50 +///// days, so the parser should be invoked at least every 25 days. Failure to observe +///// this requirement may result in false timeouts or delays in getting parsed packets. +///// +//#ifdef MICROSTRAIN_TIMESTAMP_TYPE +//typedef MICROSTRAIN_TIMESTAMP_TYPE microstrain_timestamp; +// static_assert( sizeof(microstrain_timestamp) >= 8 || microstrain_timestamp(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); +//#else +//typedef uint64_t microstrain_timestamp; +//#endif +// +//typedef microstrain_timestamp microstrain_timeout; +// +// +//#ifdef __cplusplus +// +//} // extern "C" +//} // namespace C +// +//using Timestamp = C::mip_timestamp; +//using Timeout = C::mip_timeout; +// +//} // namespace microstrain diff --git a/src/microstrain/connections/CMakeLists.txt b/src/microstrain/connections/CMakeLists.txt new file mode 100644 index 000000000..73ebed9ea --- /dev/null +++ b/src/microstrain/connections/CMakeLists.txt @@ -0,0 +1,14 @@ + + +option(MIP_USE_SERIAL "Build serial connection support into the library and examples" ON) +option(MIP_USE_TCP "Build TCP connection support into the library and exampels" ON) + +if(MIP_USE_SERIAL) + add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/serial) +endif() + +if(MIP_USE_TCP) + add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/tcp) +endif() + + diff --git a/src/microstrain/connections/connection.hpp b/src/microstrain/connections/connection.hpp new file mode 100644 index 000000000..04d178af2 --- /dev/null +++ b/src/microstrain/connections/connection.hpp @@ -0,0 +1,63 @@ +#pragma once + +#include "microstrain/common/platform.h" + +#include +#include + +#if __cpp_lib_span >= 202002L +#include +#endif + + +namespace microstrain +{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief Represents a type of connection to a MIP device. +/// +/// The following methods are pure virtual and must be implemented by a derived +/// class. These functions map to the corresponding C functions. +///@li `bool sendToDevice(const uint8_t* data, size_t length)` - corresponds to mip_interface_user_send_to_device. +///@li `bool recvFromDevice(uint8_t* buffer, size_t maxLength, size_t* lengthOut, Timestamp* timestampOut)` - corresponds to mip_interface_user_recv_from_device. +/// +class Connection +{ +public: + + static constexpr auto TYPE = "None"; + + Connection() { mType = TYPE; }; + virtual ~Connection() {} + + virtual bool sendToDevice(const uint8_t* data, size_t length) = 0; + virtual bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out) = 0; + +#if __cpp_lib_span >= 202002L + bool sendToDevice(std::span data) { return sendToDevice(data.data(), data.size()); } + bool recvFromDevice(std::span& buffer, unsigned int wait_time_ms) { + size_t length = 0; + if(!recvFromDevice(buffer.data(), buffer.size(), wait_time_ms, &length)) + return false; + buffer = buffer.first(length); + return true; + } +#endif + + virtual bool isConnected() const = 0; + virtual bool connect() = 0; + virtual bool disconnect() = 0; + + const char* type() const { return mType; }; + + virtual const char* interfaceName() const = 0; + virtual uint32_t parameter() const = 0; + +protected: + + const char *mType; + +}; + + +} // namespace microstrain diff --git a/src/microstrain/connections/serial/CMakeLists.txt b/src/microstrain/connections/serial/CMakeLists.txt new file mode 100644 index 000000000..0f7c3f6bd --- /dev/null +++ b/src/microstrain/connections/serial/CMakeLists.txt @@ -0,0 +1,15 @@ + + +set(SOURCES + serial_connection.cpp + serial_connection.hpp + serial_port.h + serial_port.c + ../connection.hpp +) + +add_library(microstrain_serial ${SOURCES}) + +target_link_libraries(microstrain_serial PUBLIC microstrain_common) + +target_include_directories(microstrain_serial PRIVATE ${SRC_DIR}) diff --git a/src/mip/platform/serial_connection.cpp b/src/microstrain/connections/serial/serial_connection.cpp similarity index 94% rename from src/mip/platform/serial_connection.cpp rename to src/microstrain/connections/serial/serial_connection.cpp index 22603e7a6..7b9380b66 100644 --- a/src/mip/platform/serial_connection.cpp +++ b/src/microstrain/connections/serial/serial_connection.cpp @@ -13,9 +13,9 @@ namespace platform /// ///@param portName Path to the port to connect to. On Windows, this usually looks like "COM", on linux, "/dev/tty" ///@param baudrate Baud rate to open the device at. Note that the device needs to be configured to -SerialConnection::SerialConnection(const std::string& portName, uint32_t baudrate) +SerialConnection::SerialConnection(std::string portName, uint32_t baudrate) { - mPortName = portName; + mPortName = std::move(portName); mBaudrate = baudrate; mType = TYPE; diff --git a/src/mip/platform/serial_connection.hpp b/src/microstrain/connections/serial/serial_connection.hpp similarity index 79% rename from src/mip/platform/serial_connection.hpp rename to src/microstrain/connections/serial/serial_connection.hpp index 6ecd6d5f1..1ad819527 100644 --- a/src/mip/platform/serial_connection.hpp +++ b/src/microstrain/connections/serial/serial_connection.hpp @@ -1,13 +1,14 @@ #pragma once -#include -#include +#include "mip/mip_device.hpp" +#include "../connection.hpp" +#include "serial_port.h" #include -namespace mip +namespace microstrain { -namespace platform +namespace connections { //////////////////////////////////////////////////////////////////////////////// @@ -17,16 +18,16 @@ namespace platform //////////////////////////////////////////////////////////////////////////////// ///@brief Can be used on Windows, OSX, or linux to communicate with a MIP device over serial /// -class SerialConnection : public mip::Connection +class Serial : public microstrain::Connection { public: static constexpr auto TYPE = "Serial"; - SerialConnection(const std::string& portName, uint32_t baudrate); - ~SerialConnection(); + Connection(std::string portName, uint32_t baudrate); + ~Connection(); - bool recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, mip::Timestamp* timestamp) final; + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out) final; bool sendToDevice(const uint8_t* data, size_t length) final; bool isConnected() const override; diff --git a/src/mip/utils/serial_port.c b/src/microstrain/connections/serial/serial_port.c similarity index 99% rename from src/mip/utils/serial_port.c rename to src/microstrain/connections/serial/serial_port.c index bffa9a829..9de7e9602 100644 --- a/src/mip/utils/serial_port.c +++ b/src/microstrain/connections/serial/serial_port.c @@ -1,5 +1,5 @@ -#include "mip/mip_logging.h" +#include "microstrain/common/mip_logging.h" #include "serial_port.h" diff --git a/src/mip/utils/serial_port.h b/src/microstrain/connections/serial/serial_port.h similarity index 100% rename from src/mip/utils/serial_port.h rename to src/microstrain/connections/serial/serial_port.h diff --git a/src/microstrain/connections/tcp/CMakeLists.txt b/src/microstrain/connections/tcp/CMakeLists.txt new file mode 100644 index 000000000..66f5285fa --- /dev/null +++ b/src/microstrain/connections/tcp/CMakeLists.txt @@ -0,0 +1,19 @@ + + +set(SOURCES + tcp_connection.cpp + tcp_connection.hpp + tcp_socket.h + tcp_socket.c + ../connection.hpp +) + +add_library(microstrain_socket ${SOURCES}) + +target_link_libraries(microstrain_socket PUBLIC microstrain_common) + +if(WIN32) + target_link_libraries(microstrain_socket PUBLIC "ws2_32") +endif() + +target_include_directories(microstrain_socket PRIVATE ${SRC_DIR}) diff --git a/src/mip/platform/tcp_connection.cpp b/src/microstrain/connections/tcp/tcp_connection.cpp similarity index 100% rename from src/mip/platform/tcp_connection.cpp rename to src/microstrain/connections/tcp/tcp_connection.cpp diff --git a/src/mip/platform/tcp_connection.hpp b/src/microstrain/connections/tcp/tcp_connection.hpp similarity index 95% rename from src/mip/platform/tcp_connection.hpp rename to src/microstrain/connections/tcp/tcp_connection.hpp index a33bc9558..4692e51cb 100644 --- a/src/mip/platform/tcp_connection.hpp +++ b/src/microstrain/connections/tcp/tcp_connection.hpp @@ -1,8 +1,8 @@ #pragma once -#include +#include "mip/mip_device.hpp" -#include +#include "tcp_socket.h" #include diff --git a/src/mip/utils/tcp_socket.c b/src/microstrain/connections/tcp/tcp_socket.c similarity index 99% rename from src/mip/utils/tcp_socket.c rename to src/microstrain/connections/tcp/tcp_socket.c index 1e4d05734..6297a45b3 100644 --- a/src/mip/utils/tcp_socket.c +++ b/src/microstrain/connections/tcp/tcp_socket.c @@ -1,7 +1,7 @@ #include "tcp_socket.h" -#include "mip/mip_logging.h" +#include "microstrain/common/mip_logging.h" #ifdef _WIN32 diff --git a/src/mip/utils/tcp_socket.h b/src/microstrain/connections/tcp/tcp_socket.h similarity index 100% rename from src/mip/utils/tcp_socket.h rename to src/microstrain/connections/tcp/tcp_socket.h diff --git a/src/microstrain/extras/CMakeLists.txt b/src/microstrain/extras/CMakeLists.txt new file mode 100644 index 000000000..7d1509e22 --- /dev/null +++ b/src/microstrain/extras/CMakeLists.txt @@ -0,0 +1,5 @@ + + +set(SOURCES + composite_result.hpp +) diff --git a/src/mip/extras/composite_result.hpp b/src/microstrain/extras/composite_result.hpp similarity index 97% rename from src/mip/extras/composite_result.hpp rename to src/microstrain/extras/composite_result.hpp index 89729a049..569825cf0 100644 --- a/src/mip/extras/composite_result.hpp +++ b/src/microstrain/extras/composite_result.hpp @@ -1,10 +1,10 @@ #pragma once -#include "descriptor_id.hpp" +#include "microstrain/common/descriptor_id.hpp" -#include "../mip_device.hpp" -#include "../mip_result.h" -#include "../definitions/descriptors.h" +#include "mip/mip_device.hpp" +#include "mip/mip_result.h" +#include "mip/definitions/descriptors.h" #include diff --git a/src/mip/extras/recording_connection.cpp b/src/microstrain/extras/recording_connection.cpp similarity index 100% rename from src/mip/extras/recording_connection.cpp rename to src/microstrain/extras/recording_connection.cpp diff --git a/src/mip/extras/recording_connection.hpp b/src/microstrain/extras/recording_connection.hpp similarity index 99% rename from src/mip/extras/recording_connection.hpp rename to src/microstrain/extras/recording_connection.hpp index 4297d7651..71af6743b 100644 --- a/src/mip/extras/recording_connection.hpp +++ b/src/microstrain/extras/recording_connection.hpp @@ -1,6 +1,6 @@ #pragma once -#include +#include "mip/mip_device.hpp" #include #include diff --git a/src/mip/extras/scope_helper.cpp b/src/microstrain/extras/scope_helper.cpp similarity index 100% rename from src/mip/extras/scope_helper.cpp rename to src/microstrain/extras/scope_helper.cpp diff --git a/src/mip/extras/scope_helper.hpp b/src/microstrain/extras/scope_helper.hpp similarity index 100% rename from src/mip/extras/scope_helper.hpp rename to src/microstrain/extras/scope_helper.hpp diff --git a/src/mip/extras/version.cpp b/src/microstrain/extras/version.cpp similarity index 100% rename from src/mip/extras/version.cpp rename to src/microstrain/extras/version.cpp diff --git a/src/mip/extras/version.hpp b/src/microstrain/extras/version.hpp similarity index 100% rename from src/mip/extras/version.hpp rename to src/microstrain/extras/version.hpp diff --git a/src/mip/CMakeLists.txt b/src/mip/CMakeLists.txt new file mode 100644 index 000000000..5ec9e15be --- /dev/null +++ b/src/mip/CMakeLists.txt @@ -0,0 +1,117 @@ + + +option(MIP_DISABLE_CPP "Excludes all C++ files from the project." OFF) +option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) + +set(MIP_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") + +# +# Utils +# + +set(UTILS_DIR "${MIP_DIR}/utils") + +set(UTILS_SOURCES + "${UTILS_DIR}/byte_ring.c" + "${UTILS_DIR}/byte_ring.h" + "${UTILS_DIR}/serialization.c" + "${UTILS_DIR}/serialization.h" +) + +# +# MIP Control +# + +set(MIP_SOURCES + "${VERSION_OUT_FILE}" + "${MIP_DIR}/mip_cmdqueue.c" + "${MIP_DIR}/mip_cmdqueue.h" + "${MIP_DIR}/mip_dispatch.c" + "${MIP_DIR}/mip_dispatch.h" + "${MIP_DIR}/mip_field.c" + "${MIP_DIR}/mip_field.h" + "${MIP_DIR}/mip_offsets.h" + "${MIP_DIR}/mip_packet.c" + "${MIP_DIR}/mip_packet.h" + "${MIP_DIR}/mip_parser.c" + "${MIP_DIR}/mip_parser.h" + "${MIP_DIR}/mip_result.c" + "${MIP_DIR}/mip_result.h" + "${MIP_DIR}/mip_types.h" + "${MIP_DIR}/definitions/common.c" + "${MIP_DIR}/definitions/common.h" + "${MIP_DIR}/definitions/descriptors.c" + "${MIP_DIR}/definitions/descriptors.h" + "${MIP_DIR}/mip.hpp" + "${MIP_DIR}/mip_all.h" + "${MIP_DIR}/mip_all.hpp" +) + +set(MIPDEV_SOURCES + "${MIP_DIR}/mip_interface.c" + "${MIP_DIR}/mip_interface.h" + "${MIP_DIR}/mip_device.cpp" + "${MIP_DIR}/mip_device.hpp" +) + +set(MIPDEF_SOURCES + "${MIP_DIR}/definitions/commands_3dm.c" + "${MIP_DIR}/definitions/commands_3dm.h" + "${MIP_DIR}/definitions/commands_base.c" + "${MIP_DIR}/definitions/commands_base.h" + "${MIP_DIR}/definitions/commands_filter.c" + "${MIP_DIR}/definitions/commands_filter.h" + "${MIP_DIR}/definitions/commands_gnss.c" + "${MIP_DIR}/definitions/commands_gnss.h" + "${MIP_DIR}/definitions/commands_rtk.c" + "${MIP_DIR}/definitions/commands_rtk.h" + "${MIP_DIR}/definitions/commands_aiding.c" + "${MIP_DIR}/definitions/commands_aiding.h" + "${MIP_DIR}/definitions/commands_system.c" + "${MIP_DIR}/definitions/commands_system.h" + "${MIP_DIR}/definitions/data_filter.c" + "${MIP_DIR}/definitions/data_filter.h" + "${MIP_DIR}/definitions/data_gnss.c" + "${MIP_DIR}/definitions/data_gnss.h" + "${MIP_DIR}/definitions/data_sensor.c" + "${MIP_DIR}/definitions/data_sensor.h" + "${MIP_DIR}/definitions/data_shared.c" + "${MIP_DIR}/definitions/data_shared.h" + "${MIP_DIR}/definitions/data_system.c" + "${MIP_DIR}/definitions/data_system.h" + ${INTDEF_SOURCES} +) + +string(REGEX REPLACE "\.h(;|$)" ".hpp\\1" MIPDEF_HPP_SOURCES "${MIPDEF_SOURCES}") +string(REGEX REPLACE "\.c(;|$)" ".cpp\\1" MIPDEF_CPP_SOURCES "${MIPDEF_HPP_SOURCES}") + +set(ALL_MIP_SOURCES + ${MIPDEF_SOURCES} + ${MIPDEF_CPP_SOURCES} + ${MIPDEV_SOURCES} + ${MIP_SOURCES} + ${UTILS_SOURCES} + ${MIP_CPP_HEADERS} + ${MIP_INTERFACE_SOURCES} + ${MIP_EXTRA_SOURCES} +) + +if(MIP_DISABLE_CPP) + list(FILTER ALL_MIP_SOURCES EXCLUDE REGEX "[c|h]pp$") +endif() + +add_library(mip ${ALL_MIP_SOURCES}) + + + +if(${MIP_ENABLE_DIAGNOSTICS}) + list(APPEND MIP_DEFINES "MIP_ENABLE_DIAGNOSTICS") +endif() + +if(${MIP_TIMESTAMP_TYPE}) + list(APPEND MIP_DEFINES "MIP_TIMESTAMP_TYPE=${MIP_TIMESTAMP_TYPE}") +endif() + +target_compile_definitions(mip PUBLIC "${MIP_DEFINES}") + +target_link_libraries(mip PUBLIC microstrain_common) diff --git a/src/mip/mip_device.cpp b/src/mip/mip_device.cpp index d1d47968a..88db73a27 100644 --- a/src/mip/mip_device.cpp +++ b/src/mip/mip_device.cpp @@ -24,28 +24,28 @@ namespace mip { //////////////////////////////////////////////////////////////////////////////// -//////////////////////////////////////////////////////////////////////////////// -///@brief Sets up the mip interface callbacks to point at this object. -/// -///@note This sets the interface's user pointer to this connection object. -/// -///@param device Device to configure. -/// -void Connection::connect_interface(C::mip_interface* device) -{ - auto send = [](C::mip_interface* device, const uint8_t* data, size_t length)->bool - { - return static_cast(C::mip_interface_user_pointer(device))->sendToDevice(data, length); - }; - auto recv = [](C::mip_interface* device, uint8_t* buffer, size_t max_length, C::mip_timeout wait_time, size_t* length_out, C::mip_timestamp* timestamp_out)->bool - { - return static_cast(C::mip_interface_user_pointer(device))->recvFromDevice(buffer, max_length, wait_time, length_out, timestamp_out); - }; - - C::mip_interface_set_user_pointer(device, this); - - C::mip_interface_set_send_function(device, send); - C::mip_interface_set_recv_function(device, recv); -} +////////////////////////////////////////////////////////////////////////////////// +/////@brief Sets up the mip interface callbacks to point at this object. +///// +/////@note This sets the interface's user pointer to this connection object. +///// +/////@param device Device to configure. +///// +//void Connection::connect_interface(C::mip_interface* device) +//{ +// auto send = [](C::mip_interface* device, const uint8_t* data, size_t length)->bool +// { +// return static_cast(C::mip_interface_user_pointer(device))->sendToDevice(data, length); +// }; +// auto recv = [](C::mip_interface* device, uint8_t* buffer, size_t max_length, C::mip_timeout wait_time, size_t* length_out, C::mip_timestamp* timestamp_out)->bool +// { +// return static_cast(C::mip_interface_user_pointer(device))->recvFromDevice(buffer, max_length, wait_time, length_out, timestamp_out); +// }; +// +// C::mip_interface_set_user_pointer(device, this); +// +// C::mip_interface_set_send_function(device, send); +// C::mip_interface_set_recv_function(device, recv); +//} } // namespace mip diff --git a/src/mip/mip_device.hpp b/src/mip/mip_device.hpp index 743186dd3..ee201226e 100644 --- a/src/mip/mip_device.hpp +++ b/src/mip/mip_device.hpp @@ -133,44 +133,6 @@ template CmdResult runCommand(C::mip_interface& device template bool startCommand(C::mip_interface& device, C::mip_pending_cmd& pending, const Cmd& cmd, Timeout additionalTime); -//////////////////////////////////////////////////////////////////////////////// -///@brief Represents a type of connection to a MIP device. -/// -/// The following methods are pure virtual and must be implemented by a derived -/// class. These functions map to the corresponding C functions. -///@li `bool sendToDevice(const uint8_t* data, size_t length)` - corresponds to mip_interface_user_send_to_device. -///@li `bool recvFromDevice(uint8_t* buffer, size_t maxLength, size_t* lengthOut, Timestamp* timestampOut)` - corresponds to mip_interface_user_recv_from_device. -/// -class Connection -{ -public: - - static constexpr auto TYPE = "None"; - - Connection() { mType = TYPE; }; - virtual ~Connection() {} - - virtual bool sendToDevice(const uint8_t* data, size_t length) = 0; - virtual bool recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, Timestamp* timestamp_out) = 0; - - virtual bool isConnected() const = 0; - virtual bool connect() = 0; - virtual bool disconnect() = 0; - - void connect_interface(C::mip_interface* device); - - const char* type() const { return mType; }; - - virtual const char* interfaceName() const = 0; - virtual uint32_t parameter() const = 0; - -protected: - - const char *mType; - -}; - - //////////////////////////////////////////////////////////////////////////////// ///@brief Represents a connected MIP device. /// @@ -188,14 +150,14 @@ class DeviceInterface : public C::mip_interface C::mip_interface_init(this, parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout, nullptr, nullptr, &C::mip_interface_default_update, nullptr); } - ///@copydoc mip::C::mip_interface_init - ///@param connection The connection object used to communicate with the device. This object must exist for the life of the DeviceInterface object - DeviceInterface(Connection* connection, uint8_t* parseBuffer, size_t parseBufferSize, Timeout parseTimeout, Timeout baseReplyTimeout) : - DeviceInterface(parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout) - { - if(connection) - connection->connect_interface(this); - } + /////@copydoc mip::C::mip_interface_init + /////@param connection The connection object used to communicate with the device. This object must exist for the life of the DeviceInterface object + //DeviceInterface(Connection* connection, uint8_t* parseBuffer, size_t parseBufferSize, Timeout parseTimeout, Timeout baseReplyTimeout) : + // DeviceInterface(parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout) + //{ + // if(connection) + // connection->connect_interface(this); + //} DeviceInterface(const DeviceInterface&) = delete; DeviceInterface& operator=(const DeviceInterface&) = delete; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 14d2eb56a..011136407 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -9,6 +9,7 @@ macro(add_mip_test name sources command) add_executable(${name} ${sources}) + target_include_directories(${name} PRIVATE ${SRC_DIR}) target_link_libraries(${name} mip) add_test(${name} ${command} ${ARGN}) @@ -22,9 +23,9 @@ add_mip_test(TestMipFields "${TEST_DIR}/mip/test_mip_fields.c" TestMipFi add_mip_test(TestMipCpp "${TEST_DIR}/mip/test_mip.cpp" TestMipCpp) add_mip_test(TestMipPerf "${TEST_DIR}/mip/mip_parser_performance.cpp" TestMipPerf) -if(WITH_SERIAL) +if(MIP_USE_SERIAL) add_executable(TestSerial "${TEST_DIR}/test_serial.cpp") - target_include_directories(TestSerial PUBLIC "${SERIAL_INCLUDE_DIRS}") + target_include_directories(TestSerial PUBLIC "${SRC_DIR}") target_link_libraries(TestSerial PUBLIC "serial") add_test(TestSerial TestSerial) endif() diff --git a/test/test_serial.cpp b/test/test_serial.cpp index b01796417..18e2d890b 100644 --- a/test/test_serial.cpp +++ b/test/test_serial.cpp @@ -1,6 +1,7 @@ -#include +#include +#include #include From 183fa8a80b94e26f59ebfd9f5532d6745bfb2549 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 6 May 2024 17:01:52 -0400 Subject: [PATCH 002/147] Continue WIP. DeviceInfo example works. --- examples/CMakeLists.txt | 86 ++++++++----------- examples/CV7_INS/ublox_device.hpp | 18 ++-- examples/example_utils.cpp | 24 +++--- examples/example_utils.hpp | 4 +- examples/threading.cpp | 2 +- src/microstrain/common/CMakeLists.txt | 3 +- src/microstrain/common/microstrain_time.h | 46 ++++++++++ src/microstrain/common/mip_logging.h | 6 -- src/microstrain/common/platform.h | 38 +------- src/microstrain/connections/CMakeLists.txt | 5 +- src/microstrain/connections/connection.hpp | 4 +- .../connections/recording/CMakeLists.txt | 13 +++ .../recording}/recording_connection.cpp | 26 +++--- .../recording}/recording_connection.hpp | 25 +++--- .../connections/serial/CMakeLists.txt | 2 +- .../connections/serial/serial_connection.cpp | 12 +-- .../connections/serial/serial_connection.hpp | 12 +-- .../connections/tcp/CMakeLists.txt | 2 +- .../connections/tcp/tcp_connection.cpp | 14 +-- .../connections/tcp/tcp_connection.hpp | 24 +++--- src/mip/CMakeLists.txt | 2 + src/mip/mip_device.cpp | 50 ++++++----- src/mip/mip_device.hpp | 28 ++++-- test/CMakeLists.txt | 12 +-- test/test_serial.cpp | 3 +- 25 files changed, 248 insertions(+), 213 deletions(-) create mode 100644 src/microstrain/common/microstrain_time.h create mode 100644 src/microstrain/connections/recording/CMakeLists.txt rename src/microstrain/{extras => connections/recording}/recording_connection.cpp (72%) rename src/microstrain/{extras => connections/recording}/recording_connection.hpp (82%) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index dfedda563..5eee7b56f 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -2,19 +2,25 @@ set(EXAMPLE_DIR "${CMAKE_CURRENT_LIST_DIR}") -set(DEVICE_SOURCES +set(EXAMPLE_SOURCES "${EXAMPLE_DIR}/example_utils.cpp" "${EXAMPLE_DIR}/example_utils.hpp" ) +set(EXAMPLE_LIBS ) + if(MIP_USE_SERIAL) set(SERIAL_DEFS "MIP_USE_SERIAL") - set(SERIAL_LIB microstrain_serial) + list(APPEND EXAMPLE_LIBS microstrain_serial) endif() if(MIP_USE_TCP) set(TCP_DEFS "MIP_USE_TCP") - set(SOCKET_LIB microstrain_socket) + list(APPEND EXAMPLE_LIBS microstrain_socket) +endif() + +if(MIP_USE_SERIAL OR MIP_USE_TCP) + list(APPEND EXAMPLE_LIBS microstrain_recording_connection) endif() if(MIP_USE_EXTRAS) @@ -23,51 +29,32 @@ endif() set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) +macro(add_mip_example name sources) + + add_executable(${name} ${sources}) + + target_link_libraries(${name} mip ${EXAMPLE_LIBS}) + target_compile_definitions(${name} PUBLIC ${MIP_EXAMPLE_DEFS}) + target_include_directories(${name} PRIVATE ${SRC_DIR}) + +endmacro() + # C++ examples need either serial or TCP support if(MIP_USE_SERIAL OR MIP_USE_TCP) if(NOT MIP_DISABLE_CPP) - add_executable(DeviceInfo "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/device_info.cpp" ${DEVICE_SOURCES}) - target_link_libraries(DeviceInfo mip "${SERIAL_LIB}" "${SOCKET_LIB}") - target_compile_definitions(DeviceInfo PUBLIC "${MIP_EXAMPLE_DEFS}") - target_include_directories(DeviceInfo PRIVATE ${SRC_DIR}) - - add_executable(WatchImu "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/watch_imu.cpp" ${DEVICE_SOURCES}) - target_link_libraries(WatchImu mip "${SERIAL_LIB}" "${SOCKET_LIB}") - target_compile_definitions(WatchImu PUBLIC "${MIP_EXAMPLE_DEFS}") - target_include_directories(WatchImu PRIVATE ${SRC_DIR}) - - find_package(Threads REQUIRED) - add_executable(ThreadingDemo "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/threading.cpp" ${DEVICE_SOURCES}) - target_link_libraries(ThreadingDemo mip "${SERIAL_LIB}" "${SOCKET_LIB}" "${CMAKE_THREAD_LIBS_INIT}") - target_compile_definitions(ThreadingDemo PUBLIC "${MIP_EXAMPLE_DEFS}") - target_include_directories(ThreadingDemo PRIVATE ${SRC_DIR}) - - add_executable(GQ7_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/GQ7/GQ7_example.cpp" ${DEVICE_SOURCES}) - target_link_libraries(GQ7_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") - target_compile_definitions(GQ7_Example PUBLIC "${MIP_EXAMPLE_DEFS}") - target_include_directories(GQ7_Example PRIVATE ${SRC_DIR}) - - add_executable(CV7_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/CV7/CV7_example.cpp" ${DEVICE_SOURCES}) - target_link_libraries(CV7_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") - target_compile_definitions(CV7_Example PUBLIC "${MIP_EXAMPLE_DEFS}") - target_include_directories(CV7_Example PRIVATE ${SRC_DIR}) - - add_executable(CV7_INS_Simple_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_example.cpp" ${DEVICE_SOURCES}) - target_link_libraries(CV7_INS_Simple_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") - target_compile_definitions(CV7_INS_Simple_Example PUBLIC "${SERIAL_DEFS}" "${TCP_DEFS}") - target_include_directories(CV7_INS_Simple_Example PRIVATE ${SRC_DIR}) - - add_executable(CV7_INS_Simple_Ublox_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_ublox_example.cpp" ${DEVICE_SOURCES} CV7_INS/ublox_device.hpp CV7_INS/simple_ublox_parser.hpp) - target_link_libraries(CV7_INS_Simple_Ublox_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") - target_compile_definitions(CV7_INS_Simple_Ublox_Example PUBLIC "${SERIAL_DEFS}" "${TCP_DEFS}") - target_include_directories(CV7_INS_Simple_Ublox_Example PRIVATE ${SRC_DIR}) - - add_executable(GX5_45_Example "${EXAMPLE_SOURCES}" "${EXAMPLE_DIR}/GX5_45/GX5_45_example.cpp" ${DEVICE_SOURCES}) - target_link_libraries(GX5_45_Example mip "${SERIAL_LIB}" "${SOCKET_LIB}") - target_compile_definitions(GX5_45_Example PUBLIC "${MIP_EXAMPLE_DEFS}") - target_include_directories(GX5_45_Example PRIVATE ${SRC_DIR}) + # Generic examples + add_mip_example(DeviceInfo "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/device_info.cpp") + add_mip_example(WatchImu "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.cpp") + add_mip_example(Threads "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/threading.cpp") + + # Product-specific examples + add_mip_example(GQ7_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") + add_mip_example(CV7_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CV7/CV7_example.cpp") + add_mip_example(CV7_INS_Simple_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_example.cpp") + add_mip_example(CV7_INS_Simple_Ublox_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_ublox_example.cpp") + add_mip_example(GX5_45_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/GX5_45/GX5_45_example.cpp") endif() @@ -75,15 +62,10 @@ endif() # C examples need serial support if(MIP_USE_SERIAL) - add_executable(WatchImuC "${EXAMPLE_DIR}/watch_imu.c") - target_link_libraries(WatchImuC mip) - - add_executable(GQ7_ExampleC "${EXAMPLE_DIR}/GQ7/GQ7_example.c") - target_link_libraries(GQ7_ExampleC mip) - add_executable(CV7_ExampleC "${EXAMPLE_DIR}/CV7/CV7_example.c") - target_link_libraries(CV7_ExampleC mip) + add_mip_example(WatchImuC "${EXAMPLE_DIR}/watch_imu.c") + add_mip_example(GQ7_ExampleC "${EXAMPLE_DIR}/GQ7/GQ7_example.c") + add_mip_example(CV7_ExampleC "${EXAMPLE_DIR}/CV7/CV7_example.c") + add_mip_example(GX5_45_ExampleC "${EXAMPLE_DIR}/GX5_45/GX5_45_example.c") - add_executable(GX5_45_ExampleC "${EXAMPLE_DIR}/GX5_45/GX5_45_example.c") - target_link_libraries(GX5_45_ExampleC mip) endif() \ No newline at end of file diff --git a/examples/CV7_INS/ublox_device.hpp b/examples/CV7_INS/ublox_device.hpp index b861eec4b..f6ea7440c 100644 --- a/examples/CV7_INS/ublox_device.hpp +++ b/examples/CV7_INS/ublox_device.hpp @@ -135,12 +135,16 @@ namespace mip { public: - UbloxDevice(std::unique_ptr connection) : _connection(std::move(connection)), - _message_parser( - [this](const std::vector& packet) { - handle_packet(packet); - }) - {} + UbloxDevice(std::unique_ptr connection) : + _connection(std::move(connection)), + _message_parser( + [this](const std::vector &packet) + { + handle_packet(packet); + } + ) + { + } void handle_packet(const std::vector& packet) { @@ -184,7 +188,7 @@ namespace mip protected: - std::unique_ptr _connection; + std::unique_ptr _connection; UbloxMessageParser _message_parser; bool _new_pvt_message_received = false; diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index ca9231a2d..ad683ee22 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -49,12 +49,12 @@ void customLog(void* user, mip_log_level level, const char* fmt, va_list args) std::unique_ptr openFromArgs(const std::string& port_or_hostname, const std::string& baud_or_port, const std::string& binary_file_path) { - auto example_utils = std::unique_ptr(new ExampleUtils()); + auto example_utils = std::make_unique(); if( !binary_file_path.empty() ) { #ifdef MIP_USE_EXTRAS - example_utils->recordedFile = std::unique_ptr(new std::ofstream(binary_file_path)); + example_utils->recordedFile = std::make_unique(binary_file_path); if( !example_utils->recordedFile->is_open() ) throw std::runtime_error("Unable to open binary file"); #else // MIP_USE_EXTRAS @@ -71,14 +71,14 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, throw std::runtime_error("Invalid TCP port (must be between 1024 and 65535."); #ifdef MIP_USE_EXTRAS - using RecordingTcpConnection = mip::extras::RecordingConnectionWrapper; - example_utils->connection = std::unique_ptr(new RecordingTcpConnection(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, port)); + using RecordingTcpConnection = microstrain::connections::RecordingConnectionWrapper; + example_utils->connection = std::make_unique(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, port); #else // MIP_USE_EXTRAS - using TcpConnection = mip::platform::TcpConnection; - example_utils->connection = std::unique_ptr(new TcpConnection(port_or_hostname, port)); + using TcpConnection = microstrain::connections::TcpConnection; + example_utils->connection = std::make_unique(port_or_hostname, port); #endif // MIP_USE_EXTRAS - example_utils->device = std::unique_ptr(new mip::DeviceInterface(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), 1000, 2000)); + example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), 1000, 2000); #else // MIP_USE_TCP throw std::runtime_error("This program was compiled without socket support. Recompile with -DMIP_USE_TCP=1"); #endif // MIP_USE_TCP @@ -93,14 +93,14 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, throw std::runtime_error("Serial baud rate must be a decimal integer greater than 0."); #ifdef MIP_USE_EXTRAS - using RecordingSerialConnection = mip::extras::RecordingConnectionWrapper; - example_utils->connection = std::unique_ptr(new RecordingSerialConnection(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, baud)); + using RecordingSerialConnection = microstrain::connections::RecordingConnectionWrapper; + example_utils->connection = std::make_unique(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, baud); #else // MIP_USE_EXTRAS - using SerialConnection = mip::platform::SerialConnection; - example_utils->connection = std::unique_ptr(new SerialConnection(port_or_hostname, baud)); + using SerialConnection = microstrain::connections::SerialConnection; + example_utils->connection = std::make_unique(port_or_hostname, baud); #endif // MIP_USE_EXTRAS - example_utils->device = std::unique_ptr(new mip::DeviceInterface(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), mip::C::mip_timeout_from_baudrate(baud), 500)); + example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), mip::C::mip_timeout_from_baudrate(baud), 500); #else // MIP_USE_SERIAL throw std::runtime_error("This program was compiled without serial support. Recompile with -DMIP_USE_SERIAL=1.\n"); #endif //MIP_USE_SERIAL diff --git a/examples/example_utils.hpp b/examples/example_utils.hpp index 04afbafa6..b20daf939 100644 --- a/examples/example_utils.hpp +++ b/examples/example_utils.hpp @@ -8,7 +8,7 @@ #include "microstrain/connections/tcp/tcp_connection.hpp" #endif #ifdef MIP_USE_EXTRAS - #include "mip/extras/recording_connection.hpp" + #include "microstrain/connections/recording/recording_connection.hpp" #endif @@ -22,7 +22,7 @@ struct ExampleUtils { - std::unique_ptr connection; + std::unique_ptr connection; std::unique_ptr device; std::unique_ptr recordedFile; uint8_t buffer[1024]; diff --git a/examples/threading.cpp b/examples/threading.cpp index 33eeb93af..bb294796a 100644 --- a/examples/threading.cpp +++ b/examples/threading.cpp @@ -43,7 +43,7 @@ unsigned int display_progress() void packet_callback(void*, const mip::PacketRef& packet, mip::Timestamp timestamp) { - numSamples++; + numSamples = numSamples + 1; } void device_thread_loop(mip::DeviceInterface* device) diff --git a/src/microstrain/common/CMakeLists.txt b/src/microstrain/common/CMakeLists.txt index d8ebbd658..7ed56b782 100644 --- a/src/microstrain/common/CMakeLists.txt +++ b/src/microstrain/common/CMakeLists.txt @@ -20,7 +20,8 @@ if(MIP_ENABLE_LOGGING) message(FATAL_ERROR "MIP_LOGGING_MAX_LEVEL must be MIP_LOG_LEVEL_* or a number") endif() target_sources(microstrain_common PRIVATE "mip_logging.c") + message("Logging enabled. Max level = ${MIP_LOGGING_MAX_LEVEL}") target_compile_definitions(microstrain_common PUBLIC "MIP_ENABLE_LOGGING" "MIP_LOGGING_MAX_LEVEL=${MIP_LOGGING_MAX_LEVEL}") endif() -target_include_directories(microstrain_common PRIVATE ${SRC_DIR}) +target_include_directories(microstrain_common PUBLIC ${SRC_DIR}) diff --git a/src/microstrain/common/microstrain_time.h b/src/microstrain/common/microstrain_time.h new file mode 100644 index 000000000..766e9df45 --- /dev/null +++ b/src/microstrain/common/microstrain_time.h @@ -0,0 +1,46 @@ + +#include "platform.h" + +#include + + + +#ifdef __cplusplus +namespace microstrain { +namespace C { +#endif + +///@brief Type used for packet timestamps and timeouts. +/// +/// Timestamps must be monotonic except for overflow at the maximum value back to 0. +/// The units can be anything, but typically are milliseconds. Choose a long enough +/// unit so that consecutive calls to the parser will not exceed half of the maximum +/// value for this type. For milliseconds, the time to overflow is approximately 50 +/// days, so the parser should be invoked at least every 25 days. Failure to observe +/// this requirement may result in false timeouts or delays in getting parsed packets. +/// +#ifdef MICROSTRAIN_TIMESTAMP_TYPE +typedef MICROSTRAIN_TIMESTAMP_TYPE microstrain_timestamp; +static_assert( sizeof(microstrain_timestamp) >= 8 || microstrain_timestamp(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); + +#elif defined(MICROSTRAIN_PLATFORM_DESKTOP) +// By default, on desktop we use 64-bit timestamps. +typedef uint64_t microstrain_timestamp; +#else +// If the platform isn't known, assume u32 timestamps. +typedef uint32_t microstrain_timestamp; +#endif + +// Timeouts are just an alias for timestamps +typedef microstrain_timestamp microstrain_timeout; + + +#ifdef __cplusplus + +} // namespace C + +using Timestamp = C::microstrain_timestamp; +using Timeout = C::microstrain_timeout; + +} // namespace microstrain +#endif // __cplusplus diff --git a/src/microstrain/common/mip_logging.h b/src/microstrain/common/mip_logging.h index dba5f0288..e8d7c39aa 100644 --- a/src/microstrain/common/mip_logging.h +++ b/src/microstrain/common/mip_logging.h @@ -74,14 +74,8 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); #define MIP_LOG_LOG(level, ...) (void)0 #endif -#define XSTR(x) STR(x) -#define STR(x) #x - #ifndef MIP_LOGGING_MAX_LEVEL #define MIP_LOGGING_MAX_LEVEL MIP_LOG_LEVEL_WARN -#pragma message "NOT DEFINED" -#else -#pragma message "The value of ABC: " XSTR(MIP_LOGGING_MAX_LEVEL) #endif //////////////////////////////////////////////////////////////////////////////// diff --git a/src/microstrain/common/platform.h b/src/microstrain/common/platform.h index 243e2dbdb..e3527ec26 100644 --- a/src/microstrain/common/platform.h +++ b/src/microstrain/common/platform.h @@ -2,47 +2,15 @@ #if defined _WIN32 #define MICROSTRAIN_PLATFORM_WINDOWS +#define MICROSTRAIN_PLATFORM_DESKTOP #elif defined __APPLE__ #define MICROSTRAIN_PLATFORM_APPLE +#define MICROSTRAIN_PLATFORM_DESKTOP #elif defined __linux__ #define MICROSTRAIN_PLATFORM_LINUX +#define MICROSTRAIN_PLATFORM_DESKTOP #else #define MICROSTRAIN_PLATFORM_OTHER #endif -#include - - -//#ifdef __cplusplus -//namespace microstrain { -//#endif -// -/////@brief Type used for packet timestamps and timeouts. -///// -///// Timestamps must be monotonic except for overflow at the maximum value back to 0. -///// The units can be anything, but typically are milliseconds. Choose a long enough -///// unit so that consecutive calls to the parser will not exceed half of the maximum -///// value for this type. For milliseconds, the time to overflow is approximately 50 -///// days, so the parser should be invoked at least every 25 days. Failure to observe -///// this requirement may result in false timeouts or delays in getting parsed packets. -///// -//#ifdef MICROSTRAIN_TIMESTAMP_TYPE -//typedef MICROSTRAIN_TIMESTAMP_TYPE microstrain_timestamp; -// static_assert( sizeof(microstrain_timestamp) >= 8 || microstrain_timestamp(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); -//#else -//typedef uint64_t microstrain_timestamp; -//#endif -// -//typedef microstrain_timestamp microstrain_timeout; -// -// -//#ifdef __cplusplus -// -//} // extern "C" -//} // namespace C -// -//using Timestamp = C::mip_timestamp; -//using Timeout = C::mip_timeout; -// -//} // namespace microstrain diff --git a/src/microstrain/connections/CMakeLists.txt b/src/microstrain/connections/CMakeLists.txt index 73ebed9ea..2370ed165 100644 --- a/src/microstrain/connections/CMakeLists.txt +++ b/src/microstrain/connections/CMakeLists.txt @@ -11,4 +11,7 @@ if(MIP_USE_TCP) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/tcp) endif() - +# Don't include recording connection if no connections are enabled. +if(MIP_USE_SERIAL OR MIP_USE_TCP) + add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/recording) +endif() diff --git a/src/microstrain/connections/connection.hpp b/src/microstrain/connections/connection.hpp index 04d178af2..e68268a0b 100644 --- a/src/microstrain/connections/connection.hpp +++ b/src/microstrain/connections/connection.hpp @@ -1,6 +1,6 @@ #pragma once -#include "microstrain/common/platform.h" +#include "microstrain/common/microstrain_time.h" #include #include @@ -31,7 +31,7 @@ class Connection virtual ~Connection() {} virtual bool sendToDevice(const uint8_t* data, size_t length) = 0; - virtual bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out) = 0; + virtual bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, Timestamp* timestamp_out) = 0; #if __cpp_lib_span >= 202002L bool sendToDevice(std::span data) { return sendToDevice(data.data(), data.size()); } diff --git a/src/microstrain/connections/recording/CMakeLists.txt b/src/microstrain/connections/recording/CMakeLists.txt new file mode 100644 index 000000000..4ca575742 --- /dev/null +++ b/src/microstrain/connections/recording/CMakeLists.txt @@ -0,0 +1,13 @@ + + +set(SOURCES + recording_connection.cpp + recording_connection.hpp + ../connection.hpp +) + +add_library(microstrain_recording_connection ${SOURCES}) + +target_link_libraries(microstrain_recording_connection PUBLIC microstrain_common) + +#target_include_directories(microstrain_serial PRIVATE ${SRC_DIR}) diff --git a/src/microstrain/extras/recording_connection.cpp b/src/microstrain/connections/recording/recording_connection.cpp similarity index 72% rename from src/microstrain/extras/recording_connection.cpp rename to src/microstrain/connections/recording/recording_connection.cpp index b9a3e7d7a..ab5af689c 100644 --- a/src/microstrain/extras/recording_connection.cpp +++ b/src/microstrain/connections/recording/recording_connection.cpp @@ -1,8 +1,10 @@ + #include "recording_connection.hpp" -namespace mip + +namespace microstrain { -namespace extras +namespace connections { ///@brief Creates a RecordingConnection that will write received bytes to recvStream, and sent bytes to sendStream @@ -20,10 +22,10 @@ RecordingConnection::RecordingConnection(Connection* connection, std::ostream* r bool RecordingConnection::sendToDevice(const uint8_t* data, size_t length) { const bool ok = mConnection->sendToDevice(data, length); - if( ok && mSendFile != nullptr && mConnection->isConnected()) - { - mSendFile->write(reinterpret_cast(data), length); + if( ok && mSendFile != nullptr) + { + mSendFile->write(reinterpret_cast(data), length); mSendFileWritten += length; } @@ -31,18 +33,18 @@ bool RecordingConnection::sendToDevice(const uint8_t* data, size_t length) } ///@copydoc mip::Connection::recvFromDevice -bool RecordingConnection::recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* count_out, Timestamp* timestamp_out) +bool RecordingConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* count_out, Timestamp* timestamp_out) { - const bool ok = mConnection->recvFromDevice(buffer, max_length, wait_time, count_out, timestamp_out); - if (ok && mRecvFile != nullptr && mConnection->isConnected()) - { - mRecvFile->write(reinterpret_cast(buffer), *count_out); + const bool ok = mConnection->recvFromDevice(buffer, max_length, wait_time_ms, count_out, timestamp_out); + if (ok && mRecvFile != nullptr) + { + mRecvFile->write(reinterpret_cast(buffer), *count_out); mRecvFileWritten += *count_out; } return ok; } -} // namespace extras -} // namespace mip \ No newline at end of file +} // namespace connections +} // namespace microstrain diff --git a/src/microstrain/extras/recording_connection.hpp b/src/microstrain/connections/recording/recording_connection.hpp similarity index 82% rename from src/microstrain/extras/recording_connection.hpp rename to src/microstrain/connections/recording/recording_connection.hpp index 71af6743b..ea4cf79d4 100644 --- a/src/microstrain/extras/recording_connection.hpp +++ b/src/microstrain/connections/recording/recording_connection.hpp @@ -1,14 +1,14 @@ #pragma once -#include "mip/mip_device.hpp" +#include #include #include #include -namespace mip +namespace microstrain { -namespace extras +namespace connections { //////////////////////////////////////////////////////////////////////////////// @@ -24,11 +24,12 @@ class RecordingConnection : public Connection static constexpr auto TYPE = "Recording"; RecordingConnection(Connection *connection, std::ostream *recvStream = nullptr, std::ostream *sendStream = nullptr); + ~RecordingConnection() = default; - bool sendToDevice(const uint8_t* data, size_t length) final; - bool recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, Timestamp* timestamp_out) final; + bool sendToDevice(const uint8_t* data, size_t length) override; + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, Timestamp* timestamp_out) override; - bool isConnected() const + bool isConnected() const override { if(mConnection) return mConnection->isConnected(); @@ -36,13 +37,13 @@ class RecordingConnection : public Connection return false; }; - bool connect() + bool connect() override { if (mConnection) return mConnection->connect(); return false; }; - bool disconnect() + bool disconnect() override { if (mConnection) return mConnection->disconnect(); @@ -52,12 +53,12 @@ class RecordingConnection : public Connection const char* interfaceName() const override { return mConnection->interfaceName(); } uint32_t parameter() const override { return mConnection->parameter(); } - uint64_t recvFileBytesWritten() + uint64_t recvFileBytesWritten() const { return mRecvFileWritten; } - uint64_t sendFileBytesWritten() + uint64_t sendFileBytesWritten() const { return mSendFileWritten; } @@ -97,5 +98,5 @@ class RecordingConnectionWrapper : public RecordingConnection ///@} //////////////////////////////////////////////////////////////////////////////// -} // namespace extras -} // namespace mip +} // namespace connections +} // namespace microstrain diff --git a/src/microstrain/connections/serial/CMakeLists.txt b/src/microstrain/connections/serial/CMakeLists.txt index 0f7c3f6bd..18a8e6c78 100644 --- a/src/microstrain/connections/serial/CMakeLists.txt +++ b/src/microstrain/connections/serial/CMakeLists.txt @@ -12,4 +12,4 @@ add_library(microstrain_serial ${SOURCES}) target_link_libraries(microstrain_serial PUBLIC microstrain_common) -target_include_directories(microstrain_serial PRIVATE ${SRC_DIR}) +#target_include_directories(microstrain_serial PRIVATE ${SRC_DIR}) diff --git a/src/microstrain/connections/serial/serial_connection.cpp b/src/microstrain/connections/serial/serial_connection.cpp index 7b9380b66..b4c769d6d 100644 --- a/src/microstrain/connections/serial/serial_connection.cpp +++ b/src/microstrain/connections/serial/serial_connection.cpp @@ -4,12 +4,12 @@ #include #include -namespace mip +namespace microstrain { -namespace platform +namespace connections { -///@brief Creates a SerialConnection that will communicate with a device over serial +///@brief Creates a Serial Connection that will communicate with a device over serial /// ///@param portName Path to the port to connect to. On Windows, this usually looks like "COM", on linux, "/dev/tty" ///@param baudrate Baud rate to open the device at. Note that the device needs to be configured to @@ -55,7 +55,7 @@ bool SerialConnection::disconnect() ///@copydoc mip::Connection::recvFromDevice -bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, mip::Timestamp* timestamp) +bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, mip::Timestamp* timestamp) { *timestamp = std::chrono::duration_cast(std::chrono::steady_clock::now().time_since_epoch()).count(); @@ -69,5 +69,5 @@ bool SerialConnection::sendToDevice(const uint8_t* data, size_t length) return serial_port_write(&mPort, data, length, &length_out); } -} // namespace platform -} // namespace mip +} // namespace connections +} // namespace microstrain diff --git a/src/microstrain/connections/serial/serial_connection.hpp b/src/microstrain/connections/serial/serial_connection.hpp index 1ad819527..0734e11f1 100644 --- a/src/microstrain/connections/serial/serial_connection.hpp +++ b/src/microstrain/connections/serial/serial_connection.hpp @@ -18,16 +18,16 @@ namespace connections //////////////////////////////////////////////////////////////////////////////// ///@brief Can be used on Windows, OSX, or linux to communicate with a MIP device over serial /// -class Serial : public microstrain::Connection +class SerialConnection : public microstrain::Connection { public: static constexpr auto TYPE = "Serial"; - Connection(std::string portName, uint32_t baudrate); - ~Connection(); + SerialConnection(std::string portName, uint32_t baudrate); + ~SerialConnection(); - bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out) final; + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, Timestamp* timestamp_out) final; bool sendToDevice(const uint8_t* data, size_t length) final; bool isConnected() const override; @@ -64,5 +64,5 @@ class UsbSerialConnection : public SerialConnection ///@} //////////////////////////////////////////////////////////////////////////////// -} // namespace platform -} // namespace mip \ No newline at end of file +} // namespace connections +} // namespace microstrain \ No newline at end of file diff --git a/src/microstrain/connections/tcp/CMakeLists.txt b/src/microstrain/connections/tcp/CMakeLists.txt index 66f5285fa..4f90572ee 100644 --- a/src/microstrain/connections/tcp/CMakeLists.txt +++ b/src/microstrain/connections/tcp/CMakeLists.txt @@ -16,4 +16,4 @@ if(WIN32) target_link_libraries(microstrain_socket PUBLIC "ws2_32") endif() -target_include_directories(microstrain_socket PRIVATE ${SRC_DIR}) +#target_include_directories(microstrain_socket PRIVATE ${SRC_DIR}) diff --git a/src/microstrain/connections/tcp/tcp_connection.cpp b/src/microstrain/connections/tcp/tcp_connection.cpp index 8131a465c..b1a71610c 100644 --- a/src/microstrain/connections/tcp/tcp_connection.cpp +++ b/src/microstrain/connections/tcp/tcp_connection.cpp @@ -5,9 +5,9 @@ #include #include -namespace mip +namespace microstrain { -namespace platform +namespace connections { ///@brief Creates a TcpConnection that will communicate with a device over TCP @@ -56,11 +56,11 @@ bool TcpConnection::disconnect() } ///@copydoc mip::Connection::sendToDevice -bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, mip::Timestamp* timestamp) +bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, Timestamp* timestamp_out) { - (void)wait_time; // Not used, timeout is always fixed + (void)wait_time_ms; // Not used, timeout is always fixed - *timestamp = std::chrono::duration_cast(std::chrono::steady_clock::now().time_since_epoch()).count(); + *timestamp_out = std::chrono::duration_cast(std::chrono::steady_clock::now().time_since_epoch()).count(); return tcp_socket_recv(&mSocket, buffer, max_length, length_out); } @@ -72,5 +72,5 @@ bool TcpConnection::sendToDevice(const uint8_t* data, size_t length) return tcp_socket_send(&mSocket, data, length, &length_out); } -} // namespace platform -} // namespace mip \ No newline at end of file +} // namespace connections +} // namespace microstrain \ No newline at end of file diff --git a/src/microstrain/connections/tcp/tcp_connection.hpp b/src/microstrain/connections/tcp/tcp_connection.hpp index 4692e51cb..9043ca281 100644 --- a/src/microstrain/connections/tcp/tcp_connection.hpp +++ b/src/microstrain/connections/tcp/tcp_connection.hpp @@ -1,14 +1,14 @@ #pragma once -#include "mip/mip_device.hpp" +#include #include "tcp_socket.h" #include -namespace mip +namespace microstrain { -namespace platform +namespace connections { //////////////////////////////////////////////////////////////////////////////// @@ -18,21 +18,23 @@ namespace platform //////////////////////////////////////////////////////////////////////////////// ///@brief Can be used on Windows, OSX, or linux to communicate with a MIP device over TCP /// -class TcpConnection : public mip::Connection +class TcpConnection : public microstrain::Connection { public: static constexpr auto TYPE = "TCP"; - TcpConnection() = default; TcpConnection(const std::string& hostname, uint16_t port); ~TcpConnection(); - bool recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, mip::Timestamp* timestamp) final; + TcpConnection(const TcpConnection&) = delete; + TcpConnection& operator=(const TcpConnection&) = delete; + + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, Timestamp* timestamp_out) final; bool sendToDevice(const uint8_t* data, size_t length) final; - bool isConnected() const; - bool connect(); - bool disconnect(); + bool isConnected() const final; + bool connect() final; + bool disconnect() final; void connectionInfo(std::string &host_name, uint32_t &port) const { @@ -53,5 +55,5 @@ class TcpConnection : public mip::Connection ///@} //////////////////////////////////////////////////////////////////////////////// -}; // namespace platform -}; // namespace mip \ No newline at end of file +}; // namespace microstrain +}; // namespace connections \ No newline at end of file diff --git a/src/mip/CMakeLists.txt b/src/mip/CMakeLists.txt index 5ec9e15be..fcfe5fb7b 100644 --- a/src/mip/CMakeLists.txt +++ b/src/mip/CMakeLists.txt @@ -115,3 +115,5 @@ endif() target_compile_definitions(mip PUBLIC "${MIP_DEFINES}") target_link_libraries(mip PUBLIC microstrain_common) + +#target_include_directories(mip INTERFACE ${CMAKE_CURRENT_LIST_DIR}) diff --git a/src/mip/mip_device.cpp b/src/mip/mip_device.cpp index 88db73a27..7e83d6a86 100644 --- a/src/mip/mip_device.cpp +++ b/src/mip/mip_device.cpp @@ -1,6 +1,9 @@ #include "mip_device.hpp" +#include "../microstrain/connections/connection.hpp" + + namespace mip { //////////////////////////////////////////////////////////////////////////////// @@ -23,29 +26,30 @@ namespace mip { ///@param timestamp Timestamp of when the data was received //////////////////////////////////////////////////////////////////////////////// +//////////////////////////////////////////////////////////////////////////////// +///@brief Sets up the mip interface callbacks to point at this object. +/// +///@note This sets the interface's user pointer to this connection object. +/// +///@param device Device to configure. +/// +void connect_interface(mip::DeviceInterface& device, microstrain::Connection& conn) +{ + using microstrain::Connection; + + auto send = [](C::mip_interface* device, const uint8_t* data, size_t length)->bool + { + return static_cast(C::mip_interface_user_pointer(device))->sendToDevice(data, length); + }; + auto recv = [](C::mip_interface* device, uint8_t* buffer, size_t max_length, C::mip_timeout wait_time, size_t* length_out, C::mip_timestamp* timestamp_out)->bool + { + return static_cast(C::mip_interface_user_pointer(device))->recvFromDevice(buffer, max_length, wait_time, length_out, timestamp_out); + }; + + C::mip_interface_set_user_pointer(&device, &conn); -////////////////////////////////////////////////////////////////////////////////// -/////@brief Sets up the mip interface callbacks to point at this object. -///// -/////@note This sets the interface's user pointer to this connection object. -///// -/////@param device Device to configure. -///// -//void Connection::connect_interface(C::mip_interface* device) -//{ -// auto send = [](C::mip_interface* device, const uint8_t* data, size_t length)->bool -// { -// return static_cast(C::mip_interface_user_pointer(device))->sendToDevice(data, length); -// }; -// auto recv = [](C::mip_interface* device, uint8_t* buffer, size_t max_length, C::mip_timeout wait_time, size_t* length_out, C::mip_timestamp* timestamp_out)->bool -// { -// return static_cast(C::mip_interface_user_pointer(device))->recvFromDevice(buffer, max_length, wait_time, length_out, timestamp_out); -// }; -// -// C::mip_interface_set_user_pointer(device, this); -// -// C::mip_interface_set_send_function(device, send); -// C::mip_interface_set_recv_function(device, recv); -//} + C::mip_interface_set_send_function(&device, send); + C::mip_interface_set_recv_function(&device, recv); +} } // namespace mip diff --git a/src/mip/mip_device.hpp b/src/mip/mip_device.hpp index ee201226e..e0d4496a4 100644 --- a/src/mip/mip_device.hpp +++ b/src/mip/mip_device.hpp @@ -7,9 +7,21 @@ #include +namespace microstrain +{ + class Connection; +} + namespace mip { +class DeviceInterface; + +void connect_interface(mip::DeviceInterface& dev, microstrain::Connection& conn); + + + + //////////////////////////////////////////////////////////////////////////////// ///@addtogroup mip_cpp ///@{ @@ -150,14 +162,14 @@ class DeviceInterface : public C::mip_interface C::mip_interface_init(this, parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout, nullptr, nullptr, &C::mip_interface_default_update, nullptr); } - /////@copydoc mip::C::mip_interface_init - /////@param connection The connection object used to communicate with the device. This object must exist for the life of the DeviceInterface object - //DeviceInterface(Connection* connection, uint8_t* parseBuffer, size_t parseBufferSize, Timeout parseTimeout, Timeout baseReplyTimeout) : - // DeviceInterface(parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout) - //{ - // if(connection) - // connection->connect_interface(this); - //} + ///@copydoc mip::C::mip_interface_init + ///@param connection The connection object used to communicate with the device. This object must exist for the life of the DeviceInterface object + DeviceInterface(microstrain::Connection* connection, uint8_t* parseBuffer, size_t parseBufferSize, Timeout parseTimeout, Timeout baseReplyTimeout) : + DeviceInterface(parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout) + { + if(connection) + connect_interface(*this, *connection); + } DeviceInterface(const DeviceInterface&) = delete; DeviceInterface& operator=(const DeviceInterface&) = delete; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 011136407..0029dd828 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -23,9 +23,9 @@ add_mip_test(TestMipFields "${TEST_DIR}/mip/test_mip_fields.c" TestMipFi add_mip_test(TestMipCpp "${TEST_DIR}/mip/test_mip.cpp" TestMipCpp) add_mip_test(TestMipPerf "${TEST_DIR}/mip/mip_parser_performance.cpp" TestMipPerf) -if(MIP_USE_SERIAL) - add_executable(TestSerial "${TEST_DIR}/test_serial.cpp") - target_include_directories(TestSerial PUBLIC "${SRC_DIR}") - target_link_libraries(TestSerial PUBLIC "serial") - add_test(TestSerial TestSerial) -endif() +#if(MIP_USE_SERIAL) +# add_executable(TestSerial "${TEST_DIR}/test_serial.cpp") +# target_include_directories(TestSerial PUBLIC "${SRC_DIR}") +# target_link_libraries(TestSerial PUBLIC "serial") +# add_test(TestSerial TestSerial) +#endif() diff --git a/test/test_serial.cpp b/test/test_serial.cpp index 18e2d890b..ea806ec1e 100644 --- a/test/test_serial.cpp +++ b/test/test_serial.cpp @@ -3,6 +3,7 @@ #include #include +#include int main(int argc, const char* argv[]) @@ -12,7 +13,7 @@ int main(int argc, const char* argv[]) if( argc == 1 ) { printf("Available serial ports:\n"); - std::vector ports = serial::list_ports(); + std::vector ports = serial::list_ports(); for(const serial::PortInfo& port : ports) { From e7bbe4389c067d05f591ae988a0fc41831132be8 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 8 May 2024 10:43:55 -0400 Subject: [PATCH 003/147] Fix a few compilation errors on Windows. --- CMakeLists.txt | 2 +- examples/CMakeLists.txt | 2 +- src/microstrain/connections/connection.hpp | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b579fa91b..068993802 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -110,7 +110,7 @@ endif() # Disable windows defined min/max # Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) if(WIN32) - compile_definitions("NOMINMAX=1" "_WIN32_WINNT=0x0501") + add_compile_definitions("NOMINMAX=1" "_WIN32_WINNT=0x0501") endif() if(MSVC) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 5eee7b56f..3962f2a36 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -35,7 +35,7 @@ macro(add_mip_example name sources) target_link_libraries(${name} mip ${EXAMPLE_LIBS}) target_compile_definitions(${name} PUBLIC ${MIP_EXAMPLE_DEFS}) - target_include_directories(${name} PRIVATE ${SRC_DIR}) + #target_include_directories(${name} PRIVATE ${SRC_DIR}) endmacro() diff --git a/src/microstrain/connections/connection.hpp b/src/microstrain/connections/connection.hpp index e68268a0b..7687e6fa1 100644 --- a/src/microstrain/connections/connection.hpp +++ b/src/microstrain/connections/connection.hpp @@ -35,9 +35,9 @@ class Connection #if __cpp_lib_span >= 202002L bool sendToDevice(std::span data) { return sendToDevice(data.data(), data.size()); } - bool recvFromDevice(std::span& buffer, unsigned int wait_time_ms) { + bool recvFromDevice(std::span& buffer, unsigned int wait_time_ms, Timestamp* timestamp_out) { size_t length = 0; - if(!recvFromDevice(buffer.data(), buffer.size(), wait_time_ms, &length)) + if(!recvFromDevice(buffer.data(), buffer.size(), wait_time_ms, &length, timestamp_out)) return false; buffer = buffer.first(length); return true; From 55754b1e2456450e5fb86ac5a5028d99d8f264af Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 8 May 2024 16:37:24 -0400 Subject: [PATCH 004/147] Rename logging from mip to microstrain. --- examples/example_utils.cpp | 10 ++-- examples/watch_imu.c | 12 ++-- src/microstrain/common/CMakeLists.txt | 14 ++--- .../common/{mip_logging.c => logging.c} | 38 ++++++------ .../common/{mip_logging.h => logging.h} | 58 +++++++++---------- .../connections/serial/serial_port.c | 2 +- src/microstrain/connections/tcp/tcp_socket.c | 2 +- 7 files changed, 68 insertions(+), 68 deletions(-) rename src/microstrain/common/{mip_logging.c => logging.c} (64%) rename src/microstrain/common/{mip_logging.h => logging.h} (63%) diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index ad683ee22..064d045d1 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -3,7 +3,7 @@ #include -#include "microstrain/common/mip_logging.h" +#include "microstrain/common/logging.h" #include "example_utils.hpp" @@ -20,7 +20,7 @@ mip::Timestamp getCurrentTimestamp() return duration_cast( steady_clock::now().time_since_epoch() ).count(); } -void customLog(void* user, mip_log_level level, const char* fmt, va_list args) +void customLog(void* user, microstrain_log_level level, const char* fmt, va_list args) { // Convert the varargs into a string std::string log; @@ -37,8 +37,8 @@ void customLog(void* user, mip_log_level level, const char* fmt, va_list args) // Print to the proper stream switch (level) { - case MIP_LOG_LEVEL_FATAL: - case MIP_LOG_LEVEL_ERROR: + case MICROSTRAIN_LOG_LEVEL_FATAL: + case MICROSTRAIN_LOG_LEVEL_ERROR: std::cerr << log; break; default: @@ -115,7 +115,7 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, std::unique_ptr handleCommonArgs(int argc, const char* argv[], int maxArgs) { // Setup the logger for the MIP SDK - MIP_LOG_INIT(&customLog, MIP_LOG_LEVEL_DEBUG, nullptr); + MIP_LOG_INIT(&customLog, MICROSTRAIN_LOG_LEVEL_DEBUG, nullptr); if( argc < 3 || argc > maxArgs ) { diff --git a/examples/watch_imu.c b/examples/watch_imu.c index 7cc5fb3cd..ddc7cbb5f 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -4,7 +4,7 @@ #include #include #include -#include "microstrain/common/mip_logging.h" +#include "microstrain/common/logging.h" #include #include @@ -14,7 +14,7 @@ #include "microstrain/connections/serial/serial_port.h" -#include "microstrain/common/mip_logging.h" +#include "microstrain/common/logging.h" #include #include @@ -36,12 +36,12 @@ uint8_t parse_buffer[1024]; mip_interface device; mip_sensor_scaled_accel_data scaled_accel; -void customLog(void* user, mip_log_level level, const char* fmt, va_list args) +void customLog(void* user, microstrain_log_level level, const char* fmt, va_list args) { switch (level) { - case MIP_LOG_LEVEL_FATAL: - case MIP_LOG_LEVEL_ERROR: + case MICROSTRAIN_LOG_LEVEL_FATAL: + case MICROSTRAIN_LOG_LEVEL_ERROR: vfprintf(stderr, fmt, args); break; default: @@ -159,7 +159,7 @@ int main(int argc, const char* argv[]) return usage(argv[0]); // Initialize the MIP logger before opening the port so we can print errors if they occur - MIP_LOG_INIT(&customLog, MIP_LOG_LEVEL_INFO, NULL); + MIP_LOG_INIT(&customLog, MICROSTRAIN_LOG_LEVEL_INFO, NULL); if( !open_port(argv[1], baudrate) ) return 1; diff --git a/src/microstrain/common/CMakeLists.txt b/src/microstrain/common/CMakeLists.txt index 7ed56b782..df1776614 100644 --- a/src/microstrain/common/CMakeLists.txt +++ b/src/microstrain/common/CMakeLists.txt @@ -1,13 +1,13 @@ option(MIP_ENABLE_LOGGING "Build with logging functions enabled" ON) -set(MIP_LOGGING_MAX_LEVEL "MIP_LOG_LEVEL_WARN" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") +set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any call to logging functions with a higher level than this will be compiled out.") set(SOURCES platform.h descriptor_id.hpp index.hpp - mip_logging.h + logging.h ) @@ -16,12 +16,12 @@ add_library(microstrain_common ${SOURCES}) # Logging is a little weird since we need to install the header no matter what if(MIP_ENABLE_LOGGING) - if(MIP_LOGGING_LEVEL_MAX STREQUAL "") - message(FATAL_ERROR "MIP_LOGGING_MAX_LEVEL must be MIP_LOG_LEVEL_* or a number") + if(MICROSTRAIN_LOGGING_MAX_LEVEL STREQUAL "") + message(ERROR "MICROSTRAIN_LOGGING_MAX_LEVEL must be MIP_LOG_LEVEL_* or a number") endif() - target_sources(microstrain_common PRIVATE "mip_logging.c") - message("Logging enabled. Max level = ${MIP_LOGGING_MAX_LEVEL}") - target_compile_definitions(microstrain_common PUBLIC "MIP_ENABLE_LOGGING" "MIP_LOGGING_MAX_LEVEL=${MIP_LOGGING_MAX_LEVEL}") + target_sources(microstrain_common PRIVATE "logging.c") + message("MicroStrain logging is enabled. Max level = '${MICROSTRAIN_LOGGING_MAX_LEVEL}'") + target_compile_definitions(microstrain_common PUBLIC "MIP_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") endif() target_include_directories(microstrain_common PUBLIC ${SRC_DIR}) diff --git a/src/microstrain/common/mip_logging.c b/src/microstrain/common/logging.c similarity index 64% rename from src/microstrain/common/mip_logging.c rename to src/microstrain/common/logging.c index 23592293a..ac709b0fe 100644 --- a/src/microstrain/common/mip_logging.c +++ b/src/microstrain/common/logging.c @@ -1,19 +1,19 @@ -#include "mip_logging.h" +#include "logging.h" #include //////////////////////////////////////////////////////////////////////////////// ///@brief Global logging callback. Do not access directly -mip_log_callback mip_log_callback_ = NULL; +microstrain_log_callback microstrain_log_callback_ = NULL; //////////////////////////////////////////////////////////////////////////////// ///@brief Global logging level. Do not access directly -mip_log_level mip_log_level_ = MIP_LOG_LEVEL_OFF; +microstrain_log_level microstrain_log_level_ = MICROSTRAIN_LOG_LEVEL_OFF; //////////////////////////////////////////////////////////////////////////////// ///@brief Global logging user data. Do not access directly -void* mip_log_user_data_ = NULL; +void* microstrain_log_user_data_ = NULL; //////////////////////////////////////////////////////////////////////////////// ///@brief Initializes the logger with a callback and user data. @@ -24,11 +24,11 @@ void* mip_log_user_data_ = NULL; ///@param level The level that the MIP SDK should log at ///@param user User data that will be passed to the callback every time it is excuted /// -void mip_logging_init(mip_log_callback callback, mip_log_level level, void* user) +void microstrain_logging_init(microstrain_log_callback callback, microstrain_log_level level, void* user) { - mip_log_callback_ = callback; - mip_log_level_ = level; - mip_log_user_data_ = user; + microstrain_log_callback_ = callback; + microstrain_log_level_ = level; + microstrain_log_user_data_ = user; } //////////////////////////////////////////////////////////////////////////////// @@ -36,9 +36,9 @@ void mip_logging_init(mip_log_callback callback, mip_log_level level, void* user /// ///@return The currently active logging callback /// -mip_log_callback mip_logging_callback() +microstrain_log_callback microstrain_logging_callback() { - return mip_log_callback_; + return microstrain_log_callback_; } //////////////////////////////////////////////////////////////////////////////// @@ -46,9 +46,9 @@ mip_log_callback mip_logging_callback() /// ///@return The currently active logging level /// -mip_log_level mip_logging_level() +microstrain_log_level microstrain_logging_level() { - return mip_log_level_; + return microstrain_log_level_; } //////////////////////////////////////////////////////////////////////////////// @@ -56,25 +56,25 @@ mip_log_level mip_logging_level() /// ///@return The currently active logging user data /// -void* mip_logging_user_data() +void* microstrain_logging_user_data() { - return mip_log_user_data_; + return microstrain_log_user_data_; } //////////////////////////////////////////////////////////////////////////////// ///@brief Internal log function called by logging macros. /// Call MIP_LOG_* macros instead of using this function directly -///@copydetails mip::C::mip_log_callback +///@copydetails mip::C::microstrain_log_callback /// -void mip_logging_log(mip_log_level level, const char* fmt, ...) +void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...) { - const mip_log_callback logging_callback = mip_logging_callback(); - const mip_log_level logging_level = mip_logging_level(); + const microstrain_log_callback logging_callback = microstrain_logging_callback(); + const microstrain_log_level logging_level = microstrain_logging_level(); if (logging_callback != NULL && logging_level >= level) { va_list args; va_start(args, fmt); - logging_callback(mip_logging_user_data(), level, fmt, args); + logging_callback(microstrain_logging_user_data(), level, fmt, args); va_end(args); } } \ No newline at end of file diff --git a/src/microstrain/common/mip_logging.h b/src/microstrain/common/logging.h similarity index 63% rename from src/microstrain/common/mip_logging.h rename to src/microstrain/common/logging.h index e8d7c39aa..bcc05b85e 100644 --- a/src/microstrain/common/mip_logging.h +++ b/src/microstrain/common/logging.h @@ -11,11 +11,11 @@ extern "C" { ///@addtogroup mip_c ///@{ //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_logging Mip Logging [C] +///@defgroup microstrain_logging MicroStrain Logging [C] /// -///@brief High-level C functions for logging information from within the MIP SDK +///@brief High-level C functions for logging information from within the MicroStrain SDK /// -/// This module contains functions that allow the MIP SDK to log information +/// This module contains functions that allow the MicroStrain SDK to log information /// and allows users to override the logging functions /// ///@{ @@ -23,14 +23,14 @@ extern "C" { //////////////////////////////////////////////////////////////////////////////// ///@brief Logging level enum /// -typedef uint8_t mip_log_level; -#define MIP_LOG_LEVEL_OFF 0 ///< Signifies that the log is turned off -#define MIP_LOG_LEVEL_FATAL 1 ///< Fatal logs are logged when an unrecoverable error occurs -#define MIP_LOG_LEVEL_ERROR 2 ///< Error logs are logged when an error occurs -#define MIP_LOG_LEVEL_WARN 3 ///< Warning logs are logged when something concerning happens that may or not be a mistake -#define MIP_LOG_LEVEL_INFO 4 ///< Info logs are logged when some general info needs to be conveyed to the user -#define MIP_LOG_LEVEL_DEBUG 5 ///< Debug logs are logged for debug purposes. -#define MIP_LOG_LEVEL_TRACE 6 ///< Trace logs are logged in similar cases to debug logs but can be logged in tight loops +typedef uint8_t microstrain_log_level; +#define MICROSTRAIN_LOG_LEVEL_OFF 0 ///< Signifies that the log is turned off +#define MICROSTRAIN_LOG_LEVEL_FATAL 1 ///< Fatal logs are logged when an unrecoverable error occurs +#define MICROSTRAIN_LOG_LEVEL_ERROR 2 ///< Error logs are logged when an error occurs +#define MICROSTRAIN_LOG_LEVEL_WARN 3 ///< Warning logs are logged when something concerning happens that may or not be a mistake +#define MICROSTRAIN_LOG_LEVEL_INFO 4 ///< Info logs are logged when some general info needs to be conveyed to the user +#define MICROSTRAIN_LOG_LEVEL_DEBUG 5 ///< Debug logs are logged for debug purposes. +#define MICROSTRAIN_LOG_LEVEL_TRACE 6 ///< Trace logs are logged in similar cases to debug logs but can be logged in tight loops //////////////////////////////////////////////////////////////////////////////// ///@brief Callback function typedef for custom logging behavior. @@ -39,15 +39,15 @@ typedef uint8_t mip_log_level; ///@param fmt printf style format string ///@param ... Variadic args used to populate the fmt string /// -typedef void (*mip_log_callback)(void* user, mip_log_level level, const char* fmt, va_list args); +typedef void (*microstrain_log_callback)(void* user, microstrain_log_level level, const char* fmt, va_list args); -void mip_logging_init(mip_log_callback callback, mip_log_level level, void* user); +void microstrain_logging_init(microstrain_log_callback callback, microstrain_log_level level, void* user); -mip_log_callback mip_logging_callback(); -mip_log_level mip_logging_level(); -void* mip_logging_user_data(); +microstrain_log_callback microstrain_logging_callback(); +microstrain_log_level microstrain_logging_level(); +void* microstrain_logging_user_data(); -void mip_logging_log(mip_log_level level, const char* fmt, ...); +void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to initialize the MIP logger. @@ -58,7 +58,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); ///@param user User data that will be passed to the callback every time it is excuted /// #ifdef MIP_ENABLE_LOGGING -#define MIP_LOG_INIT(callback, level, user) mip_logging_init(callback, level, user) +#define MIP_LOG_INIT(callback, level, user) microstrain_logging_init(callback, level, user) #else #define MIP_LOG_INIT(callback, level, user) (void)0 #endif @@ -66,10 +66,10 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK. Prefer specific /// log level functions like MIP_LOG_INFO, etc. when possible. -///@copydetails mip::C::mip_log_callback +///@copydetails mip::C::microstrain_log_callback /// #ifdef MIP_ENABLE_LOGGING -#define MIP_LOG_LOG(level, ...) mip_logging_log(level, __VA_ARGS__) +#define MIP_LOG_LOG(level, ...) microstrain_logging_log(level, __VA_ARGS__) #else #define MIP_LOG_LOG(level, ...) (void)0 #endif @@ -85,8 +85,8 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); ///@param fmt printf style format string ///@param ... Variadic args used to populate the fmt string /// -#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_FATAL -#define MIP_LOG_FATAL(...) MIP_LOG_LOG(MIP_LOG_LEVEL_FATAL, __VA_ARGS__) +#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_FATAL +#define MIP_LOG_FATAL(...) MIP_LOG_LOG(MICROSTRAIN_LOG_LEVEL_FATAL, __VA_ARGS__) #else #define MIP_LOG_FATAL(...) (void)0 #endif @@ -94,8 +94,8 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at error level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_ERROR -#define MIP_LOG_ERROR(...) MIP_LOG_LOG(MIP_LOG_LEVEL_ERROR, __VA_ARGS__) +#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_ERROR +#define MIP_LOG_ERROR(...) MIP_LOG_LOG(MICROSTRAIN_LOG_LEVEL_ERROR, __VA_ARGS__) #else #define MIP_LOG_ERROR(...) (void)0 #endif @@ -103,8 +103,8 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at warn level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_WARN -#define MIP_LOG_WARN(...) MIP_LOG_LOG(MIP_LOG_LEVEL_WARN, __VA_ARGS__) +#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_WARN +#define MIP_LOG_WARN(...) MIP_LOG_LOG(MICROSTRAIN_LOG_LEVEL_WARN, __VA_ARGS__) #else #define MIP_LOG_WARN(...) (void)0 #endif @@ -112,7 +112,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at info level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_INFO +#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_INFO #define MIP_LOG_INFO(...) MIP_LOG_LOG(MIP_LOG_LEVEL_INFO, __VA_ARGS__) #else #define MIP_LOG_INFO(...) (void)0 @@ -121,7 +121,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at debug level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_DEBUG +#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_DEBUG #define MIP_LOG_DEBUG(...) MIP_LOG_LOG(MIP_LOG_LEVEL_DEBUG, __VA_ARGS__) #else #define MIP_LOG_DEBUG(...) (void)0 @@ -130,7 +130,7 @@ void mip_logging_log(mip_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at trace level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MIP_LOG_LEVEL_TRACE +#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_TRACE #define MIP_LOG_TRACE(...) MIP_LOG_LOG(MIP_LOG_LEVEL_TRACE, __VA_ARGS__) #else #define MIP_LOG_TRACE(...) (void)0 diff --git a/src/microstrain/connections/serial/serial_port.c b/src/microstrain/connections/serial/serial_port.c index 9de7e9602..21e8a637d 100644 --- a/src/microstrain/connections/serial/serial_port.c +++ b/src/microstrain/connections/serial/serial_port.c @@ -1,5 +1,5 @@ -#include "microstrain/common/mip_logging.h" +#include "microstrain/common/logging.h" #include "serial_port.h" diff --git a/src/microstrain/connections/tcp/tcp_socket.c b/src/microstrain/connections/tcp/tcp_socket.c index 6297a45b3..8e85d2e37 100644 --- a/src/microstrain/connections/tcp/tcp_socket.c +++ b/src/microstrain/connections/tcp/tcp_socket.c @@ -1,7 +1,7 @@ #include "tcp_socket.h" -#include "microstrain/common/mip_logging.h" +#include "microstrain/common/logging.h" #ifdef _WIN32 From 30e670a7ac0bc5ea4cfd738a9a274b46396c0434 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 8 May 2024 17:14:12 -0400 Subject: [PATCH 005/147] Rename microstrain_timestamp to microstrain_embedded_timestamp. --- .../common/{microstrain_time.h => embedded_time.h} | 11 +++++------ src/microstrain/connections/connection.hpp | 4 ++-- .../connections/recording/recording_connection.cpp | 2 +- .../connections/recording/recording_connection.hpp | 2 +- .../connections/serial/serial_connection.hpp | 2 +- src/microstrain/connections/tcp/tcp_connection.cpp | 2 +- src/microstrain/connections/tcp/tcp_connection.hpp | 2 +- 7 files changed, 12 insertions(+), 13 deletions(-) rename src/microstrain/common/{microstrain_time.h => embedded_time.h} (73%) diff --git a/src/microstrain/common/microstrain_time.h b/src/microstrain/common/embedded_time.h similarity index 73% rename from src/microstrain/common/microstrain_time.h rename to src/microstrain/common/embedded_time.h index 766e9df45..b05eda6fa 100644 --- a/src/microstrain/common/microstrain_time.h +++ b/src/microstrain/common/embedded_time.h @@ -21,26 +21,25 @@ namespace C { /// #ifdef MICROSTRAIN_TIMESTAMP_TYPE typedef MICROSTRAIN_TIMESTAMP_TYPE microstrain_timestamp; -static_assert( sizeof(microstrain_timestamp) >= 8 || microstrain_timestamp(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); +static_assert( sizeof(microstrain_embedded_timestamp) >= 8 || microstrain_embedded_timestamp(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); #elif defined(MICROSTRAIN_PLATFORM_DESKTOP) // By default, on desktop we use 64-bit timestamps. -typedef uint64_t microstrain_timestamp; +typedef uint64_t microstrain_embedded_timestamp; #else // If the platform isn't known, assume u32 timestamps. typedef uint32_t microstrain_timestamp; #endif // Timeouts are just an alias for timestamps -typedef microstrain_timestamp microstrain_timeout; - +typedef microstrain_embedded_timestamp microstrain_embedded_timeout; #ifdef __cplusplus } // namespace C -using Timestamp = C::microstrain_timestamp; -using Timeout = C::microstrain_timeout; +using EmbeddedTimestamp = C::microstrain_embedded_timestamp; +using EmbeddedTimeout = C::microstrain_embedded_timeout; } // namespace microstrain #endif // __cplusplus diff --git a/src/microstrain/connections/connection.hpp b/src/microstrain/connections/connection.hpp index e68268a0b..0a9bfe78e 100644 --- a/src/microstrain/connections/connection.hpp +++ b/src/microstrain/connections/connection.hpp @@ -1,6 +1,6 @@ #pragma once -#include "microstrain/common/microstrain_time.h" +#include "microstrain/common/embedded_time.h" #include #include @@ -31,7 +31,7 @@ class Connection virtual ~Connection() {} virtual bool sendToDevice(const uint8_t* data, size_t length) = 0; - virtual bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, Timestamp* timestamp_out) = 0; + virtual bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) = 0; #if __cpp_lib_span >= 202002L bool sendToDevice(std::span data) { return sendToDevice(data.data(), data.size()); } diff --git a/src/microstrain/connections/recording/recording_connection.cpp b/src/microstrain/connections/recording/recording_connection.cpp index ab5af689c..5ab0add89 100644 --- a/src/microstrain/connections/recording/recording_connection.cpp +++ b/src/microstrain/connections/recording/recording_connection.cpp @@ -33,7 +33,7 @@ bool RecordingConnection::sendToDevice(const uint8_t* data, size_t length) } ///@copydoc mip::Connection::recvFromDevice -bool RecordingConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* count_out, Timestamp* timestamp_out) +bool RecordingConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* count_out, EmbeddedTimestamp* timestamp_out) { const bool ok = mConnection->recvFromDevice(buffer, max_length, wait_time_ms, count_out, timestamp_out); diff --git a/src/microstrain/connections/recording/recording_connection.hpp b/src/microstrain/connections/recording/recording_connection.hpp index ea4cf79d4..94b50f0f2 100644 --- a/src/microstrain/connections/recording/recording_connection.hpp +++ b/src/microstrain/connections/recording/recording_connection.hpp @@ -27,7 +27,7 @@ class RecordingConnection : public Connection ~RecordingConnection() = default; bool sendToDevice(const uint8_t* data, size_t length) override; - bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, Timestamp* timestamp_out) override; + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) override; bool isConnected() const override { diff --git a/src/microstrain/connections/serial/serial_connection.hpp b/src/microstrain/connections/serial/serial_connection.hpp index 0734e11f1..6ec3840ec 100644 --- a/src/microstrain/connections/serial/serial_connection.hpp +++ b/src/microstrain/connections/serial/serial_connection.hpp @@ -27,7 +27,7 @@ class SerialConnection : public microstrain::Connection SerialConnection(std::string portName, uint32_t baudrate); ~SerialConnection(); - bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, Timestamp* timestamp_out) final; + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, EmbeddedTimestamp* timestamp_out) final; bool sendToDevice(const uint8_t* data, size_t length) final; bool isConnected() const override; diff --git a/src/microstrain/connections/tcp/tcp_connection.cpp b/src/microstrain/connections/tcp/tcp_connection.cpp index b1a71610c..fe3b348da 100644 --- a/src/microstrain/connections/tcp/tcp_connection.cpp +++ b/src/microstrain/connections/tcp/tcp_connection.cpp @@ -56,7 +56,7 @@ bool TcpConnection::disconnect() } ///@copydoc mip::Connection::sendToDevice -bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, Timestamp* timestamp_out) +bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) { (void)wait_time_ms; // Not used, timeout is always fixed diff --git a/src/microstrain/connections/tcp/tcp_connection.hpp b/src/microstrain/connections/tcp/tcp_connection.hpp index 9043ca281..4f39e20e0 100644 --- a/src/microstrain/connections/tcp/tcp_connection.hpp +++ b/src/microstrain/connections/tcp/tcp_connection.hpp @@ -29,7 +29,7 @@ class TcpConnection : public microstrain::Connection TcpConnection(const TcpConnection&) = delete; TcpConnection& operator=(const TcpConnection&) = delete; - bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, Timestamp* timestamp_out) final; + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, EmbeddedTimestamp* timestamp_out) final; bool sendToDevice(const uint8_t* data, size_t length) final; bool isConnected() const final; From db0f45abeaeac44dc629081cfc837c2b3a3b072c Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 8 May 2024 18:10:34 -0400 Subject: [PATCH 006/147] Start renaming serializer [WIP]. --- examples/watch_imu.c | 2 +- examples/watch_imu.cpp | 2 +- src/microstrain/common/CMakeLists.txt | 4 +- .../common}/serialization.c | 24 +- .../common}/serialization.h | 152 +- src/mip/CMakeLists.txt | 2 - src/mip/definitions/commands_3dm.c | 2448 ++++++++------- src/mip/definitions/commands_3dm.cpp | 2 +- src/mip/definitions/commands_aiding.c | 537 ++-- src/mip/definitions/commands_aiding.cpp | 2 +- src/mip/definitions/commands_base.c | 160 +- src/mip/definitions/commands_base.cpp | 2 +- src/mip/definitions/commands_filter.c | 2730 +++++++++-------- src/mip/definitions/commands_filter.cpp | 2 +- src/mip/definitions/commands_gnss.c | 194 +- src/mip/definitions/commands_gnss.cpp | 2 +- src/mip/definitions/commands_rtk.c | 174 +- src/mip/definitions/commands_rtk.cpp | 2 +- src/mip/definitions/commands_system.c | 33 +- src/mip/definitions/commands_system.cpp | 2 +- src/mip/definitions/common.c | 10 +- src/mip/definitions/common.h | 2 +- src/mip/definitions/data_filter.c | 1056 +++---- src/mip/definitions/data_filter.cpp | 2 +- src/mip/definitions/data_gnss.c | 1704 +++++----- src/mip/definitions/data_gnss.cpp | 2 +- src/mip/definitions/data_sensor.c | 208 +- src/mip/definitions/data_sensor.cpp | 2 +- src/mip/definitions/data_shared.c | 76 +- src/mip/definitions/data_shared.cpp | 2 +- src/mip/definitions/data_system.c | 42 +- src/mip/definitions/data_system.cpp | 2 +- src/mip/definitions/descriptors.c | 6 +- src/mip/definitions/descriptors.h | 2 +- src/mip/mip_all.h | 2 +- src/mip/mip_all.hpp | 2 +- 36 files changed, 5019 insertions(+), 4577 deletions(-) rename src/{mip/utils => microstrain/common}/serialization.c (89%) rename src/{mip/utils => microstrain/common}/serialization.h (59%) diff --git a/examples/watch_imu.c b/examples/watch_imu.c index ddc7cbb5f..a802bd5af 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -5,7 +5,7 @@ #include #include #include "microstrain/common/logging.h" -#include +#include "microstrain/common/serialization.h" #include #include diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index c071d73f4..13237f0db 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -3,7 +3,7 @@ #include #include -#include +#include "microstrain/common/serialization.h" #include #include diff --git a/src/microstrain/common/CMakeLists.txt b/src/microstrain/common/CMakeLists.txt index df1776614..5a9377525 100644 --- a/src/microstrain/common/CMakeLists.txt +++ b/src/microstrain/common/CMakeLists.txt @@ -4,10 +4,12 @@ set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max set(SOURCES - platform.h descriptor_id.hpp index.hpp logging.h + platform.h + serialization.c + serialization.h ) diff --git a/src/mip/utils/serialization.c b/src/microstrain/common/serialization.c similarity index 89% rename from src/mip/utils/serialization.c rename to src/microstrain/common/serialization.c index 96cef9bce..18025a96c 100644 --- a/src/mip/utils/serialization.c +++ b/src/microstrain/common/serialization.c @@ -1,8 +1,8 @@ #include "serialization.h" -#include "../mip_field.h" -#include "../mip_packet.h" -#include "../mip_offsets.h" +#include "mip/mip_field.h" +#include "mip/mip_packet.h" +#include "mip/mip_offsets.h" #include #include @@ -85,7 +85,7 @@ void mip_serializer_finish_new_field(const mip_serializer* serializer, mip_packe { assert(packet); - if( mip_serializer_is_ok(serializer) ) + if(microstrain_serializer_is_ok(serializer) ) { assert(serializer->_offset <= MIP_FIELD_LENGTH_MAX); // Payload too long! mip_packet_realloc_last_field(packet, serializer->_buffer, (uint8_t) serializer->_offset); @@ -125,7 +125,7 @@ size_t mip_serializer_capacity(const mip_serializer* serializer) /// For insertion, returns how many bytes have been written. /// For extraction, returns how many bytes have been read. /// -///@note This may exceed the buffer size. Check mip_serializer_is_ok() before using +///@note This may exceed the buffer size. Check microstrain_serializer_is_ok() before using /// the data. /// size_t mip_serializer_length(const mip_serializer* serializer) @@ -143,11 +143,11 @@ size_t mip_serializer_length(const mip_serializer* serializer) /// ///@note This can be a negative number if the application attempted to write /// or read more data than contained in the buffer. This is not a bug and -/// it can be detected with the mip_serializer_is_ok() function. +/// it can be detected with the microstrain_serializer_is_ok() function. /// int mip_serializer_remaining(const mip_serializer* serializer) { - return (int)(mip_serializer_capacity(serializer) - mip_serializer_length(serializer)); + return (int)(microstrain_serializer_capacity(serializer) - microstrain_serializer_length(serializer)); } //////////////////////////////////////////////////////////////////////////////// @@ -160,11 +160,11 @@ int mip_serializer_remaining(const mip_serializer* serializer) /// ///@param serializer /// -///@returns true if mip_serializer_remaining() >= 0. +///@returns true if microstrain_serializer_remaining() >= 0. /// bool mip_serializer_is_ok(const mip_serializer* serializer) { - return mip_serializer_length(serializer) <= mip_serializer_capacity(serializer); + return microstrain_serializer_length(serializer) <= microstrain_serializer_capacity(serializer); } //////////////////////////////////////////////////////////////////////////////// @@ -175,7 +175,7 @@ bool mip_serializer_is_ok(const mip_serializer* serializer) /// ///@param serializer /// -///@returns true if mip_serializer_remaining() == 0. +///@returns true if microstrain_serializer_remaining() == 0. /// bool mip_serializer_is_complete(const mip_serializer* serializer) { @@ -244,7 +244,7 @@ EXTRACT_MACRO(double, double ) //////////////////////////////////////////////////////////////////////////////// -///@brief Similar to extract_u8 but allows a maximum value to be specified. +///@brief Similar to microstrain_extract_u8 but allows a maximum value to be specified. /// /// If the maximum count would be exceeded, an error is generated which causes /// further extraction to fail. @@ -259,7 +259,7 @@ EXTRACT_MACRO(double, double ) void extract_count(mip_serializer* serializer, uint8_t* count_out, uint8_t max_count) { *count_out = 0; // Default to zero if extraction fails. - extract_u8(serializer, count_out); + microstrain_extract_u8(serializer, count_out); if( *count_out > max_count ) { // This is an error condition which can occur if the device sends diff --git a/src/mip/utils/serialization.h b/src/microstrain/common/serialization.h similarity index 59% rename from src/mip/utils/serialization.h rename to src/microstrain/common/serialization.h index d0b03f6b0..4c9d4406b 100644 --- a/src/mip/utils/serialization.h +++ b/src/microstrain/common/serialization.h @@ -3,9 +3,9 @@ #include #include -#include "../mip_field.h" -#include "../mip_packet.h" -#include "../mip_types.h" +#include "mip/mip_field.h" +#include "mip/mip_packet.h" +#include "mip/mip_types.h" //////////////////////////////////////////////////////////////////////////////// ///@defgroup mip_serialization MIP Serialization @@ -17,9 +17,9 @@ ///@} #ifdef __cplusplus -#include +#include -namespace mip { +namespace microstrain { namespace C { extern "C" { #endif // __cplusplus @@ -42,61 +42,61 @@ extern "C" { /// as they are subject to change in future versions of this software. /// /// -typedef struct mip_serializer +typedef struct microstrain_serializer { uint8_t* _buffer; ///<@private Pointer to data for serialization. size_t _buffer_size; ///<@private Size of the buffer. size_t _offset; ///<@private Current offset into the buffer (can exceed buffer_size!). -} mip_serializer; +} microstrain_serializer; -void mip_serializer_init_insertion(mip_serializer* serializer, uint8_t* buffer, size_t buffer_size); -void mip_serializer_init_extraction(mip_serializer* serializer, const uint8_t* buffer, size_t buffer_size); -void mip_serializer_init_new_field(mip_serializer* serializer, mip_packet* packet, uint8_t field_descriptor); -void mip_serializer_finish_new_field(const mip_serializer* serializer, mip_packet* packet); -void mip_serializer_init_from_field(mip_serializer* serializer, const mip_field* field); +void microstrain_serializer_init_insertion(microstrain_serializer* serializer, uint8_t* buffer, size_t buffer_size); +void microstrain_serializer_init_extraction(microstrain_serializer* serializer, const uint8_t* buffer, size_t buffer_size); +void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor); +void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet* packet); +void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field* field); -size_t mip_serializer_capacity(const mip_serializer* serializer); -size_t mip_serializer_length(const mip_serializer* serializer); -int mip_serializer_remaining(const mip_serializer* serializer); +size_t microstrain_serializer_capacity(const microstrain_serializer* serializer); +size_t microstrain_serializer_length(const microstrain_serializer* serializer); +int microstrain_serializer_remaining(const microstrain_serializer* serializer); -bool mip_serializer_is_ok(const mip_serializer* serializer); -bool mip_serializer_is_complete(const mip_serializer* serializer); +bool microstrain_serializer_is_ok(const microstrain_serializer* serializer); +bool microstrain_serializer_is_complete(const microstrain_serializer* serializer); -void insert_bool(mip_serializer* serializer, bool value); -void insert_char(mip_serializer* serializer, char value); +void microstrain_insert_bool(microstrain_serializer* serializer, bool value); +void microstrain_insert_char(microstrain_serializer* serializer, char value); -void insert_u8 (mip_serializer* serializer, uint8_t value); -void insert_u16(mip_serializer* serializer, uint16_t value); -void insert_u32(mip_serializer* serializer, uint32_t value); -void insert_u64(mip_serializer* serializer, uint64_t value); +void microstrain_insert_u8 (microstrain_serializer* serializer, uint8_t value); +void microstrain_insert_u16(microstrain_serializer* serializer, uint16_t value); +void microstrain_insert_u32(microstrain_serializer* serializer, uint32_t value); +void microstrain_insert_u64(microstrain_serializer* serializer, uint64_t value); -void insert_s8 (mip_serializer* serializer, int8_t value); -void insert_s16(mip_serializer* serializer, int16_t value); -void insert_s32(mip_serializer* serializer, int32_t value); -void insert_s64(mip_serializer* serializer, int64_t value); +void microstrain_insert_s8 (microstrain_serializer* serializer, int8_t value); +void microstrain_insert_s16(microstrain_serializer* serializer, int16_t value); +void microstrain_insert_s32(microstrain_serializer* serializer, int32_t value); +void microstrain_insert_s64(microstrain_serializer* serializer, int64_t value); -void insert_float (mip_serializer* serializer, float value); -void insert_double(mip_serializer* serializer, double value); +void microstrain_insert_float(microstrain_serializer* serializer, float value); +void microstrain_insert_double(microstrain_serializer* serializer, double value); -void extract_bool(mip_serializer* serializer, bool* value); -void extract_char(mip_serializer* serializer, char* value); +void microstrain_extract_bool(microstrain_serializer* serializer, bool* value); +void microstrain_extract_char(microstrain_serializer* serializer, char* value); -void extract_u8 (mip_serializer* serializer, uint8_t* value); -void extract_u16(mip_serializer* serializer, uint16_t* value); -void extract_u32(mip_serializer* serializer, uint32_t* value); -void extract_u64(mip_serializer* serializer, uint64_t* value); +void microstrain_extract_u8 (microstrain_serializer* serializer, uint8_t* value); +void microstrain_extract_u16(microstrain_serializer* serializer, uint16_t* value); +void microstrain_extract_u32(microstrain_serializer* serializer, uint32_t* value); +void microstrain_extract_u64(microstrain_serializer* serializer, uint64_t* value); -void extract_s8 (mip_serializer* serializer, int8_t* value); -void extract_s16(mip_serializer* serializer, int16_t* value); -void extract_s32(mip_serializer* serializer, int32_t* value); -void extract_s64(mip_serializer* serializer, int64_t* value); +void microstrain_extract_s8 (microstrain_serializer* serializer, int8_t* value); +void microstrain_extract_s16(microstrain_serializer* serializer, int16_t* value); +void microstrain_extract_s32(microstrain_serializer* serializer, int32_t* value); +void microstrain_extract_s64(microstrain_serializer* serializer, int64_t* value); -void extract_float (mip_serializer* serializer, float* value); -void extract_double(mip_serializer* serializer, double* value); +void microstrain_extract_float (microstrain_serializer* serializer, float* value); +void microstrain_extract_double(microstrain_serializer* serializer, double* value); -void extract_count(mip_serializer* serializer, uint8_t* count_out, uint8_t max_count); +void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* count_out, uint8_t max_count); ///@} //////////////////////////////////////////////////////////////////////////////// @@ -149,19 +149,19 @@ void extract_count(mip_serializer* serializer, uint8_t* count_out, uint8_t max_c //////////////////////////////////////////////////////////////////////////////// ///@brief Serialization class. /// -class Serializer : public C::mip_serializer +class Serializer : public C::microstrain_serializer { public: - Serializer(C::mip_packet& packet, uint8_t newFieldDescriptor) { C::mip_serializer_init_new_field(this, &packet, newFieldDescriptor); } - Serializer(uint8_t* buffer, size_t size, size_t offset=0) { C::mip_serializer_init_insertion(this, buffer, size); this->_offset = offset; } - Serializer(const uint8_t* buffer, size_t size, size_t offset=0) { C::mip_serializer_init_extraction(this, const_cast(buffer), size); this->_offset = offset; } + Serializer(C::mip_packet& packet, uint8_t newFieldDescriptor) { C::microstrain_serializer_init_new_field(this, &packet, newFieldDescriptor); } + Serializer(uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_insertion(this, buffer, size); this->_offset = offset; } + Serializer(const uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_extraction(this, const_cast(buffer), size); this->_offset = offset; } - size_t capacity() const { return C::mip_serializer_capacity(this); } - size_t length() const { return C::mip_serializer_length(this); } - int remaining() const { return C::mip_serializer_remaining(this); } + size_t capacity() const { return C::microstrain_serializer_capacity(this); } + size_t length() const { return C::microstrain_serializer_length(this); } + int remaining() const { return C::microstrain_serializer_remaining(this); } - bool isOk() const { return C::mip_serializer_is_ok(this); } - bool isComplete() const { return C::mip_serializer_is_complete(this); } + bool isOk() const { return C::microstrain_serializer_is_ok(this); } + bool isComplete() const { return C::microstrain_serializer_is_complete(this); } operator const void*() const { return isOk() ? this : nullptr; } bool operator!() const { return !isOk(); } @@ -169,18 +169,18 @@ class Serializer : public C::mip_serializer -inline void insert(Serializer& serializer, bool value) { return C::insert_bool (&serializer, value); } -inline void insert(Serializer& serializer, char value) { return C::insert_char (&serializer, value); } -inline void insert(Serializer& serializer, uint8_t value) { return C::insert_u8 (&serializer, value); } -inline void insert(Serializer& serializer, uint16_t value) { return C::insert_u16 (&serializer, value); } -inline void insert(Serializer& serializer, uint32_t value) { return C::insert_u32 (&serializer, value); } -inline void insert(Serializer& serializer, uint64_t value) { return C::insert_u64 (&serializer, value); } -inline void insert(Serializer& serializer, int8_t value) { return C::insert_s8 (&serializer, value); } -inline void insert(Serializer& serializer, int16_t value) { return C::insert_s16 (&serializer, value); } -inline void insert(Serializer& serializer, int32_t value) { return C::insert_s32 (&serializer, value); } -inline void insert(Serializer& serializer, int64_t value) { return C::insert_s64 (&serializer, value); } -inline void insert(Serializer& serializer, float value) { return C::insert_float (&serializer, value); } -inline void insert(Serializer& serializer, double value) { return C::insert_double(&serializer, value); } +inline void insert(Serializer& serializer, bool value) { return C::microstrain_insert_bool(&serializer, value); } +inline void insert(Serializer& serializer, char value) { return C::microstrain_insert_char(&serializer, value); } +inline void insert(Serializer& serializer, uint8_t value) { return C::microstrain_insert_u8(&serializer, value); } +inline void insert(Serializer& serializer, uint16_t value) { return C::microstrain_insert_u16(&serializer, value); } +inline void insert(Serializer& serializer, uint32_t value) { return C::microstrain_insert_u32(&serializer, value); } +inline void insert(Serializer& serializer, uint64_t value) { return C::microstrain_insert_u64(&serializer, value); } +inline void insert(Serializer& serializer, int8_t value) { return C::microstrain_insert_s8(&serializer, value); } +inline void insert(Serializer& serializer, int16_t value) { return C::microstrain_insert_s16(&serializer, value); } +inline void insert(Serializer& serializer, int32_t value) { return C::microstrain_insert_s32(&serializer, value); } +inline void insert(Serializer& serializer, int64_t value) { return C::microstrain_insert_s64(&serializer, value); } +inline void insert(Serializer& serializer, float value) { return C::microstrain_insert_float(&serializer, value); } +inline void insert(Serializer& serializer, double value) { return C::microstrain_insert_double(&serializer, value); } //////////////////////////////////////////////////////////////////////////////// ///@brief Inserts an enum into the buffer. @@ -215,18 +215,18 @@ bool insert(const T& value, uint8_t* buffer, size_t bufferSize, size_t offset=0) return !!serializer; } -inline void extract(Serializer& serializer, bool& value) { return C::extract_bool (&serializer, &value); } -inline void extract(Serializer& serializer, char& value) { return C::extract_char (&serializer, &value); } -inline void extract(Serializer& serializer, uint8_t& value) { return C::extract_u8 (&serializer, &value); } -inline void extract(Serializer& serializer, uint16_t& value) { return C::extract_u16 (&serializer, &value); } -inline void extract(Serializer& serializer, uint32_t& value) { return C::extract_u32 (&serializer, &value); } -inline void extract(Serializer& serializer, uint64_t& value) { return C::extract_u64 (&serializer, &value); } -inline void extract(Serializer& serializer, int8_t& value) { return C::extract_s8 (&serializer, &value); } -inline void extract(Serializer& serializer, int16_t& value) { return C::extract_s16 (&serializer, &value); } -inline void extract(Serializer& serializer, int32_t& value) { return C::extract_s32 (&serializer, &value); } -inline void extract(Serializer& serializer, int64_t& value) { return C::extract_s64 (&serializer, &value); } -inline void extract(Serializer& serializer, float& value) { return C::extract_float (&serializer, &value); } -inline void extract(Serializer& serializer, double& value) { return C::extract_double(&serializer, &value); } +inline void extract(Serializer& serializer, bool& value) { return C::microstrain_extract_bool(&serializer, &value); } +inline void extract(Serializer& serializer, char& value) { return C::microstrain_extract_char(&serializer, &value); } +inline void extract(Serializer& serializer, uint8_t& value) { return C::microstrain_extract_u8(&serializer, &value); } +inline void extract(Serializer& serializer, uint16_t& value) { return C::microstrain_extract_u16(&serializer, &value); } +inline void extract(Serializer& serializer, uint32_t& value) { return C::microstrain_extract_u32(&serializer, &value); } +inline void extract(Serializer& serializer, uint64_t& value) { return C::microstrain_extract_u64(&serializer, &value); } +inline void extract(Serializer& serializer, int8_t& value) { return C::microstrain_extract_s8(&serializer, &value); } +inline void extract(Serializer& serializer, int16_t& value) { return C::microstrain_extract_s16(&serializer, &value); } +inline void extract(Serializer& serializer, int32_t& value) { return C::microstrain_extract_s32(&serializer, &value); } +inline void extract(Serializer& serializer, int64_t& value) { return C::microstrain_extract_s64(&serializer, &value); } +inline void extract(Serializer& serializer, float& value) { return C::microstrain_extract_float(&serializer, &value); } +inline void extract(Serializer& serializer, double& value) { return C::microstrain_extract_double(&serializer, &value); } //////////////////////////////////////////////////////////////////////////////// ///@brief Extract an enum from the buffer. @@ -276,7 +276,7 @@ bool extract(T& value_out, const uint8_t* buffer, size_t bufferSize, size_t offs ///@} //////////////////////////////////////////////////////////////////////////////// -} // namespace mip +} // namespace microstrain #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// \ No newline at end of file diff --git a/src/mip/CMakeLists.txt b/src/mip/CMakeLists.txt index fcfe5fb7b..36da16faa 100644 --- a/src/mip/CMakeLists.txt +++ b/src/mip/CMakeLists.txt @@ -14,8 +14,6 @@ set(UTILS_DIR "${MIP_DIR}/utils") set(UTILS_SOURCES "${UTILS_DIR}/byte_ring.c" "${UTILS_DIR}/byte_ring.h" - "${UTILS_DIR}/serialization.c" - "${UTILS_DIR}/serialization.h" ) # diff --git a/src/mip/definitions/commands_3dm.c b/src/mip/definitions/commands_3dm.c index 8e5708e96..3fbaa81ad 100644 --- a/src/mip/definitions/commands_3dm.c +++ b/src/mip/definitions/commands_3dm.c @@ -1,7 +1,7 @@ #include "commands_3dm.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -27,10 +27,10 @@ void insert_mip_nmea_message(mip_serializer* serializer, const mip_nmea_message* insert_mip_nmea_message_message_id(serializer, self->message_id); insert_mip_nmea_message_talker_id(serializer, self->talker_id); - - insert_u8(serializer, self->source_desc_set); - - insert_u16(serializer, self->decimation); + + microstrain_insert_u8(serializer, self->source_desc_set); + + microstrain_insert_u16(serializer, self->decimation); } void extract_mip_nmea_message(mip_serializer* serializer, mip_nmea_message* self) @@ -38,43 +38,43 @@ void extract_mip_nmea_message(mip_serializer* serializer, mip_nmea_message* self extract_mip_nmea_message_message_id(serializer, &self->message_id); extract_mip_nmea_message_talker_id(serializer, &self->talker_id); - - extract_u8(serializer, &self->source_desc_set); - - extract_u16(serializer, &self->decimation); + + microstrain_extract_u8(serializer, &self->source_desc_set); + + microstrain_extract_u16(serializer, &self->decimation); } void insert_mip_nmea_message_message_id(struct mip_serializer* serializer, const mip_nmea_message_message_id self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_nmea_message_message_id(struct mip_serializer* serializer, mip_nmea_message_message_id* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_nmea_message_talker_id(struct mip_serializer* serializer, const mip_nmea_message_talker_id self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_nmea_message_talker_id(struct mip_serializer* serializer, mip_nmea_message_talker_id* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_sensor_range_type(struct mip_serializer* serializer, const mip_sensor_range_type self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_sensor_range_type(struct mip_serializer* serializer, mip_sensor_range_type* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -85,9 +85,9 @@ void extract_mip_sensor_range_type(struct mip_serializer* serializer, mip_sensor void insert_mip_3dm_poll_imu_message_command(mip_serializer* serializer, const mip_3dm_poll_imu_message_command* self) { - insert_bool(serializer, self->suppress_ack); - - insert_u8(serializer, self->num_descriptors); + microstrain_insert_bool(serializer, self->suppress_ack); + + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -96,10 +96,11 @@ void insert_mip_3dm_poll_imu_message_command(mip_serializer* serializer, const m } void extract_mip_3dm_poll_imu_message_command(mip_serializer* serializer, mip_3dm_poll_imu_message_command* self) { - extract_bool(serializer, &self->suppress_ack); + microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -111,24 +112,25 @@ mip_cmd_result mip_3dm_poll_imu_message(struct mip_interface* device, bool suppr mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_bool(&serializer, suppress_ack); - - insert_u8(&serializer, num_descriptors); + + microstrain_insert_bool(&serializer, suppress_ack); + + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); for(unsigned int i=0; i < num_descriptors; i++) insert_mip_descriptor_rate(&serializer, &descriptors[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_IMU_MESSAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_IMU_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_poll_gnss_message_command(mip_serializer* serializer, const mip_3dm_poll_gnss_message_command* self) { - insert_bool(serializer, self->suppress_ack); - - insert_u8(serializer, self->num_descriptors); + microstrain_insert_bool(serializer, self->suppress_ack); + + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -137,10 +139,11 @@ void insert_mip_3dm_poll_gnss_message_command(mip_serializer* serializer, const } void extract_mip_3dm_poll_gnss_message_command(mip_serializer* serializer, mip_3dm_poll_gnss_message_command* self) { - extract_bool(serializer, &self->suppress_ack); + microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -152,24 +155,25 @@ mip_cmd_result mip_3dm_poll_gnss_message(struct mip_interface* device, bool supp mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_bool(&serializer, suppress_ack); - - insert_u8(&serializer, num_descriptors); + + microstrain_insert_bool(&serializer, suppress_ack); + + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); for(unsigned int i=0; i < num_descriptors; i++) insert_mip_descriptor_rate(&serializer, &descriptors[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_GNSS_MESSAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_GNSS_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_poll_filter_message_command(mip_serializer* serializer, const mip_3dm_poll_filter_message_command* self) { - insert_bool(serializer, self->suppress_ack); - - insert_u8(serializer, self->num_descriptors); + microstrain_insert_bool(serializer, self->suppress_ack); + + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -178,10 +182,11 @@ void insert_mip_3dm_poll_filter_message_command(mip_serializer* serializer, cons } void extract_mip_3dm_poll_filter_message_command(mip_serializer* serializer, mip_3dm_poll_filter_message_command* self) { - extract_bool(serializer, &self->suppress_ack); + microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -193,18 +198,19 @@ mip_cmd_result mip_3dm_poll_filter_message(struct mip_interface* device, bool su mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_bool(&serializer, suppress_ack); - - insert_u8(&serializer, num_descriptors); + + microstrain_insert_bool(&serializer, suppress_ack); + + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); for(unsigned int i=0; i < num_descriptors; i++) insert_mip_descriptor_rate(&serializer, &descriptors[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_FILTER_MESSAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_FILTER_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_imu_message_format_command(mip_serializer* serializer, const mip_3dm_imu_message_format_command* self) { @@ -212,7 +218,7 @@ void insert_mip_3dm_imu_message_format_command(mip_serializer* serializer, const if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->num_descriptors); + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -227,7 +233,8 @@ void extract_mip_3dm_imu_message_format_command(mip_serializer* serializer, mip_ if( self->function == MIP_FUNCTION_WRITE ) { assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -237,7 +244,7 @@ void extract_mip_3dm_imu_message_format_command(mip_serializer* serializer, mip_ void insert_mip_3dm_imu_message_format_response(mip_serializer* serializer, const mip_3dm_imu_message_format_response* self) { - insert_u8(serializer, self->num_descriptors); + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -247,7 +254,8 @@ void insert_mip_3dm_imu_message_format_response(mip_serializer* serializer, cons void extract_mip_3dm_imu_message_format_response(mip_serializer* serializer, mip_3dm_imu_message_format_response* self) { assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -261,16 +269,17 @@ mip_cmd_result mip_3dm_write_imu_message_format(struct mip_interface* device, ui mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, num_descriptors); + + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); for(unsigned int i=0; i < num_descriptors; i++) insert_mip_descriptor_rate(&serializer, &descriptors[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { @@ -280,10 +289,11 @@ mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uin insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -291,13 +301,13 @@ mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uin mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(num_descriptors_out); - extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); + microstrain_extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); assert(descriptors_out || (num_descriptors_out == 0)); for(unsigned int i=0; i < *num_descriptors_out; i++) extract_mip_descriptor_rate(&deserializer, &descriptors_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -310,9 +320,10 @@ mip_cmd_result mip_3dm_save_imu_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_imu_message_format(struct mip_interface* device) { @@ -322,9 +333,10 @@ mip_cmd_result mip_3dm_load_imu_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_imu_message_format(struct mip_interface* device) { @@ -334,9 +346,10 @@ mip_cmd_result mip_3dm_default_imu_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_gps_message_format_command(mip_serializer* serializer, const mip_3dm_gps_message_format_command* self) { @@ -344,7 +357,7 @@ void insert_mip_3dm_gps_message_format_command(mip_serializer* serializer, const if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->num_descriptors); + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -359,7 +372,8 @@ void extract_mip_3dm_gps_message_format_command(mip_serializer* serializer, mip_ if( self->function == MIP_FUNCTION_WRITE ) { assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -369,7 +383,7 @@ void extract_mip_3dm_gps_message_format_command(mip_serializer* serializer, mip_ void insert_mip_3dm_gps_message_format_response(mip_serializer* serializer, const mip_3dm_gps_message_format_response* self) { - insert_u8(serializer, self->num_descriptors); + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -379,7 +393,8 @@ void insert_mip_3dm_gps_message_format_response(mip_serializer* serializer, cons void extract_mip_3dm_gps_message_format_response(mip_serializer* serializer, mip_3dm_gps_message_format_response* self) { assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -393,16 +408,17 @@ mip_cmd_result mip_3dm_write_gps_message_format(struct mip_interface* device, ui mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, num_descriptors); + + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); for(unsigned int i=0; i < num_descriptors; i++) insert_mip_descriptor_rate(&serializer, &descriptors[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { @@ -412,10 +428,11 @@ mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uin insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -423,13 +440,13 @@ mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uin mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(num_descriptors_out); - extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); + microstrain_extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); assert(descriptors_out || (num_descriptors_out == 0)); for(unsigned int i=0; i < *num_descriptors_out; i++) extract_mip_descriptor_rate(&deserializer, &descriptors_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -442,9 +459,10 @@ mip_cmd_result mip_3dm_save_gps_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_gps_message_format(struct mip_interface* device) { @@ -454,9 +472,10 @@ mip_cmd_result mip_3dm_load_gps_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_gps_message_format(struct mip_interface* device) { @@ -466,9 +485,10 @@ mip_cmd_result mip_3dm_default_gps_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_filter_message_format_command(mip_serializer* serializer, const mip_3dm_filter_message_format_command* self) { @@ -476,7 +496,7 @@ void insert_mip_3dm_filter_message_format_command(mip_serializer* serializer, co if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->num_descriptors); + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -491,7 +511,8 @@ void extract_mip_3dm_filter_message_format_command(mip_serializer* serializer, m if( self->function == MIP_FUNCTION_WRITE ) { assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -501,7 +522,7 @@ void extract_mip_3dm_filter_message_format_command(mip_serializer* serializer, m void insert_mip_3dm_filter_message_format_response(mip_serializer* serializer, const mip_3dm_filter_message_format_response* self) { - insert_u8(serializer, self->num_descriptors); + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -511,7 +532,8 @@ void insert_mip_3dm_filter_message_format_response(mip_serializer* serializer, c void extract_mip_3dm_filter_message_format_response(mip_serializer* serializer, mip_3dm_filter_message_format_response* self) { assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -525,16 +547,17 @@ mip_cmd_result mip_3dm_write_filter_message_format(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, num_descriptors); + + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); for(unsigned int i=0; i < num_descriptors; i++) insert_mip_descriptor_rate(&serializer, &descriptors[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { @@ -544,10 +567,11 @@ mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -555,13 +579,13 @@ mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(num_descriptors_out); - extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); + microstrain_extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); assert(descriptors_out || (num_descriptors_out == 0)); for(unsigned int i=0; i < *num_descriptors_out; i++) extract_mip_descriptor_rate(&deserializer, &descriptors_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -574,9 +598,10 @@ mip_cmd_result mip_3dm_save_filter_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_filter_message_format(struct mip_interface* device) { @@ -586,9 +611,10 @@ mip_cmd_result mip_3dm_load_filter_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_filter_message_format(struct mip_interface* device) { @@ -598,9 +624,10 @@ mip_cmd_result mip_3dm_default_filter_message_format(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_imu_get_base_rate(struct mip_interface* device, uint16_t* rate_out) { @@ -615,9 +642,9 @@ mip_cmd_result mip_3dm_imu_get_base_rate(struct mip_interface* device, uint16_t* mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(rate_out); - extract_u16(&deserializer, rate_out); + microstrain_extract_u16(&deserializer, rate_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -635,9 +662,9 @@ mip_cmd_result mip_3dm_gps_get_base_rate(struct mip_interface* device, uint16_t* mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(rate_out); - extract_u16(&deserializer, rate_out); + microstrain_extract_u16(&deserializer, rate_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -655,37 +682,38 @@ mip_cmd_result mip_3dm_filter_get_base_rate(struct mip_interface* device, uint16 mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(rate_out); - extract_u16(&deserializer, rate_out); + microstrain_extract_u16(&deserializer, rate_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } void insert_mip_3dm_poll_data_command(mip_serializer* serializer, const mip_3dm_poll_data_command* self) { - insert_u8(serializer, self->desc_set); - - insert_bool(serializer, self->suppress_ack); - - insert_u8(serializer, self->num_descriptors); + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_bool(serializer, self->suppress_ack); + + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) - insert_u8(serializer, self->descriptors[i]); + microstrain_insert_u8(serializer, self->descriptors[i]); } void extract_mip_3dm_poll_data_command(mip_serializer* serializer, mip_3dm_poll_data_command* self) { - extract_u8(serializer, &self->desc_set); - - extract_bool(serializer, &self->suppress_ack); + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) - extract_u8(serializer, &self->descriptors[i]); + microstrain_extract_u8(serializer, &self->descriptors[i]); } @@ -694,44 +722,45 @@ mip_cmd_result mip_3dm_poll_data(struct mip_interface* device, uint8_t desc_set, mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_u8(&serializer, desc_set); - - insert_bool(&serializer, suppress_ack); - - insert_u8(&serializer, num_descriptors); + + microstrain_insert_u8(&serializer, desc_set); + + microstrain_insert_bool(&serializer, suppress_ack); + + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); for(unsigned int i=0; i < num_descriptors; i++) - insert_u8(&serializer, descriptors[i]); + microstrain_insert_u8(&serializer, descriptors[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_DATA, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_DATA, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_get_base_rate_command(mip_serializer* serializer, const mip_3dm_get_base_rate_command* self) { - insert_u8(serializer, self->desc_set); + microstrain_insert_u8(serializer, self->desc_set); } void extract_mip_3dm_get_base_rate_command(mip_serializer* serializer, mip_3dm_get_base_rate_command* self) { - extract_u8(serializer, &self->desc_set); + microstrain_extract_u8(serializer, &self->desc_set); } void insert_mip_3dm_get_base_rate_response(mip_serializer* serializer, const mip_3dm_get_base_rate_response* self) { - insert_u8(serializer, self->desc_set); - - insert_u16(serializer, self->rate); + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u16(serializer, self->rate); } void extract_mip_3dm_get_base_rate_response(mip_serializer* serializer, mip_3dm_get_base_rate_response* self) { - extract_u8(serializer, &self->desc_set); - - extract_u16(serializer, &self->rate); + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_u16(serializer, &self->rate); } @@ -740,25 +769,26 @@ mip_cmd_result mip_3dm_get_base_rate(struct mip_interface* device, uint8_t desc_ mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + microstrain_insert_u8(&serializer, desc_set); - insert_u8(&serializer, desc_set); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GET_BASE_RATE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_BASE_RATE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GET_BASE_RATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_BASE_RATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &desc_set); + + microstrain_extract_u8(&deserializer, &desc_set); assert(rate_out); - extract_u16(&deserializer, rate_out); + microstrain_extract_u16(&deserializer, rate_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -766,12 +796,12 @@ mip_cmd_result mip_3dm_get_base_rate(struct mip_interface* device, uint8_t desc_ void insert_mip_3dm_message_format_command(mip_serializer* serializer, const mip_3dm_message_format_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->desc_set); + + microstrain_insert_u8(serializer, self->desc_set); if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->num_descriptors); + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -782,13 +812,14 @@ void insert_mip_3dm_message_format_command(mip_serializer* serializer, const mip void extract_mip_3dm_message_format_command(mip_serializer* serializer, mip_3dm_message_format_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->desc_set); + + microstrain_extract_u8(serializer, &self->desc_set); if( self->function == MIP_FUNCTION_WRITE ) { assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -798,9 +829,9 @@ void extract_mip_3dm_message_format_command(mip_serializer* serializer, mip_3dm_ void insert_mip_3dm_message_format_response(mip_serializer* serializer, const mip_3dm_message_format_response* self) { - insert_u8(serializer, self->desc_set); - - insert_u8(serializer, self->num_descriptors); + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u8(serializer, self->num_descriptors); for(unsigned int i=0; i < self->num_descriptors; i++) @@ -809,10 +840,11 @@ void insert_mip_3dm_message_format_response(mip_serializer* serializer, const mi } void extract_mip_3dm_message_format_response(mip_serializer* serializer, mip_3dm_message_format_response* self) { - extract_u8(serializer, &self->desc_set); + microstrain_extract_u8(serializer, &self->desc_set); assert(self->num_descriptors); - extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, + sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -826,18 +858,19 @@ mip_cmd_result mip_3dm_write_message_format(struct mip_interface* device, uint8_ mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, desc_set); - - insert_u8(&serializer, num_descriptors); + + microstrain_insert_u8(&serializer, desc_set); + + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); for(unsigned int i=0; i < num_descriptors; i++) insert_mip_descriptor_rate(&serializer, &descriptors[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_message_format(struct mip_interface* device, uint8_t desc_set, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { @@ -846,29 +879,30 @@ mip_cmd_result mip_3dm_read_message_format(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, desc_set); - insert_u8(&serializer, desc_set); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &desc_set); + + microstrain_extract_u8(&deserializer, &desc_set); assert(num_descriptors_out); - extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); + microstrain_extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); assert(descriptors_out || (num_descriptors_out == 0)); for(unsigned int i=0; i < *num_descriptors_out; i++) extract_mip_descriptor_rate(&deserializer, &descriptors_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -880,12 +914,13 @@ mip_cmd_result mip_3dm_save_message_format(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, desc_set); - insert_u8(&serializer, desc_set); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_message_format(struct mip_interface* device, uint8_t desc_set) { @@ -894,12 +929,13 @@ mip_cmd_result mip_3dm_load_message_format(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, desc_set); - insert_u8(&serializer, desc_set); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_message_format(struct mip_interface* device, uint8_t desc_set) { @@ -908,18 +944,19 @@ mip_cmd_result mip_3dm_default_message_format(struct mip_interface* device, uint mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, desc_set); - insert_u8(&serializer, desc_set); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_nmea_poll_data_command(mip_serializer* serializer, const mip_3dm_nmea_poll_data_command* self) { - insert_bool(serializer, self->suppress_ack); - - insert_u8(serializer, self->count); + microstrain_insert_bool(serializer, self->suppress_ack); + + microstrain_insert_u8(serializer, self->count); for(unsigned int i=0; i < self->count; i++) @@ -928,10 +965,10 @@ void insert_mip_3dm_nmea_poll_data_command(mip_serializer* serializer, const mip } void extract_mip_3dm_nmea_poll_data_command(mip_serializer* serializer, mip_3dm_nmea_poll_data_command* self) { - extract_bool(serializer, &self->suppress_ack); + microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->count); - extract_count(serializer, &self->count, sizeof(self->format_entries)/sizeof(self->format_entries[0])); + microstrain_extract_count(serializer, &self->count, sizeof(self->format_entries) / sizeof(self->format_entries[0])); for(unsigned int i=0; i < self->count; i++) extract_mip_nmea_message(serializer, &self->format_entries[i]); @@ -943,18 +980,19 @@ mip_cmd_result mip_3dm_nmea_poll_data(struct mip_interface* device, bool suppres mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_bool(&serializer, suppress_ack); - - insert_u8(&serializer, count); + + microstrain_insert_bool(&serializer, suppress_ack); + + microstrain_insert_u8(&serializer, count); assert(format_entries || (count == 0)); for(unsigned int i=0; i < count; i++) insert_mip_nmea_message(&serializer, &format_entries[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_NMEA_MESSAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_NMEA_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_nmea_message_format_command(mip_serializer* serializer, const mip_3dm_nmea_message_format_command* self) { @@ -962,7 +1000,7 @@ void insert_mip_3dm_nmea_message_format_command(mip_serializer* serializer, cons if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->count); + microstrain_insert_u8(serializer, self->count); for(unsigned int i=0; i < self->count; i++) @@ -977,7 +1015,8 @@ void extract_mip_3dm_nmea_message_format_command(mip_serializer* serializer, mip if( self->function == MIP_FUNCTION_WRITE ) { assert(self->count); - extract_count(serializer, &self->count, sizeof(self->format_entries)/sizeof(self->format_entries[0])); + microstrain_extract_count(serializer, &self->count, + sizeof(self->format_entries) / sizeof(self->format_entries[0])); for(unsigned int i=0; i < self->count; i++) extract_mip_nmea_message(serializer, &self->format_entries[i]); @@ -987,7 +1026,7 @@ void extract_mip_3dm_nmea_message_format_command(mip_serializer* serializer, mip void insert_mip_3dm_nmea_message_format_response(mip_serializer* serializer, const mip_3dm_nmea_message_format_response* self) { - insert_u8(serializer, self->count); + microstrain_insert_u8(serializer, self->count); for(unsigned int i=0; i < self->count; i++) @@ -997,7 +1036,7 @@ void insert_mip_3dm_nmea_message_format_response(mip_serializer* serializer, con void extract_mip_3dm_nmea_message_format_response(mip_serializer* serializer, mip_3dm_nmea_message_format_response* self) { assert(self->count); - extract_count(serializer, &self->count, sizeof(self->format_entries)/sizeof(self->format_entries[0])); + microstrain_extract_count(serializer, &self->count, sizeof(self->format_entries) / sizeof(self->format_entries[0])); for(unsigned int i=0; i < self->count; i++) extract_mip_nmea_message(serializer, &self->format_entries[i]); @@ -1011,16 +1050,17 @@ mip_cmd_result mip_3dm_write_nmea_message_format(struct mip_interface* device, u mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, count); + + microstrain_insert_u8(&serializer, count); assert(format_entries || (count == 0)); for(unsigned int i=0; i < count; i++) insert_mip_nmea_message(&serializer, &format_entries[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, uint8_t* count_out, uint8_t count_out_max, mip_nmea_message* format_entries_out) { @@ -1030,10 +1070,11 @@ mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, ui insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1041,13 +1082,13 @@ mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, ui mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(count_out); - extract_count(&deserializer, count_out, count_out_max); + microstrain_extract_count(&deserializer, count_out, count_out_max); assert(format_entries_out || (count_out == 0)); for(unsigned int i=0; i < *count_out; i++) extract_mip_nmea_message(&deserializer, &format_entries_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1060,9 +1101,10 @@ mip_cmd_result mip_3dm_save_nmea_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_nmea_message_format(struct mip_interface* device) { @@ -1072,9 +1114,10 @@ mip_cmd_result mip_3dm_load_nmea_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_nmea_message_format(struct mip_interface* device) { @@ -1084,9 +1127,10 @@ mip_cmd_result mip_3dm_default_nmea_message_format(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_device_settings_command(mip_serializer* serializer, const mip_3dm_device_settings_command* self) { @@ -1107,9 +1151,10 @@ mip_cmd_result mip_3dm_save_device_settings(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_device_settings(struct mip_interface* device) { @@ -1119,9 +1164,10 @@ mip_cmd_result mip_3dm_load_device_settings(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_device_settings(struct mip_interface* device) { @@ -1131,9 +1177,10 @@ mip_cmd_result mip_3dm_default_device_settings(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_uart_baudrate_command(mip_serializer* serializer, const mip_3dm_uart_baudrate_command* self) { @@ -1141,7 +1188,7 @@ void insert_mip_3dm_uart_baudrate_command(mip_serializer* serializer, const mip_ if( self->function == MIP_FUNCTION_WRITE ) { - insert_u32(serializer, self->baud); + microstrain_insert_u32(serializer, self->baud); } } @@ -1151,19 +1198,19 @@ void extract_mip_3dm_uart_baudrate_command(mip_serializer* serializer, mip_3dm_u if( self->function == MIP_FUNCTION_WRITE ) { - extract_u32(serializer, &self->baud); + microstrain_extract_u32(serializer, &self->baud); } } void insert_mip_3dm_uart_baudrate_response(mip_serializer* serializer, const mip_3dm_uart_baudrate_response* self) { - insert_u32(serializer, self->baud); + microstrain_insert_u32(serializer, self->baud); } void extract_mip_3dm_uart_baudrate_response(mip_serializer* serializer, mip_3dm_uart_baudrate_response* self) { - extract_u32(serializer, &self->baud); + microstrain_extract_u32(serializer, &self->baud); } @@ -1174,12 +1221,13 @@ mip_cmd_result mip_3dm_write_uart_baudrate(struct mip_interface* device, uint32_ mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u32(&serializer, baud); - insert_u32(&serializer, baud); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t* baud_out) { @@ -1189,10 +1237,11 @@ mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_UART_BAUDRATE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_UART_BAUDRATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1200,9 +1249,9 @@ mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(baud_out); - extract_u32(&deserializer, baud_out); + microstrain_extract_u32(&deserializer, baud_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1215,9 +1264,10 @@ mip_cmd_result mip_3dm_save_uart_baudrate(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_uart_baudrate(struct mip_interface* device) { @@ -1227,9 +1277,10 @@ mip_cmd_result mip_3dm_load_uart_baudrate(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_uart_baudrate(struct mip_interface* device) { @@ -1239,33 +1290,34 @@ mip_cmd_result mip_3dm_default_uart_baudrate(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_factory_streaming_command(mip_serializer* serializer, const mip_3dm_factory_streaming_command* self) { insert_mip_3dm_factory_streaming_command_action(serializer, self->action); - - insert_u8(serializer, self->reserved); + + microstrain_insert_u8(serializer, self->reserved); } void extract_mip_3dm_factory_streaming_command(mip_serializer* serializer, mip_3dm_factory_streaming_command* self) { extract_mip_3dm_factory_streaming_command_action(serializer, &self->action); - - extract_u8(serializer, &self->reserved); + + microstrain_extract_u8(serializer, &self->reserved); } void insert_mip_3dm_factory_streaming_command_action(struct mip_serializer* serializer, const mip_3dm_factory_streaming_command_action self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_factory_streaming_command_action(struct mip_serializer* serializer, mip_3dm_factory_streaming_command_action* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -1276,50 +1328,51 @@ mip_cmd_result mip_3dm_factory_streaming(struct mip_interface* device, mip_3dm_f mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_3dm_factory_streaming_command_action(&serializer, action); + + microstrain_insert_u8(&serializer, reserved); - insert_u8(&serializer, reserved); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_datastream_control_command(mip_serializer* serializer, const mip_3dm_datastream_control_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->desc_set); + + microstrain_insert_u8(serializer, self->desc_set); if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->enable); + microstrain_insert_bool(serializer, self->enable); } } void extract_mip_3dm_datastream_control_command(mip_serializer* serializer, mip_3dm_datastream_control_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->desc_set); + + microstrain_extract_u8(serializer, &self->desc_set); if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->enable); + microstrain_extract_bool(serializer, &self->enable); } } void insert_mip_3dm_datastream_control_response(mip_serializer* serializer, const mip_3dm_datastream_control_response* self) { - insert_u8(serializer, self->desc_set); - - insert_bool(serializer, self->enabled); + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_bool(serializer, self->enabled); } void extract_mip_3dm_datastream_control_response(mip_serializer* serializer, mip_3dm_datastream_control_response* self) { - extract_u8(serializer, &self->desc_set); - - extract_bool(serializer, &self->enabled); + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_bool(serializer, &self->enabled); } @@ -1330,14 +1383,15 @@ mip_cmd_result mip_3dm_write_datastream_control(struct mip_interface* device, ui mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, desc_set); + + microstrain_insert_bool(&serializer, enable); - insert_u8(&serializer, desc_set); - - insert_bool(&serializer, enable); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_datastream_control(struct mip_interface* device, uint8_t desc_set, bool* enabled_out) { @@ -1346,25 +1400,26 @@ mip_cmd_result mip_3dm_read_datastream_control(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, desc_set); - insert_u8(&serializer, desc_set); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_DATASTREAM_ENABLE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_DATASTREAM_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &desc_set); + + microstrain_extract_u8(&deserializer, &desc_set); assert(enabled_out); - extract_bool(&deserializer, enabled_out); + microstrain_extract_bool(&deserializer, enabled_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1376,12 +1431,13 @@ mip_cmd_result mip_3dm_save_datastream_control(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, desc_set); - insert_u8(&serializer, desc_set); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_datastream_control(struct mip_interface* device, uint8_t desc_set) { @@ -1390,12 +1446,13 @@ mip_cmd_result mip_3dm_load_datastream_control(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, desc_set); - insert_u8(&serializer, desc_set); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_datastream_control(struct mip_interface* device, uint8_t desc_set) { @@ -1404,12 +1461,13 @@ mip_cmd_result mip_3dm_default_datastream_control(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, desc_set); - insert_u8(&serializer, desc_set); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_constellation_settings_command(mip_serializer* serializer, const mip_3dm_constellation_settings_command* self) { @@ -1417,9 +1475,9 @@ void insert_mip_3dm_constellation_settings_command(mip_serializer* serializer, c if( self->function == MIP_FUNCTION_WRITE ) { - insert_u16(serializer, self->max_channels); - - insert_u8(serializer, self->config_count); + microstrain_insert_u16(serializer, self->max_channels); + + microstrain_insert_u8(serializer, self->config_count); for(unsigned int i=0; i < self->config_count; i++) @@ -1433,10 +1491,10 @@ void extract_mip_3dm_constellation_settings_command(mip_serializer* serializer, if( self->function == MIP_FUNCTION_WRITE ) { - extract_u16(serializer, &self->max_channels); + microstrain_extract_u16(serializer, &self->max_channels); assert(self->config_count); - extract_count(serializer, &self->config_count, sizeof(self->settings)/sizeof(self->settings[0])); + microstrain_extract_count(serializer, &self->config_count, sizeof(self->settings) / sizeof(self->settings[0])); for(unsigned int i=0; i < self->config_count; i++) extract_mip_3dm_constellation_settings_command_settings(serializer, &self->settings[i]); @@ -1446,11 +1504,11 @@ void extract_mip_3dm_constellation_settings_command(mip_serializer* serializer, void insert_mip_3dm_constellation_settings_response(mip_serializer* serializer, const mip_3dm_constellation_settings_response* self) { - insert_u16(serializer, self->max_channels_available); - - insert_u16(serializer, self->max_channels_use); - - insert_u8(serializer, self->config_count); + microstrain_insert_u16(serializer, self->max_channels_available); + + microstrain_insert_u16(serializer, self->max_channels_use); + + microstrain_insert_u8(serializer, self->config_count); for(unsigned int i=0; i < self->config_count; i++) @@ -1459,12 +1517,12 @@ void insert_mip_3dm_constellation_settings_response(mip_serializer* serializer, } void extract_mip_3dm_constellation_settings_response(mip_serializer* serializer, mip_3dm_constellation_settings_response* self) { - extract_u16(serializer, &self->max_channels_available); - - extract_u16(serializer, &self->max_channels_use); + microstrain_extract_u16(serializer, &self->max_channels_available); + + microstrain_extract_u16(serializer, &self->max_channels_use); assert(self->config_count); - extract_count(serializer, &self->config_count, sizeof(self->settings)/sizeof(self->settings[0])); + microstrain_extract_count(serializer, &self->config_count, sizeof(self->settings) / sizeof(self->settings[0])); for(unsigned int i=0; i < self->config_count; i++) extract_mip_3dm_constellation_settings_command_settings(serializer, &self->settings[i]); @@ -1473,35 +1531,35 @@ void extract_mip_3dm_constellation_settings_response(mip_serializer* serializer, void insert_mip_3dm_constellation_settings_command_constellation_id(struct mip_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_constellation_settings_command_constellation_id(struct mip_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_3dm_constellation_settings_command_option_flags(struct mip_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_3dm_constellation_settings_command_option_flags(struct mip_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_3dm_constellation_settings_command_settings(mip_serializer* serializer, const mip_3dm_constellation_settings_command_settings* self) { insert_mip_3dm_constellation_settings_command_constellation_id(serializer, self->constellation_id); - - insert_u8(serializer, self->enable); - - insert_u8(serializer, self->reserved_channels); - - insert_u8(serializer, self->max_channels); + + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_u8(serializer, self->reserved_channels); + + microstrain_insert_u8(serializer, self->max_channels); insert_mip_3dm_constellation_settings_command_option_flags(serializer, self->option_flags); @@ -1509,12 +1567,12 @@ void insert_mip_3dm_constellation_settings_command_settings(mip_serializer* seri void extract_mip_3dm_constellation_settings_command_settings(mip_serializer* serializer, mip_3dm_constellation_settings_command_settings* self) { extract_mip_3dm_constellation_settings_command_constellation_id(serializer, &self->constellation_id); - - extract_u8(serializer, &self->enable); - - extract_u8(serializer, &self->reserved_channels); - - extract_u8(serializer, &self->max_channels); + + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_u8(serializer, &self->reserved_channels); + + microstrain_extract_u8(serializer, &self->max_channels); extract_mip_3dm_constellation_settings_command_option_flags(serializer, &self->option_flags); @@ -1527,18 +1585,19 @@ mip_cmd_result mip_3dm_write_constellation_settings(struct mip_interface* device mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u16(&serializer, max_channels); - - insert_u8(&serializer, config_count); + + microstrain_insert_u16(&serializer, max_channels); + + microstrain_insert_u8(&serializer, config_count); assert(settings || (config_count == 0)); for(unsigned int i=0; i < config_count; i++) insert_mip_3dm_constellation_settings_command_settings(&serializer, &settings[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, uint16_t* max_channels_available_out, uint16_t* max_channels_use_out, uint8_t* config_count_out, uint8_t config_count_out_max, mip_3dm_constellation_settings_command_settings* settings_out) { @@ -1548,10 +1607,11 @@ mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1559,19 +1619,19 @@ mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(max_channels_available_out); - extract_u16(&deserializer, max_channels_available_out); + microstrain_extract_u16(&deserializer, max_channels_available_out); assert(max_channels_use_out); - extract_u16(&deserializer, max_channels_use_out); + microstrain_extract_u16(&deserializer, max_channels_use_out); assert(config_count_out); - extract_count(&deserializer, config_count_out, config_count_out_max); + microstrain_extract_count(&deserializer, config_count_out, config_count_out_max); assert(settings_out || (config_count_out == 0)); for(unsigned int i=0; i < *config_count_out; i++) extract_mip_3dm_constellation_settings_command_settings(&deserializer, &settings_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1584,9 +1644,10 @@ mip_cmd_result mip_3dm_save_constellation_settings(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_constellation_settings(struct mip_interface* device) { @@ -1596,9 +1657,10 @@ mip_cmd_result mip_3dm_load_constellation_settings(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_constellation_settings(struct mip_interface* device) { @@ -1608,9 +1670,10 @@ mip_cmd_result mip_3dm_default_constellation_settings(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_gnss_sbas_settings_command(mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_command* self) { @@ -1618,15 +1681,15 @@ void insert_mip_3dm_gnss_sbas_settings_command(mip_serializer* serializer, const if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable_sbas); + microstrain_insert_u8(serializer, self->enable_sbas); insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, self->sbas_options); - - insert_u8(serializer, self->num_included_prns); + + microstrain_insert_u8(serializer, self->num_included_prns); for(unsigned int i=0; i < self->num_included_prns; i++) - insert_u16(serializer, self->included_prns[i]); + microstrain_insert_u16(serializer, self->included_prns[i]); } } @@ -1636,54 +1699,56 @@ void extract_mip_3dm_gnss_sbas_settings_command(mip_serializer* serializer, mip_ if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable_sbas); + microstrain_extract_u8(serializer, &self->enable_sbas); extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, &self->sbas_options); assert(self->num_included_prns); - extract_count(serializer, &self->num_included_prns, sizeof(self->included_prns)/sizeof(self->included_prns[0])); + microstrain_extract_count(serializer, &self->num_included_prns, + sizeof(self->included_prns) / sizeof(self->included_prns[0])); for(unsigned int i=0; i < self->num_included_prns; i++) - extract_u16(serializer, &self->included_prns[i]); + microstrain_extract_u16(serializer, &self->included_prns[i]); } } void insert_mip_3dm_gnss_sbas_settings_response(mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_response* self) { - insert_u8(serializer, self->enable_sbas); + microstrain_insert_u8(serializer, self->enable_sbas); insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, self->sbas_options); - - insert_u8(serializer, self->num_included_prns); + + microstrain_insert_u8(serializer, self->num_included_prns); for(unsigned int i=0; i < self->num_included_prns; i++) - insert_u16(serializer, self->included_prns[i]); + microstrain_insert_u16(serializer, self->included_prns[i]); } void extract_mip_3dm_gnss_sbas_settings_response(mip_serializer* serializer, mip_3dm_gnss_sbas_settings_response* self) { - extract_u8(serializer, &self->enable_sbas); + microstrain_extract_u8(serializer, &self->enable_sbas); extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, &self->sbas_options); assert(self->num_included_prns); - extract_count(serializer, &self->num_included_prns, sizeof(self->included_prns)/sizeof(self->included_prns[0])); + microstrain_extract_count(serializer, &self->num_included_prns, + sizeof(self->included_prns) / sizeof(self->included_prns[0])); for(unsigned int i=0; i < self->num_included_prns; i++) - extract_u16(serializer, &self->included_prns[i]); + microstrain_extract_u16(serializer, &self->included_prns[i]); } void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct mip_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -1694,20 +1759,21 @@ mip_cmd_result mip_3dm_write_gnss_sbas_settings(struct mip_interface* device, ui mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, enable_sbas); + + microstrain_insert_u8(&serializer, enable_sbas); insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(&serializer, sbas_options); - - insert_u8(&serializer, num_included_prns); + + microstrain_insert_u8(&serializer, num_included_prns); assert(included_prns || (num_included_prns == 0)); for(unsigned int i=0; i < num_included_prns; i++) - insert_u16(&serializer, included_prns[i]); + microstrain_insert_u16(&serializer, included_prns[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uint8_t* enable_sbas_out, mip_3dm_gnss_sbas_settings_command_sbasoptions* sbas_options_out, uint8_t* num_included_prns_out, uint8_t num_included_prns_out_max, uint16_t* included_prns_out) { @@ -1717,10 +1783,11 @@ mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uin insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1728,19 +1795,19 @@ mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uin mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_sbas_out); - extract_u8(&deserializer, enable_sbas_out); + microstrain_extract_u8(&deserializer, enable_sbas_out); assert(sbas_options_out); extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(&deserializer, sbas_options_out); assert(num_included_prns_out); - extract_count(&deserializer, num_included_prns_out, num_included_prns_out_max); + microstrain_extract_count(&deserializer, num_included_prns_out, num_included_prns_out_max); assert(included_prns_out || (num_included_prns_out == 0)); for(unsigned int i=0; i < *num_included_prns_out; i++) - extract_u16(&deserializer, &included_prns_out[i]); + microstrain_extract_u16(&deserializer, &included_prns_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1753,9 +1820,10 @@ mip_cmd_result mip_3dm_save_gnss_sbas_settings(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_gnss_sbas_settings(struct mip_interface* device) { @@ -1765,9 +1833,10 @@ mip_cmd_result mip_3dm_load_gnss_sbas_settings(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_gnss_sbas_settings(struct mip_interface* device) { @@ -1777,9 +1846,10 @@ mip_cmd_result mip_3dm_default_gnss_sbas_settings(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_command* self) { @@ -1788,8 +1858,8 @@ void insert_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, const if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, self->option); - - insert_u8(serializer, self->flags); + + microstrain_insert_u8(serializer, self->flags); } } @@ -1800,8 +1870,8 @@ void extract_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, mip_3 if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, &self->option); - - extract_u8(serializer, &self->flags); + + microstrain_extract_u8(serializer, &self->flags); } } @@ -1809,26 +1879,26 @@ void extract_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, mip_3 void insert_mip_3dm_gnss_assisted_fix_response(mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_response* self) { insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, self->option); - - insert_u8(serializer, self->flags); + + microstrain_insert_u8(serializer, self->flags); } void extract_mip_3dm_gnss_assisted_fix_response(mip_serializer* serializer, mip_3dm_gnss_assisted_fix_response* self) { extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, &self->option); - - extract_u8(serializer, &self->flags); + + microstrain_extract_u8(serializer, &self->flags); } void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct mip_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -1841,12 +1911,13 @@ mip_cmd_result mip_3dm_write_gnss_assisted_fix(struct mip_interface* device, mip insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(&serializer, option); + + microstrain_insert_u8(&serializer, flags); - insert_u8(&serializer, flags); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* option_out, uint8_t* flags_out) { @@ -1856,10 +1927,11 @@ mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_ insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1870,9 +1942,9 @@ mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_ extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(&deserializer, option_out); assert(flags_out); - extract_u8(&deserializer, flags_out); + microstrain_extract_u8(&deserializer, flags_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1885,9 +1957,10 @@ mip_cmd_result mip_3dm_save_gnss_assisted_fix(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_gnss_assisted_fix(struct mip_interface* device) { @@ -1897,9 +1970,10 @@ mip_cmd_result mip_3dm_load_gnss_assisted_fix(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_gnss_assisted_fix(struct mip_interface* device) { @@ -1909,9 +1983,10 @@ mip_cmd_result mip_3dm_default_gnss_assisted_fix(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_gnss_time_assistance_command(mip_serializer* serializer, const mip_3dm_gnss_time_assistance_command* self) { @@ -1919,11 +1994,11 @@ void insert_mip_3dm_gnss_time_assistance_command(mip_serializer* serializer, con if( self->function == MIP_FUNCTION_WRITE ) { - insert_double(serializer, self->tow); - - insert_u16(serializer, self->week_number); - - insert_float(serializer, self->accuracy); + microstrain_insert_double(serializer, self->tow); + + microstrain_insert_u16(serializer, self->week_number); + + microstrain_insert_float(serializer, self->accuracy); } } @@ -1933,31 +2008,31 @@ void extract_mip_3dm_gnss_time_assistance_command(mip_serializer* serializer, mi if( self->function == MIP_FUNCTION_WRITE ) { - extract_double(serializer, &self->tow); - - extract_u16(serializer, &self->week_number); - - extract_float(serializer, &self->accuracy); + microstrain_extract_double(serializer, &self->tow); + + microstrain_extract_u16(serializer, &self->week_number); + + microstrain_extract_float(serializer, &self->accuracy); } } void insert_mip_3dm_gnss_time_assistance_response(mip_serializer* serializer, const mip_3dm_gnss_time_assistance_response* self) { - insert_double(serializer, self->tow); - - insert_u16(serializer, self->week_number); - - insert_float(serializer, self->accuracy); + microstrain_insert_double(serializer, self->tow); + + microstrain_insert_u16(serializer, self->week_number); + + microstrain_insert_float(serializer, self->accuracy); } void extract_mip_3dm_gnss_time_assistance_response(mip_serializer* serializer, mip_3dm_gnss_time_assistance_response* self) { - extract_double(serializer, &self->tow); - - extract_u16(serializer, &self->week_number); - - extract_float(serializer, &self->accuracy); + microstrain_extract_double(serializer, &self->tow); + + microstrain_extract_u16(serializer, &self->week_number); + + microstrain_extract_float(serializer, &self->accuracy); } @@ -1968,16 +2043,17 @@ mip_cmd_result mip_3dm_write_gnss_time_assistance(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_double(&serializer, tow); + + microstrain_insert_u16(&serializer, week_number); + + microstrain_insert_float(&serializer, accuracy); - insert_double(&serializer, tow); - - insert_u16(&serializer, week_number); - - insert_float(&serializer, accuracy); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, double* tow_out, uint16_t* week_number_out, float* accuracy_out) { @@ -1987,10 +2063,11 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1998,15 +2075,15 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(tow_out); - extract_double(&deserializer, tow_out); + microstrain_extract_double(&deserializer, tow_out); assert(week_number_out); - extract_u16(&deserializer, week_number_out); + microstrain_extract_u16(&deserializer, week_number_out); assert(accuracy_out); - extract_float(&deserializer, accuracy_out); + microstrain_extract_float(&deserializer, accuracy_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2014,64 +2091,64 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d void insert_mip_3dm_imu_lowpass_filter_command(mip_serializer* serializer, const mip_3dm_imu_lowpass_filter_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->target_descriptor); + + microstrain_insert_u8(serializer, self->target_descriptor); if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->enable); - - insert_bool(serializer, self->manual); - - insert_u16(serializer, self->frequency); - - insert_u8(serializer, self->reserved); + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_bool(serializer, self->manual); + + microstrain_insert_u16(serializer, self->frequency); + + microstrain_insert_u8(serializer, self->reserved); } } void extract_mip_3dm_imu_lowpass_filter_command(mip_serializer* serializer, mip_3dm_imu_lowpass_filter_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->target_descriptor); + + microstrain_extract_u8(serializer, &self->target_descriptor); if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->enable); - - extract_bool(serializer, &self->manual); - - extract_u16(serializer, &self->frequency); - - extract_u8(serializer, &self->reserved); + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_bool(serializer, &self->manual); + + microstrain_extract_u16(serializer, &self->frequency); + + microstrain_extract_u8(serializer, &self->reserved); } } void insert_mip_3dm_imu_lowpass_filter_response(mip_serializer* serializer, const mip_3dm_imu_lowpass_filter_response* self) { - insert_u8(serializer, self->target_descriptor); - - insert_bool(serializer, self->enable); - - insert_bool(serializer, self->manual); - - insert_u16(serializer, self->frequency); - - insert_u8(serializer, self->reserved); + microstrain_insert_u8(serializer, self->target_descriptor); + + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_bool(serializer, self->manual); + + microstrain_insert_u16(serializer, self->frequency); + + microstrain_insert_u8(serializer, self->reserved); } void extract_mip_3dm_imu_lowpass_filter_response(mip_serializer* serializer, mip_3dm_imu_lowpass_filter_response* self) { - extract_u8(serializer, &self->target_descriptor); - - extract_bool(serializer, &self->enable); - - extract_bool(serializer, &self->manual); - - extract_u16(serializer, &self->frequency); - - extract_u8(serializer, &self->reserved); + microstrain_extract_u8(serializer, &self->target_descriptor); + + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_bool(serializer, &self->manual); + + microstrain_extract_u16(serializer, &self->frequency); + + microstrain_extract_u8(serializer, &self->reserved); } @@ -2082,20 +2159,21 @@ mip_cmd_result mip_3dm_write_imu_lowpass_filter(struct mip_interface* device, ui mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, target_descriptor); + + microstrain_insert_bool(&serializer, enable); + + microstrain_insert_bool(&serializer, manual); + + microstrain_insert_u16(&serializer, frequency); + + microstrain_insert_u8(&serializer, reserved); - insert_u8(&serializer, target_descriptor); - - insert_bool(&serializer, enable); - - insert_bool(&serializer, manual); - - insert_u16(&serializer, frequency); - - insert_u8(&serializer, reserved); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor, bool* enable_out, bool* manual_out, uint16_t* frequency_out, uint8_t* reserved_out) { @@ -2104,34 +2182,35 @@ mip_cmd_result mip_3dm_read_imu_lowpass_filter(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, target_descriptor); - insert_u8(&serializer, target_descriptor); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_ADVANCED_DATA_FILTER, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_ADVANCED_DATA_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &target_descriptor); + + microstrain_extract_u8(&deserializer, &target_descriptor); assert(enable_out); - extract_bool(&deserializer, enable_out); + microstrain_extract_bool(&deserializer, enable_out); assert(manual_out); - extract_bool(&deserializer, manual_out); + microstrain_extract_bool(&deserializer, manual_out); assert(frequency_out); - extract_u16(&deserializer, frequency_out); + microstrain_extract_u16(&deserializer, frequency_out); assert(reserved_out); - extract_u8(&deserializer, reserved_out); + microstrain_extract_u8(&deserializer, reserved_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2143,12 +2222,13 @@ mip_cmd_result mip_3dm_save_imu_lowpass_filter(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, target_descriptor); - insert_u8(&serializer, target_descriptor); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) { @@ -2157,12 +2237,13 @@ mip_cmd_result mip_3dm_load_imu_lowpass_filter(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, target_descriptor); - insert_u8(&serializer, target_descriptor); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) { @@ -2171,12 +2252,13 @@ mip_cmd_result mip_3dm_default_imu_lowpass_filter(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, target_descriptor); - insert_u8(&serializer, target_descriptor); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_pps_source_command(mip_serializer* serializer, const mip_3dm_pps_source_command* self) { @@ -2212,12 +2294,12 @@ void extract_mip_3dm_pps_source_response(mip_serializer* serializer, mip_3dm_pps void insert_mip_3dm_pps_source_command_source(struct mip_serializer* serializer, const mip_3dm_pps_source_command_source self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_pps_source_command_source(struct mip_serializer* serializer, mip_3dm_pps_source_command_source* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -2231,9 +2313,10 @@ mip_cmd_result mip_3dm_write_pps_source(struct mip_interface* device, mip_3dm_pp insert_mip_3dm_pps_source_command_source(&serializer, source); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps_source_command_source* source_out) { @@ -2243,10 +2326,11 @@ mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_PPS_SOURCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_PPS_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2256,7 +2340,7 @@ mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps assert(source_out); extract_mip_3dm_pps_source_command_source(&deserializer, source_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2269,9 +2353,10 @@ mip_cmd_result mip_3dm_save_pps_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_pps_source(struct mip_interface* device) { @@ -2281,9 +2366,10 @@ mip_cmd_result mip_3dm_load_pps_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_pps_source(struct mip_interface* device) { @@ -2293,15 +2379,16 @@ mip_cmd_result mip_3dm_default_pps_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_gpio_config_command(mip_serializer* serializer, const mip_3dm_gpio_config_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->pin); + + microstrain_insert_u8(serializer, self->pin); if( self->function == MIP_FUNCTION_WRITE ) { @@ -2316,8 +2403,8 @@ void insert_mip_3dm_gpio_config_command(mip_serializer* serializer, const mip_3d void extract_mip_3dm_gpio_config_command(mip_serializer* serializer, mip_3dm_gpio_config_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->pin); + + microstrain_extract_u8(serializer, &self->pin); if( self->function == MIP_FUNCTION_WRITE ) { @@ -2332,7 +2419,7 @@ void extract_mip_3dm_gpio_config_command(mip_serializer* serializer, mip_3dm_gpi void insert_mip_3dm_gpio_config_response(mip_serializer* serializer, const mip_3dm_gpio_config_response* self) { - insert_u8(serializer, self->pin); + microstrain_insert_u8(serializer, self->pin); insert_mip_3dm_gpio_config_command_feature(serializer, self->feature); @@ -2343,7 +2430,7 @@ void insert_mip_3dm_gpio_config_response(mip_serializer* serializer, const mip_3 } void extract_mip_3dm_gpio_config_response(mip_serializer* serializer, mip_3dm_gpio_config_response* self) { - extract_u8(serializer, &self->pin); + microstrain_extract_u8(serializer, &self->pin); extract_mip_3dm_gpio_config_command_feature(serializer, &self->feature); @@ -2355,34 +2442,34 @@ void extract_mip_3dm_gpio_config_response(mip_serializer* serializer, mip_3dm_gp void insert_mip_3dm_gpio_config_command_feature(struct mip_serializer* serializer, const mip_3dm_gpio_config_command_feature self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_gpio_config_command_feature(struct mip_serializer* serializer, mip_3dm_gpio_config_command_feature* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_3dm_gpio_config_command_behavior(struct mip_serializer* serializer, const mip_3dm_gpio_config_command_behavior self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_gpio_config_command_behavior(struct mip_serializer* serializer, mip_3dm_gpio_config_command_behavior* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_3dm_gpio_config_command_pin_mode(struct mip_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_gpio_config_command_pin_mode(struct mip_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -2393,8 +2480,8 @@ mip_cmd_result mip_3dm_write_gpio_config(struct mip_interface* device, uint8_t p mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, pin); + + microstrain_insert_u8(&serializer, pin); insert_mip_3dm_gpio_config_command_feature(&serializer, feature); @@ -2402,9 +2489,10 @@ mip_cmd_result mip_3dm_write_gpio_config(struct mip_interface* device, uint8_t p insert_mip_3dm_gpio_config_command_pin_mode(&serializer, pin_mode); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature* feature_out, mip_3dm_gpio_config_command_behavior* behavior_out, mip_3dm_gpio_config_command_pin_mode* pin_mode_out) { @@ -2413,20 +2501,21 @@ mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pi mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, pin); - insert_u8(&serializer, pin); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GPIO_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_GPIO_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &pin); + + microstrain_extract_u8(&deserializer, &pin); assert(feature_out); extract_mip_3dm_gpio_config_command_feature(&deserializer, feature_out); @@ -2437,7 +2526,7 @@ mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pi assert(pin_mode_out); extract_mip_3dm_gpio_config_command_pin_mode(&deserializer, pin_mode_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2449,12 +2538,13 @@ mip_cmd_result mip_3dm_save_gpio_config(struct mip_interface* device, uint8_t pi mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, pin); - insert_u8(&serializer, pin); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_gpio_config(struct mip_interface* device, uint8_t pin) { @@ -2463,12 +2553,13 @@ mip_cmd_result mip_3dm_load_gpio_config(struct mip_interface* device, uint8_t pi mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, pin); - insert_u8(&serializer, pin); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_gpio_config(struct mip_interface* device, uint8_t pin) { @@ -2477,12 +2568,13 @@ mip_cmd_result mip_3dm_default_gpio_config(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, pin); - insert_u8(&serializer, pin); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_gpio_state_command(mip_serializer* serializer, const mip_3dm_gpio_state_command* self) { @@ -2490,12 +2582,12 @@ void insert_mip_3dm_gpio_state_command(mip_serializer* serializer, const mip_3dm if( self->function == MIP_FUNCTION_WRITE || self->function == MIP_FUNCTION_READ ) { - insert_u8(serializer, self->pin); + microstrain_insert_u8(serializer, self->pin); } if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->state); + microstrain_insert_bool(serializer, self->state); } } @@ -2505,28 +2597,28 @@ void extract_mip_3dm_gpio_state_command(mip_serializer* serializer, mip_3dm_gpio if( self->function == MIP_FUNCTION_WRITE || self->function == MIP_FUNCTION_READ ) { - extract_u8(serializer, &self->pin); + microstrain_extract_u8(serializer, &self->pin); } if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->state); + microstrain_extract_bool(serializer, &self->state); } } void insert_mip_3dm_gpio_state_response(mip_serializer* serializer, const mip_3dm_gpio_state_response* self) { - insert_u8(serializer, self->pin); - - insert_bool(serializer, self->state); + microstrain_insert_u8(serializer, self->pin); + + microstrain_insert_bool(serializer, self->state); } void extract_mip_3dm_gpio_state_response(mip_serializer* serializer, mip_3dm_gpio_state_response* self) { - extract_u8(serializer, &self->pin); - - extract_bool(serializer, &self->state); + microstrain_extract_u8(serializer, &self->pin); + + microstrain_extract_bool(serializer, &self->state); } @@ -2537,14 +2629,15 @@ mip_cmd_result mip_3dm_write_gpio_state(struct mip_interface* device, uint8_t pi mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, pin); + + microstrain_insert_bool(&serializer, state); - insert_u8(&serializer, pin); - - insert_bool(&serializer, state); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_STATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_STATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_gpio_state(struct mip_interface* device, uint8_t pin, bool* state_out) { @@ -2553,25 +2646,26 @@ mip_cmd_result mip_3dm_read_gpio_state(struct mip_interface* device, uint8_t pin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, pin); - insert_u8(&serializer, pin); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_STATE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GPIO_STATE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_STATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_GPIO_STATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &pin); + + microstrain_extract_u8(&deserializer, &pin); assert(state_out); - extract_bool(&deserializer, state_out); + microstrain_extract_bool(&deserializer, state_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2583,10 +2677,10 @@ void insert_mip_3dm_odometer_command(mip_serializer* serializer, const mip_3dm_o if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_3dm_odometer_command_mode(serializer, self->mode); - - insert_float(serializer, self->scaling); - - insert_float(serializer, self->uncertainty); + + microstrain_insert_float(serializer, self->scaling); + + microstrain_insert_float(serializer, self->uncertainty); } } @@ -2597,10 +2691,10 @@ void extract_mip_3dm_odometer_command(mip_serializer* serializer, mip_3dm_odomet if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_3dm_odometer_command_mode(serializer, &self->mode); - - extract_float(serializer, &self->scaling); - - extract_float(serializer, &self->uncertainty); + + microstrain_extract_float(serializer, &self->scaling); + + microstrain_extract_float(serializer, &self->uncertainty); } } @@ -2608,30 +2702,30 @@ void extract_mip_3dm_odometer_command(mip_serializer* serializer, mip_3dm_odomet void insert_mip_3dm_odometer_response(mip_serializer* serializer, const mip_3dm_odometer_response* self) { insert_mip_3dm_odometer_command_mode(serializer, self->mode); - - insert_float(serializer, self->scaling); - - insert_float(serializer, self->uncertainty); + + microstrain_insert_float(serializer, self->scaling); + + microstrain_insert_float(serializer, self->uncertainty); } void extract_mip_3dm_odometer_response(mip_serializer* serializer, mip_3dm_odometer_response* self) { extract_mip_3dm_odometer_command_mode(serializer, &self->mode); - - extract_float(serializer, &self->scaling); - - extract_float(serializer, &self->uncertainty); + + microstrain_extract_float(serializer, &self->scaling); + + microstrain_extract_float(serializer, &self->uncertainty); } void insert_mip_3dm_odometer_command_mode(struct mip_serializer* serializer, const mip_3dm_odometer_command_mode self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_odometer_command_mode(struct mip_serializer* serializer, mip_3dm_odometer_command_mode* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -2644,14 +2738,15 @@ mip_cmd_result mip_3dm_write_odometer(struct mip_interface* device, mip_3dm_odom insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_3dm_odometer_command_mode(&serializer, mode); + + microstrain_insert_float(&serializer, scaling); + + microstrain_insert_float(&serializer, uncertainty); - insert_float(&serializer, scaling); - - insert_float(&serializer, uncertainty); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odometer_command_mode* mode_out, float* scaling_out, float* uncertainty_out) { @@ -2661,10 +2756,11 @@ mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odome insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_ODOMETER_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_ODOMETER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2675,12 +2771,12 @@ mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odome extract_mip_3dm_odometer_command_mode(&deserializer, mode_out); assert(scaling_out); - extract_float(&deserializer, scaling_out); + microstrain_extract_float(&deserializer, scaling_out); assert(uncertainty_out); - extract_float(&deserializer, uncertainty_out); + microstrain_extract_float(&deserializer, uncertainty_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2693,9 +2789,10 @@ mip_cmd_result mip_3dm_save_odometer(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_odometer(struct mip_interface* device) { @@ -2705,9 +2802,10 @@ mip_cmd_result mip_3dm_load_odometer(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_odometer(struct mip_interface* device) { @@ -2717,9 +2815,10 @@ mip_cmd_result mip_3dm_default_odometer(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_get_event_support_command(mip_serializer* serializer, const mip_3dm_get_event_support_command* self) { @@ -2735,10 +2834,10 @@ void extract_mip_3dm_get_event_support_command(mip_serializer* serializer, mip_3 void insert_mip_3dm_get_event_support_response(mip_serializer* serializer, const mip_3dm_get_event_support_response* self) { insert_mip_3dm_get_event_support_command_query(serializer, self->query); - - insert_u8(serializer, self->max_instances); - - insert_u8(serializer, self->num_entries); + + microstrain_insert_u8(serializer, self->max_instances); + + microstrain_insert_u8(serializer, self->num_entries); for(unsigned int i=0; i < self->num_entries; i++) @@ -2748,11 +2847,11 @@ void insert_mip_3dm_get_event_support_response(mip_serializer* serializer, const void extract_mip_3dm_get_event_support_response(mip_serializer* serializer, mip_3dm_get_event_support_response* self) { extract_mip_3dm_get_event_support_command_query(serializer, &self->query); - - extract_u8(serializer, &self->max_instances); + + microstrain_extract_u8(serializer, &self->max_instances); assert(self->num_entries); - extract_count(serializer, &self->num_entries, sizeof(self->entries)/sizeof(self->entries[0])); + microstrain_extract_count(serializer, &self->num_entries, sizeof(self->entries) / sizeof(self->entries[0])); for(unsigned int i=0; i < self->num_entries; i++) extract_mip_3dm_get_event_support_command_info(serializer, &self->entries[i]); @@ -2761,27 +2860,27 @@ void extract_mip_3dm_get_event_support_response(mip_serializer* serializer, mip_ void insert_mip_3dm_get_event_support_command_query(struct mip_serializer* serializer, const mip_3dm_get_event_support_command_query self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_get_event_support_command_query(struct mip_serializer* serializer, mip_3dm_get_event_support_command_query* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_3dm_get_event_support_command_info(mip_serializer* serializer, const mip_3dm_get_event_support_command_info* self) { - insert_u8(serializer, self->type); - - insert_u8(serializer, self->count); + microstrain_insert_u8(serializer, self->type); + + microstrain_insert_u8(serializer, self->count); } void extract_mip_3dm_get_event_support_command_info(mip_serializer* serializer, mip_3dm_get_event_support_command_info* self) { - extract_u8(serializer, &self->type); - - extract_u8(serializer, &self->count); + microstrain_extract_u8(serializer, &self->type); + + microstrain_extract_u8(serializer, &self->count); } @@ -2793,10 +2892,11 @@ mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_g insert_mip_3dm_get_event_support_command_query(&serializer, query); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_SUPPORT, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_SUPPORT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_SUPPORT, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_EVENT_SUPPORT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2806,16 +2906,16 @@ mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_g extract_mip_3dm_get_event_support_command_query(&deserializer, &query); assert(max_instances_out); - extract_u8(&deserializer, max_instances_out); + microstrain_extract_u8(&deserializer, max_instances_out); assert(num_entries_out); - extract_count(&deserializer, num_entries_out, num_entries_out_max); + microstrain_extract_count(&deserializer, num_entries_out, num_entries_out_max); assert(entries_out || (num_entries_out == 0)); for(unsigned int i=0; i < *num_entries_out; i++) extract_mip_3dm_get_event_support_command_info(&deserializer, &entries_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2823,8 +2923,8 @@ mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_g void insert_mip_3dm_event_control_command(mip_serializer* serializer, const mip_3dm_event_control_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->instance); + + microstrain_insert_u8(serializer, self->instance); if( self->function == MIP_FUNCTION_WRITE ) { @@ -2835,8 +2935,8 @@ void insert_mip_3dm_event_control_command(mip_serializer* serializer, const mip_ void extract_mip_3dm_event_control_command(mip_serializer* serializer, mip_3dm_event_control_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->instance); + + microstrain_extract_u8(serializer, &self->instance); if( self->function == MIP_FUNCTION_WRITE ) { @@ -2847,14 +2947,14 @@ void extract_mip_3dm_event_control_command(mip_serializer* serializer, mip_3dm_e void insert_mip_3dm_event_control_response(mip_serializer* serializer, const mip_3dm_event_control_response* self) { - insert_u8(serializer, self->instance); + microstrain_insert_u8(serializer, self->instance); insert_mip_3dm_event_control_command_mode(serializer, self->mode); } void extract_mip_3dm_event_control_response(mip_serializer* serializer, mip_3dm_event_control_response* self) { - extract_u8(serializer, &self->instance); + microstrain_extract_u8(serializer, &self->instance); extract_mip_3dm_event_control_command_mode(serializer, &self->mode); @@ -2862,12 +2962,12 @@ void extract_mip_3dm_event_control_response(mip_serializer* serializer, mip_3dm_ void insert_mip_3dm_event_control_command_mode(struct mip_serializer* serializer, const mip_3dm_event_control_command_mode self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_event_control_command_mode(struct mip_serializer* serializer, mip_3dm_event_control_command_mode* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -2878,14 +2978,15 @@ mip_cmd_result mip_3dm_write_event_control(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, instance); + + microstrain_insert_u8(&serializer, instance); insert_mip_3dm_event_control_command_mode(&serializer, mode); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_event_control(struct mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode* mode_out) { @@ -2894,25 +2995,26 @@ mip_cmd_result mip_3dm_read_event_control(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_EVENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &instance); + + microstrain_extract_u8(&deserializer, &instance); assert(mode_out); extract_mip_3dm_event_control_command_mode(&deserializer, mode_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2924,12 +3026,13 @@ mip_cmd_result mip_3dm_save_event_control(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_event_control(struct mip_interface* device, uint8_t instance) { @@ -2938,12 +3041,13 @@ mip_cmd_result mip_3dm_load_event_control(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_event_control(struct mip_interface* device, uint8_t instance) { @@ -2952,35 +3056,37 @@ mip_cmd_result mip_3dm_default_event_control(struct mip_interface* device, uint8 mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_get_event_trigger_status_command(mip_serializer* serializer, const mip_3dm_get_event_trigger_status_command* self) { - insert_u8(serializer, self->requested_count); + microstrain_insert_u8(serializer, self->requested_count); for(unsigned int i=0; i < self->requested_count; i++) - insert_u8(serializer, self->requested_instances[i]); + microstrain_insert_u8(serializer, self->requested_instances[i]); } void extract_mip_3dm_get_event_trigger_status_command(mip_serializer* serializer, mip_3dm_get_event_trigger_status_command* self) { assert(self->requested_count); - extract_count(serializer, &self->requested_count, sizeof(self->requested_instances)/sizeof(self->requested_instances[0])); + microstrain_extract_count(serializer, &self->requested_count, + sizeof(self->requested_instances) / sizeof(self->requested_instances[0])); for(unsigned int i=0; i < self->requested_count; i++) - extract_u8(serializer, &self->requested_instances[i]); + microstrain_extract_u8(serializer, &self->requested_instances[i]); } void insert_mip_3dm_get_event_trigger_status_response(mip_serializer* serializer, const mip_3dm_get_event_trigger_status_response* self) { - insert_u8(serializer, self->count); + microstrain_insert_u8(serializer, self->count); for(unsigned int i=0; i < self->count; i++) @@ -2990,7 +3096,7 @@ void insert_mip_3dm_get_event_trigger_status_response(mip_serializer* serializer void extract_mip_3dm_get_event_trigger_status_response(mip_serializer* serializer, mip_3dm_get_event_trigger_status_response* self) { assert(self->count); - extract_count(serializer, &self->count, sizeof(self->triggers)/sizeof(self->triggers[0])); + microstrain_extract_count(serializer, &self->count, sizeof(self->triggers) / sizeof(self->triggers[0])); for(unsigned int i=0; i < self->count; i++) extract_mip_3dm_get_event_trigger_status_command_entry(serializer, &self->triggers[i]); @@ -2999,25 +3105,25 @@ void extract_mip_3dm_get_event_trigger_status_response(mip_serializer* serialize void insert_mip_3dm_get_event_trigger_status_command_status(struct mip_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_get_event_trigger_status_command_status(struct mip_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_3dm_get_event_trigger_status_command_entry(mip_serializer* serializer, const mip_3dm_get_event_trigger_status_command_entry* self) { - insert_u8(serializer, self->type); + microstrain_insert_u8(serializer, self->type); insert_mip_3dm_get_event_trigger_status_command_status(serializer, self->status); } void extract_mip_3dm_get_event_trigger_status_command_entry(mip_serializer* serializer, mip_3dm_get_event_trigger_status_command_entry* self) { - extract_u8(serializer, &self->type); + microstrain_extract_u8(serializer, &self->type); extract_mip_3dm_get_event_trigger_status_command_status(serializer, &self->status); @@ -3028,17 +3134,18 @@ mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, ui mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_u8(&serializer, requested_count); + + microstrain_insert_u8(&serializer, requested_count); assert(requested_instances || (requested_count == 0)); for(unsigned int i=0; i < requested_count; i++) - insert_u8(&serializer, requested_instances[i]); + microstrain_insert_u8(&serializer, requested_instances[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_STATUS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_TRIGGER_STATUS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_STATUS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_EVENT_TRIGGER_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3046,39 +3153,40 @@ mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, ui mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(count_out); - extract_count(&deserializer, count_out, count_out_max); + microstrain_extract_count(&deserializer, count_out, count_out_max); assert(triggers_out || (count_out == 0)); for(unsigned int i=0; i < *count_out; i++) extract_mip_3dm_get_event_trigger_status_command_entry(&deserializer, &triggers_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } void insert_mip_3dm_get_event_action_status_command(mip_serializer* serializer, const mip_3dm_get_event_action_status_command* self) { - insert_u8(serializer, self->requested_count); + microstrain_insert_u8(serializer, self->requested_count); for(unsigned int i=0; i < self->requested_count; i++) - insert_u8(serializer, self->requested_instances[i]); + microstrain_insert_u8(serializer, self->requested_instances[i]); } void extract_mip_3dm_get_event_action_status_command(mip_serializer* serializer, mip_3dm_get_event_action_status_command* self) { assert(self->requested_count); - extract_count(serializer, &self->requested_count, sizeof(self->requested_instances)/sizeof(self->requested_instances[0])); + microstrain_extract_count(serializer, &self->requested_count, + sizeof(self->requested_instances) / sizeof(self->requested_instances[0])); for(unsigned int i=0; i < self->requested_count; i++) - extract_u8(serializer, &self->requested_instances[i]); + microstrain_extract_u8(serializer, &self->requested_instances[i]); } void insert_mip_3dm_get_event_action_status_response(mip_serializer* serializer, const mip_3dm_get_event_action_status_response* self) { - insert_u8(serializer, self->count); + microstrain_insert_u8(serializer, self->count); for(unsigned int i=0; i < self->count; i++) @@ -3088,7 +3196,7 @@ void insert_mip_3dm_get_event_action_status_response(mip_serializer* serializer, void extract_mip_3dm_get_event_action_status_response(mip_serializer* serializer, mip_3dm_get_event_action_status_response* self) { assert(self->count); - extract_count(serializer, &self->count, sizeof(self->actions)/sizeof(self->actions[0])); + microstrain_extract_count(serializer, &self->count, sizeof(self->actions) / sizeof(self->actions[0])); for(unsigned int i=0; i < self->count; i++) extract_mip_3dm_get_event_action_status_command_entry(serializer, &self->actions[i]); @@ -3097,16 +3205,16 @@ void extract_mip_3dm_get_event_action_status_response(mip_serializer* serializer void insert_mip_3dm_get_event_action_status_command_entry(mip_serializer* serializer, const mip_3dm_get_event_action_status_command_entry* self) { - insert_u8(serializer, self->action_type); - - insert_u8(serializer, self->trigger_id); + microstrain_insert_u8(serializer, self->action_type); + + microstrain_insert_u8(serializer, self->trigger_id); } void extract_mip_3dm_get_event_action_status_command_entry(mip_serializer* serializer, mip_3dm_get_event_action_status_command_entry* self) { - extract_u8(serializer, &self->action_type); - - extract_u8(serializer, &self->trigger_id); + microstrain_extract_u8(serializer, &self->action_type); + + microstrain_extract_u8(serializer, &self->trigger_id); } @@ -3115,17 +3223,18 @@ mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uin mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_u8(&serializer, requested_count); + + microstrain_insert_u8(&serializer, requested_count); assert(requested_instances || (requested_count == 0)); for(unsigned int i=0; i < requested_count; i++) - insert_u8(&serializer, requested_instances[i]); + microstrain_insert_u8(&serializer, requested_instances[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_STATUS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_ACTION_STATUS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_STATUS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_EVENT_ACTION_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3133,13 +3242,13 @@ mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uin mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(count_out); - extract_count(&deserializer, count_out, count_out_max); + microstrain_extract_count(&deserializer, count_out, count_out_max); assert(actions_out || (count_out == 0)); for(unsigned int i=0; i < *count_out; i++) extract_mip_3dm_get_event_action_status_command_entry(&deserializer, &actions_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3147,8 +3256,8 @@ mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uin void insert_mip_3dm_event_trigger_command(mip_serializer* serializer, const mip_3dm_event_trigger_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->instance); + + microstrain_insert_u8(serializer, self->instance); if( self->function == MIP_FUNCTION_WRITE ) { @@ -3174,8 +3283,8 @@ void insert_mip_3dm_event_trigger_command(mip_serializer* serializer, const mip_ void extract_mip_3dm_event_trigger_command(mip_serializer* serializer, mip_3dm_event_trigger_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->instance); + + microstrain_extract_u8(serializer, &self->instance); if( self->function == MIP_FUNCTION_WRITE ) { @@ -3201,7 +3310,7 @@ void extract_mip_3dm_event_trigger_command(mip_serializer* serializer, mip_3dm_e void insert_mip_3dm_event_trigger_response(mip_serializer* serializer, const mip_3dm_event_trigger_response* self) { - insert_u8(serializer, self->instance); + microstrain_insert_u8(serializer, self->instance); insert_mip_3dm_event_trigger_command_type(serializer, self->type); @@ -3223,7 +3332,7 @@ void insert_mip_3dm_event_trigger_response(mip_serializer* serializer, const mip } void extract_mip_3dm_event_trigger_response(mip_serializer* serializer, mip_3dm_event_trigger_response* self) { - extract_u8(serializer, &self->instance); + microstrain_extract_u8(serializer, &self->instance); extract_mip_3dm_event_trigger_command_type(serializer, &self->type); @@ -3246,14 +3355,14 @@ void extract_mip_3dm_event_trigger_response(mip_serializer* serializer, mip_3dm_ void insert_mip_3dm_event_trigger_command_gpio_params(mip_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params* self) { - insert_u8(serializer, self->pin); + microstrain_insert_u8(serializer, self->pin); insert_mip_3dm_event_trigger_command_gpio_params_mode(serializer, self->mode); } void extract_mip_3dm_event_trigger_command_gpio_params(mip_serializer* serializer, mip_3dm_event_trigger_command_gpio_params* self) { - extract_u8(serializer, &self->pin); + microstrain_extract_u8(serializer, &self->pin); extract_mip_3dm_event_trigger_command_gpio_params_mode(serializer, &self->mode); @@ -3261,114 +3370,114 @@ void extract_mip_3dm_event_trigger_command_gpio_params(mip_serializer* serialize void insert_mip_3dm_event_trigger_command_gpio_params_mode(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_event_trigger_command_gpio_params_mode(struct mip_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_3dm_event_trigger_command_threshold_params(mip_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params* self) { - insert_u8(serializer, self->desc_set); - - insert_u8(serializer, self->field_desc); - - insert_u8(serializer, self->param_id); + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u8(serializer, self->field_desc); + + microstrain_insert_u8(serializer, self->param_id); insert_mip_3dm_event_trigger_command_threshold_params_type(serializer, self->type); if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) { - insert_double(serializer, self->low_thres); + microstrain_insert_double(serializer, self->low_thres); } if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) { - insert_double(serializer, self->int_thres); + microstrain_insert_double(serializer, self->int_thres); } if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) { - insert_double(serializer, self->high_thres); + microstrain_insert_double(serializer, self->high_thres); } if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) { - insert_double(serializer, self->interval); + microstrain_insert_double(serializer, self->interval); } } void extract_mip_3dm_event_trigger_command_threshold_params(mip_serializer* serializer, mip_3dm_event_trigger_command_threshold_params* self) { - extract_u8(serializer, &self->desc_set); - - extract_u8(serializer, &self->field_desc); - - extract_u8(serializer, &self->param_id); + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_u8(serializer, &self->field_desc); + + microstrain_extract_u8(serializer, &self->param_id); extract_mip_3dm_event_trigger_command_threshold_params_type(serializer, &self->type); if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) { - extract_double(serializer, &self->low_thres); + microstrain_extract_double(serializer, &self->low_thres); } if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) { - extract_double(serializer, &self->int_thres); + microstrain_extract_double(serializer, &self->int_thres); } if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) { - extract_double(serializer, &self->high_thres); + microstrain_extract_double(serializer, &self->high_thres); } if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) { - extract_double(serializer, &self->interval); + microstrain_extract_double(serializer, &self->interval); } } void insert_mip_3dm_event_trigger_command_threshold_params_type(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_event_trigger_command_threshold_params_type(struct mip_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_3dm_event_trigger_command_combination_params(mip_serializer* serializer, const mip_3dm_event_trigger_command_combination_params* self) { - insert_u16(serializer, self->logic_table); + microstrain_insert_u16(serializer, self->logic_table); for(unsigned int i=0; i < 4; i++) - insert_u8(serializer, self->input_triggers[i]); + microstrain_insert_u8(serializer, self->input_triggers[i]); } void extract_mip_3dm_event_trigger_command_combination_params(mip_serializer* serializer, mip_3dm_event_trigger_command_combination_params* self) { - extract_u16(serializer, &self->logic_table); + microstrain_extract_u16(serializer, &self->logic_table); for(unsigned int i=0; i < 4; i++) - extract_u8(serializer, &self->input_triggers[i]); + microstrain_extract_u8(serializer, &self->input_triggers[i]); } void insert_mip_3dm_event_trigger_command_type(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_type self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_event_trigger_command_type(struct mip_serializer* serializer, mip_3dm_event_trigger_command_type* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -3379,8 +3488,8 @@ mip_cmd_result mip_3dm_write_event_trigger(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, instance); + + microstrain_insert_u8(&serializer, instance); insert_mip_3dm_event_trigger_command_type(&serializer, type); @@ -3399,9 +3508,10 @@ mip_cmd_result mip_3dm_write_event_trigger(struct mip_interface* device, uint8_t insert_mip_3dm_event_trigger_command_combination_params(&serializer, ¶meters->combination); } - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type* type_out, mip_3dm_event_trigger_command_parameters* parameters_out) { @@ -3410,20 +3520,21 @@ mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &instance); + + microstrain_extract_u8(&deserializer, &instance); assert(type_out); extract_mip_3dm_event_trigger_command_type(&deserializer, type_out); @@ -3443,7 +3554,7 @@ mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t extract_mip_3dm_event_trigger_command_combination_params(&deserializer, ¶meters_out->combination); } - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3455,12 +3566,13 @@ mip_cmd_result mip_3dm_save_event_trigger(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_event_trigger(struct mip_interface* device, uint8_t instance) { @@ -3469,12 +3581,13 @@ mip_cmd_result mip_3dm_load_event_trigger(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_event_trigger(struct mip_interface* device, uint8_t instance) { @@ -3483,22 +3596,23 @@ mip_cmd_result mip_3dm_default_event_trigger(struct mip_interface* device, uint8 mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_event_action_command(mip_serializer* serializer, const mip_3dm_event_action_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->instance); + + microstrain_insert_u8(serializer, self->instance); if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->trigger); + microstrain_insert_u8(serializer, self->trigger); insert_mip_3dm_event_action_command_type(serializer, self->type); @@ -3517,12 +3631,12 @@ void insert_mip_3dm_event_action_command(mip_serializer* serializer, const mip_3 void extract_mip_3dm_event_action_command(mip_serializer* serializer, mip_3dm_event_action_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->instance); + + microstrain_extract_u8(serializer, &self->instance); if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->trigger); + microstrain_extract_u8(serializer, &self->trigger); extract_mip_3dm_event_action_command_type(serializer, &self->type); @@ -3541,9 +3655,9 @@ void extract_mip_3dm_event_action_command(mip_serializer* serializer, mip_3dm_ev void insert_mip_3dm_event_action_response(mip_serializer* serializer, const mip_3dm_event_action_response* self) { - insert_u8(serializer, self->instance); - - insert_u8(serializer, self->trigger); + microstrain_insert_u8(serializer, self->instance); + + microstrain_insert_u8(serializer, self->trigger); insert_mip_3dm_event_action_command_type(serializer, self->type); @@ -3560,9 +3674,9 @@ void insert_mip_3dm_event_action_response(mip_serializer* serializer, const mip_ } void extract_mip_3dm_event_action_response(mip_serializer* serializer, mip_3dm_event_action_response* self) { - extract_u8(serializer, &self->instance); - - extract_u8(serializer, &self->trigger); + microstrain_extract_u8(serializer, &self->instance); + + microstrain_extract_u8(serializer, &self->trigger); extract_mip_3dm_event_action_command_type(serializer, &self->type); @@ -3580,14 +3694,14 @@ void extract_mip_3dm_event_action_response(mip_serializer* serializer, mip_3dm_e void insert_mip_3dm_event_action_command_gpio_params(mip_serializer* serializer, const mip_3dm_event_action_command_gpio_params* self) { - insert_u8(serializer, self->pin); + microstrain_insert_u8(serializer, self->pin); insert_mip_3dm_event_action_command_gpio_params_mode(serializer, self->mode); } void extract_mip_3dm_event_action_command_gpio_params(mip_serializer* serializer, mip_3dm_event_action_command_gpio_params* self) { - extract_u8(serializer, &self->pin); + microstrain_extract_u8(serializer, &self->pin); extract_mip_3dm_event_action_command_gpio_params_mode(serializer, &self->mode); @@ -3595,50 +3709,50 @@ void extract_mip_3dm_event_action_command_gpio_params(mip_serializer* serializer void insert_mip_3dm_event_action_command_gpio_params_mode(struct mip_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_event_action_command_gpio_params_mode(struct mip_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_3dm_event_action_command_message_params(mip_serializer* serializer, const mip_3dm_event_action_command_message_params* self) { - insert_u8(serializer, self->desc_set); - - insert_u16(serializer, self->decimation); - - insert_u8(serializer, self->num_fields); + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u16(serializer, self->decimation); + + microstrain_insert_u8(serializer, self->num_fields); for(unsigned int i=0; i < self->num_fields; i++) - insert_u8(serializer, self->descriptors[i]); + microstrain_insert_u8(serializer, self->descriptors[i]); } void extract_mip_3dm_event_action_command_message_params(mip_serializer* serializer, mip_3dm_event_action_command_message_params* self) { - extract_u8(serializer, &self->desc_set); - - extract_u16(serializer, &self->decimation); + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_u16(serializer, &self->decimation); assert(self->num_fields); - extract_count(serializer, &self->num_fields, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_fields, sizeof(self->descriptors) / sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_fields; i++) - extract_u8(serializer, &self->descriptors[i]); + microstrain_extract_u8(serializer, &self->descriptors[i]); } void insert_mip_3dm_event_action_command_type(struct mip_serializer* serializer, const mip_3dm_event_action_command_type self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_3dm_event_action_command_type(struct mip_serializer* serializer, mip_3dm_event_action_command_type* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -3649,10 +3763,10 @@ mip_cmd_result mip_3dm_write_event_action(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, instance); - - insert_u8(&serializer, trigger); + + microstrain_insert_u8(&serializer, instance); + + microstrain_insert_u8(&serializer, trigger); insert_mip_3dm_event_action_command_type(&serializer, type); @@ -3666,9 +3780,10 @@ mip_cmd_result mip_3dm_write_event_action(struct mip_interface* device, uint8_t insert_mip_3dm_event_action_command_message_params(&serializer, ¶meters->message); } - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t instance, uint8_t* trigger_out, mip_3dm_event_action_command_type* type_out, mip_3dm_event_action_command_parameters* parameters_out) { @@ -3677,23 +3792,24 @@ mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t i mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_ACTION_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_EVENT_ACTION_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &instance); + + microstrain_extract_u8(&deserializer, &instance); assert(trigger_out); - extract_u8(&deserializer, trigger_out); + microstrain_extract_u8(&deserializer, trigger_out); assert(type_out); extract_mip_3dm_event_action_command_type(&deserializer, type_out); @@ -3708,7 +3824,7 @@ mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t i extract_mip_3dm_event_action_command_message_params(&deserializer, ¶meters_out->message); } - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3720,12 +3836,13 @@ mip_cmd_result mip_3dm_save_event_action(struct mip_interface* device, uint8_t i mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_event_action(struct mip_interface* device, uint8_t instance) { @@ -3734,12 +3851,13 @@ mip_cmd_result mip_3dm_load_event_action(struct mip_interface* device, uint8_t i mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_event_action(struct mip_interface* device, uint8_t instance) { @@ -3748,12 +3866,13 @@ mip_cmd_result mip_3dm_default_event_action(struct mip_interface* device, uint8_ mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, instance); - insert_u8(&serializer, instance); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_accel_bias_command(mip_serializer* serializer, const mip_3dm_accel_bias_command* self) { @@ -3762,7 +3881,7 @@ void insert_mip_3dm_accel_bias_command(mip_serializer* serializer, const mip_3dm if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias[i]); + microstrain_insert_float(serializer, self->bias[i]); } } @@ -3773,7 +3892,7 @@ void extract_mip_3dm_accel_bias_command(mip_serializer* serializer, mip_3dm_acce if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias[i]); + microstrain_extract_float(serializer, &self->bias[i]); } } @@ -3781,13 +3900,13 @@ void extract_mip_3dm_accel_bias_command(mip_serializer* serializer, mip_3dm_acce void insert_mip_3dm_accel_bias_response(mip_serializer* serializer, const mip_3dm_accel_bias_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias[i]); + microstrain_insert_float(serializer, self->bias[i]); } void extract_mip_3dm_accel_bias_response(mip_serializer* serializer, mip_3dm_accel_bias_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias[i]); + microstrain_extract_float(serializer, &self->bias[i]); } @@ -3801,11 +3920,12 @@ mip_cmd_result mip_3dm_write_accel_bias(struct mip_interface* device, const floa assert(bias || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, bias[i]); + microstrain_insert_float(&serializer, bias[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias_out) { @@ -3815,10 +3935,11 @@ mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_ACCEL_BIAS_VECTOR, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_ACCEL_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3827,9 +3948,9 @@ mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias assert(bias_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &bias_out[i]); + microstrain_extract_float(&deserializer, &bias_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3842,9 +3963,10 @@ mip_cmd_result mip_3dm_save_accel_bias(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_accel_bias(struct mip_interface* device) { @@ -3854,9 +3976,10 @@ mip_cmd_result mip_3dm_load_accel_bias(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_accel_bias(struct mip_interface* device) { @@ -3866,9 +3989,10 @@ mip_cmd_result mip_3dm_default_accel_bias(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_gyro_bias_command(mip_serializer* serializer, const mip_3dm_gyro_bias_command* self) { @@ -3877,7 +4001,7 @@ void insert_mip_3dm_gyro_bias_command(mip_serializer* serializer, const mip_3dm_ if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias[i]); + microstrain_insert_float(serializer, self->bias[i]); } } @@ -3888,7 +4012,7 @@ void extract_mip_3dm_gyro_bias_command(mip_serializer* serializer, mip_3dm_gyro_ if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias[i]); + microstrain_extract_float(serializer, &self->bias[i]); } } @@ -3896,13 +4020,13 @@ void extract_mip_3dm_gyro_bias_command(mip_serializer* serializer, mip_3dm_gyro_ void insert_mip_3dm_gyro_bias_response(mip_serializer* serializer, const mip_3dm_gyro_bias_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias[i]); + microstrain_insert_float(serializer, self->bias[i]); } void extract_mip_3dm_gyro_bias_response(mip_serializer* serializer, mip_3dm_gyro_bias_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias[i]); + microstrain_extract_float(serializer, &self->bias[i]); } @@ -3916,11 +4040,12 @@ mip_cmd_result mip_3dm_write_gyro_bias(struct mip_interface* device, const float assert(bias || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, bias[i]); + microstrain_insert_float(&serializer, bias[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_out) { @@ -3930,10 +4055,11 @@ mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_ insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GYRO_BIAS_VECTOR, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3942,9 +4068,9 @@ mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_ assert(bias_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &bias_out[i]); + microstrain_extract_float(&deserializer, &bias_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3957,9 +4083,10 @@ mip_cmd_result mip_3dm_save_gyro_bias(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_gyro_bias(struct mip_interface* device) { @@ -3969,9 +4096,10 @@ mip_cmd_result mip_3dm_load_gyro_bias(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_gyro_bias(struct mip_interface* device) { @@ -3981,31 +4109,32 @@ mip_cmd_result mip_3dm_default_gyro_bias(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_capture_gyro_bias_command(mip_serializer* serializer, const mip_3dm_capture_gyro_bias_command* self) { - insert_u16(serializer, self->averaging_time_ms); + microstrain_insert_u16(serializer, self->averaging_time_ms); } void extract_mip_3dm_capture_gyro_bias_command(mip_serializer* serializer, mip_3dm_capture_gyro_bias_command* self) { - extract_u16(serializer, &self->averaging_time_ms); + microstrain_extract_u16(serializer, &self->averaging_time_ms); } void insert_mip_3dm_capture_gyro_bias_response(mip_serializer* serializer, const mip_3dm_capture_gyro_bias_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias[i]); + microstrain_insert_float(serializer, self->bias[i]); } void extract_mip_3dm_capture_gyro_bias_response(mip_serializer* serializer, mip_3dm_capture_gyro_bias_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias[i]); + microstrain_extract_float(serializer, &self->bias[i]); } @@ -4014,13 +4143,14 @@ mip_cmd_result mip_3dm_capture_gyro_bias(struct mip_interface* device, uint16_t mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + microstrain_insert_u16(&serializer, averaging_time_ms); - insert_u16(&serializer, averaging_time_ms); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CAPTURE_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GYRO_BIAS_VECTOR, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CAPTURE_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4029,9 +4159,9 @@ mip_cmd_result mip_3dm_capture_gyro_bias(struct mip_interface* device, uint16_t assert(bias_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &bias_out[i]); + microstrain_extract_float(&deserializer, &bias_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4043,7 +4173,7 @@ void insert_mip_3dm_mag_hard_iron_offset_command(mip_serializer* serializer, con if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset[i]); + microstrain_insert_float(serializer, self->offset[i]); } } @@ -4054,7 +4184,7 @@ void extract_mip_3dm_mag_hard_iron_offset_command(mip_serializer* serializer, mi if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset[i]); + microstrain_extract_float(serializer, &self->offset[i]); } } @@ -4062,13 +4192,13 @@ void extract_mip_3dm_mag_hard_iron_offset_command(mip_serializer* serializer, mi void insert_mip_3dm_mag_hard_iron_offset_response(mip_serializer* serializer, const mip_3dm_mag_hard_iron_offset_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset[i]); + microstrain_insert_float(serializer, self->offset[i]); } void extract_mip_3dm_mag_hard_iron_offset_response(mip_serializer* serializer, mip_3dm_mag_hard_iron_offset_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset[i]); + microstrain_extract_float(serializer, &self->offset[i]); } @@ -4082,11 +4212,12 @@ mip_cmd_result mip_3dm_write_mag_hard_iron_offset(struct mip_interface* device, assert(offset || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, offset[i]); + microstrain_insert_float(&serializer, offset[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, float* offset_out) { @@ -4096,10 +4227,11 @@ mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, f insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4108,9 +4240,9 @@ mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, f assert(offset_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &offset_out[i]); + microstrain_extract_float(&deserializer, &offset_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4123,9 +4255,10 @@ mip_cmd_result mip_3dm_save_mag_hard_iron_offset(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_mag_hard_iron_offset(struct mip_interface* device) { @@ -4135,9 +4268,10 @@ mip_cmd_result mip_3dm_load_mag_hard_iron_offset(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_mag_hard_iron_offset(struct mip_interface* device) { @@ -4147,9 +4281,10 @@ mip_cmd_result mip_3dm_default_mag_hard_iron_offset(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_mag_soft_iron_matrix_command(mip_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_command* self) { @@ -4158,7 +4293,7 @@ void insert_mip_3dm_mag_soft_iron_matrix_command(mip_serializer* serializer, con if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->offset[i]); + microstrain_insert_float(serializer, self->offset[i]); } } @@ -4169,7 +4304,7 @@ void extract_mip_3dm_mag_soft_iron_matrix_command(mip_serializer* serializer, mi if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->offset[i]); + microstrain_extract_float(serializer, &self->offset[i]); } } @@ -4177,13 +4312,13 @@ void extract_mip_3dm_mag_soft_iron_matrix_command(mip_serializer* serializer, mi void insert_mip_3dm_mag_soft_iron_matrix_response(mip_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_response* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->offset[i]); + microstrain_insert_float(serializer, self->offset[i]); } void extract_mip_3dm_mag_soft_iron_matrix_response(mip_serializer* serializer, mip_3dm_mag_soft_iron_matrix_response* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->offset[i]); + microstrain_extract_float(serializer, &self->offset[i]); } @@ -4197,11 +4332,12 @@ mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(struct mip_interface* device, assert(offset || (9 == 0)); for(unsigned int i=0; i < 9; i++) - insert_float(&serializer, offset[i]); + microstrain_insert_float(&serializer, offset[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, float* offset_out) { @@ -4211,10 +4347,11 @@ mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, f insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4223,9 +4360,9 @@ mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, f assert(offset_out || (9 == 0)); for(unsigned int i=0; i < 9; i++) - extract_float(&deserializer, &offset_out[i]); + microstrain_extract_float(&deserializer, &offset_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4238,9 +4375,10 @@ mip_cmd_result mip_3dm_save_mag_soft_iron_matrix(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_mag_soft_iron_matrix(struct mip_interface* device) { @@ -4250,9 +4388,10 @@ mip_cmd_result mip_3dm_load_mag_soft_iron_matrix(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(struct mip_interface* device) { @@ -4262,9 +4401,10 @@ mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_coning_sculling_enable_command(mip_serializer* serializer, const mip_3dm_coning_sculling_enable_command* self) { @@ -4272,7 +4412,7 @@ void insert_mip_3dm_coning_sculling_enable_command(mip_serializer* serializer, c if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->enable); + microstrain_insert_bool(serializer, self->enable); } } @@ -4282,19 +4422,19 @@ void extract_mip_3dm_coning_sculling_enable_command(mip_serializer* serializer, if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->enable); + microstrain_extract_bool(serializer, &self->enable); } } void insert_mip_3dm_coning_sculling_enable_response(mip_serializer* serializer, const mip_3dm_coning_sculling_enable_response* self) { - insert_bool(serializer, self->enable); + microstrain_insert_bool(serializer, self->enable); } void extract_mip_3dm_coning_sculling_enable_response(mip_serializer* serializer, mip_3dm_coning_sculling_enable_response* self) { - extract_bool(serializer, &self->enable); + microstrain_extract_bool(serializer, &self->enable); } @@ -4305,12 +4445,13 @@ mip_cmd_result mip_3dm_write_coning_sculling_enable(struct mip_interface* device mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_bool(&serializer, enable); - insert_bool(&serializer, enable); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, bool* enable_out) { @@ -4320,10 +4461,11 @@ mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4331,9 +4473,9 @@ mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_bool(&deserializer, enable_out); + microstrain_extract_bool(&deserializer, enable_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4346,9 +4488,10 @@ mip_cmd_result mip_3dm_save_coning_sculling_enable(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_coning_sculling_enable(struct mip_interface* device) { @@ -4358,9 +4501,10 @@ mip_cmd_result mip_3dm_load_coning_sculling_enable(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_coning_sculling_enable(struct mip_interface* device) { @@ -4370,9 +4514,10 @@ mip_cmd_result mip_3dm_default_coning_sculling_enable(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_command* self) { @@ -4380,11 +4525,11 @@ void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(mip_serializer* ser if( self->function == MIP_FUNCTION_WRITE ) { - insert_float(serializer, self->roll); - - insert_float(serializer, self->pitch); - - insert_float(serializer, self->yaw); + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->yaw); } } @@ -4394,31 +4539,31 @@ void extract_mip_3dm_sensor_2_vehicle_transform_euler_command(mip_serializer* se if( self->function == MIP_FUNCTION_WRITE ) { - extract_float(serializer, &self->roll); - - extract_float(serializer, &self->pitch); - - extract_float(serializer, &self->yaw); + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->yaw); } } void insert_mip_3dm_sensor_2_vehicle_transform_euler_response(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_response* self) { - insert_float(serializer, self->roll); - - insert_float(serializer, self->pitch); - - insert_float(serializer, self->yaw); + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->yaw); } void extract_mip_3dm_sensor_2_vehicle_transform_euler_response(mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_response* self) { - extract_float(serializer, &self->roll); - - extract_float(serializer, &self->pitch); - - extract_float(serializer, &self->yaw); + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->yaw); } @@ -4429,16 +4574,17 @@ mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_euler(struct mip_interfa mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_float(&serializer, roll); + + microstrain_insert_float(&serializer, pitch); + + microstrain_insert_float(&serializer, yaw); - insert_float(&serializer, roll); - - insert_float(&serializer, pitch); - - insert_float(&serializer, yaw); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out) { @@ -4448,10 +4594,11 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interfac insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4459,15 +4606,15 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interfac mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(roll_out); - extract_float(&deserializer, roll_out); + microstrain_extract_float(&deserializer, roll_out); assert(pitch_out); - extract_float(&deserializer, pitch_out); + microstrain_extract_float(&deserializer, pitch_out); assert(yaw_out); - extract_float(&deserializer, yaw_out); + microstrain_extract_float(&deserializer, yaw_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4480,9 +4627,10 @@ mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_euler(struct mip_interfac insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_euler(struct mip_interface* device) { @@ -4492,9 +4640,10 @@ mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_euler(struct mip_interfac insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(struct mip_interface* device) { @@ -4504,9 +4653,10 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(struct mip_inter insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_command* self) { @@ -4515,7 +4665,7 @@ void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(mip_serializer if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 4; i++) - insert_float(serializer, self->q[i]); + microstrain_insert_float(serializer, self->q[i]); } } @@ -4526,7 +4676,7 @@ void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(mip_serialize if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 4; i++) - extract_float(serializer, &self->q[i]); + microstrain_extract_float(serializer, &self->q[i]); } } @@ -4534,13 +4684,13 @@ void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(mip_serialize void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_response(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) { for(unsigned int i=0; i < 4; i++) - insert_float(serializer, self->q[i]); + microstrain_insert_float(serializer, self->q[i]); } void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_response(mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) { for(unsigned int i=0; i < 4; i++) - extract_float(serializer, &self->q[i]); + microstrain_extract_float(serializer, &self->q[i]); } @@ -4554,11 +4704,12 @@ mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(struct mip_in assert(q || (4 == 0)); for(unsigned int i=0; i < 4; i++) - insert_float(&serializer, q[i]); + microstrain_insert_float(&serializer, q[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_interface* device, float* q_out) { @@ -4568,10 +4719,11 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_int insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4580,9 +4732,9 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_int assert(q_out || (4 == 0)); for(unsigned int i=0; i < 4; i++) - extract_float(&deserializer, &q_out[i]); + microstrain_extract_float(&deserializer, &q_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4595,9 +4747,10 @@ mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_quaternion(struct mip_int insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_quaternion(struct mip_interface* device) { @@ -4607,9 +4760,10 @@ mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_quaternion(struct mip_int insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(struct mip_interface* device) { @@ -4619,9 +4773,10 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(struct mip_ insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_command* self) { @@ -4630,7 +4785,7 @@ void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(mip_serializer* seria if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->dcm[i]); + microstrain_insert_float(serializer, self->dcm[i]); } } @@ -4641,7 +4796,7 @@ void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(mip_serializer* seri if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->dcm[i]); + microstrain_extract_float(serializer, &self->dcm[i]); } } @@ -4649,13 +4804,13 @@ void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(mip_serializer* seri void insert_mip_3dm_sensor_2_vehicle_transform_dcm_response(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_response* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->dcm[i]); + microstrain_insert_float(serializer, self->dcm[i]); } void extract_mip_3dm_sensor_2_vehicle_transform_dcm_response(mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_response* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->dcm[i]); + microstrain_extract_float(serializer, &self->dcm[i]); } @@ -4669,11 +4824,12 @@ mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(struct mip_interface assert(dcm || (9 == 0)); for(unsigned int i=0; i < 9; i++) - insert_float(&serializer, dcm[i]); + microstrain_insert_float(&serializer, dcm[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* device, float* dcm_out) { @@ -4683,10 +4839,11 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4695,9 +4852,9 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* assert(dcm_out || (9 == 0)); for(unsigned int i=0; i < 9; i++) - extract_float(&deserializer, &dcm_out[i]); + microstrain_extract_float(&deserializer, &dcm_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4710,9 +4867,10 @@ mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_dcm(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_dcm(struct mip_interface* device) { @@ -4722,9 +4880,10 @@ mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_dcm(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(struct mip_interface* device) { @@ -4734,9 +4893,10 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(struct mip_interfa insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_complementary_filter_command(mip_serializer* serializer, const mip_3dm_complementary_filter_command* self) { @@ -4744,13 +4904,13 @@ void insert_mip_3dm_complementary_filter_command(mip_serializer* serializer, con if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->pitch_roll_enable); - - insert_bool(serializer, self->heading_enable); - - insert_float(serializer, self->pitch_roll_time_constant); - - insert_float(serializer, self->heading_time_constant); + microstrain_insert_bool(serializer, self->pitch_roll_enable); + + microstrain_insert_bool(serializer, self->heading_enable); + + microstrain_insert_float(serializer, self->pitch_roll_time_constant); + + microstrain_insert_float(serializer, self->heading_time_constant); } } @@ -4760,37 +4920,37 @@ void extract_mip_3dm_complementary_filter_command(mip_serializer* serializer, mi if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->pitch_roll_enable); - - extract_bool(serializer, &self->heading_enable); - - extract_float(serializer, &self->pitch_roll_time_constant); - - extract_float(serializer, &self->heading_time_constant); + microstrain_extract_bool(serializer, &self->pitch_roll_enable); + + microstrain_extract_bool(serializer, &self->heading_enable); + + microstrain_extract_float(serializer, &self->pitch_roll_time_constant); + + microstrain_extract_float(serializer, &self->heading_time_constant); } } void insert_mip_3dm_complementary_filter_response(mip_serializer* serializer, const mip_3dm_complementary_filter_response* self) { - insert_bool(serializer, self->pitch_roll_enable); - - insert_bool(serializer, self->heading_enable); - - insert_float(serializer, self->pitch_roll_time_constant); - - insert_float(serializer, self->heading_time_constant); + microstrain_insert_bool(serializer, self->pitch_roll_enable); + + microstrain_insert_bool(serializer, self->heading_enable); + + microstrain_insert_float(serializer, self->pitch_roll_time_constant); + + microstrain_insert_float(serializer, self->heading_time_constant); } void extract_mip_3dm_complementary_filter_response(mip_serializer* serializer, mip_3dm_complementary_filter_response* self) { - extract_bool(serializer, &self->pitch_roll_enable); - - extract_bool(serializer, &self->heading_enable); - - extract_float(serializer, &self->pitch_roll_time_constant); - - extract_float(serializer, &self->heading_time_constant); + microstrain_extract_bool(serializer, &self->pitch_roll_enable); + + microstrain_extract_bool(serializer, &self->heading_enable); + + microstrain_extract_float(serializer, &self->pitch_roll_time_constant); + + microstrain_extract_float(serializer, &self->heading_time_constant); } @@ -4801,18 +4961,19 @@ mip_cmd_result mip_3dm_write_complementary_filter(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_bool(&serializer, pitch_roll_enable); + + microstrain_insert_bool(&serializer, heading_enable); + + microstrain_insert_float(&serializer, pitch_roll_time_constant); + + microstrain_insert_float(&serializer, heading_time_constant); - insert_bool(&serializer, pitch_roll_enable); - - insert_bool(&serializer, heading_enable); - - insert_float(&serializer, pitch_roll_time_constant); - - insert_float(&serializer, heading_time_constant); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, bool* pitch_roll_enable_out, bool* heading_enable_out, float* pitch_roll_time_constant_out, float* heading_time_constant_out) { @@ -4822,10 +4983,11 @@ mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, b insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_LEGACY_COMP_FILTER, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_LEGACY_COMP_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4833,18 +4995,18 @@ mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, b mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(pitch_roll_enable_out); - extract_bool(&deserializer, pitch_roll_enable_out); + microstrain_extract_bool(&deserializer, pitch_roll_enable_out); assert(heading_enable_out); - extract_bool(&deserializer, heading_enable_out); + microstrain_extract_bool(&deserializer, heading_enable_out); assert(pitch_roll_time_constant_out); - extract_float(&deserializer, pitch_roll_time_constant_out); + microstrain_extract_float(&deserializer, pitch_roll_time_constant_out); assert(heading_time_constant_out); - extract_float(&deserializer, heading_time_constant_out); + microstrain_extract_float(&deserializer, heading_time_constant_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4857,9 +5019,10 @@ mip_cmd_result mip_3dm_save_complementary_filter(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_complementary_filter(struct mip_interface* device) { @@ -4869,9 +5032,10 @@ mip_cmd_result mip_3dm_load_complementary_filter(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_complementary_filter(struct mip_interface* device) { @@ -4881,9 +5045,10 @@ mip_cmd_result mip_3dm_default_complementary_filter(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_sensor_range_command(mip_serializer* serializer, const mip_3dm_sensor_range_command* self) { @@ -4893,7 +5058,7 @@ void insert_mip_3dm_sensor_range_command(mip_serializer* serializer, const mip_3 if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->setting); + microstrain_insert_u8(serializer, self->setting); } } @@ -4905,7 +5070,7 @@ void extract_mip_3dm_sensor_range_command(mip_serializer* serializer, mip_3dm_se if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->setting); + microstrain_extract_u8(serializer, &self->setting); } } @@ -4913,15 +5078,15 @@ void extract_mip_3dm_sensor_range_command(mip_serializer* serializer, mip_3dm_se void insert_mip_3dm_sensor_range_response(mip_serializer* serializer, const mip_3dm_sensor_range_response* self) { insert_mip_sensor_range_type(serializer, self->sensor); - - insert_u8(serializer, self->setting); + + microstrain_insert_u8(serializer, self->setting); } void extract_mip_3dm_sensor_range_response(mip_serializer* serializer, mip_3dm_sensor_range_response* self) { extract_mip_sensor_range_type(serializer, &self->sensor); - - extract_u8(serializer, &self->setting); + + microstrain_extract_u8(serializer, &self->setting); } @@ -4934,12 +5099,13 @@ mip_cmd_result mip_3dm_write_sensor_range(struct mip_interface* device, mip_sens insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_sensor_range_type(&serializer, sensor); + + microstrain_insert_u8(&serializer, setting); - insert_u8(&serializer, setting); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t* setting_out) { @@ -4951,10 +5117,11 @@ mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_senso insert_mip_sensor_range_type(&serializer, sensor); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SENSOR_RANGE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_SENSOR_RANGE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4964,9 +5131,9 @@ mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_senso extract_mip_sensor_range_type(&deserializer, &sensor); assert(setting_out); - extract_u8(&deserializer, setting_out); + microstrain_extract_u8(&deserializer, setting_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4981,9 +5148,10 @@ mip_cmd_result mip_3dm_save_sensor_range(struct mip_interface* device, mip_senso insert_mip_sensor_range_type(&serializer, sensor); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor) { @@ -4995,9 +5163,10 @@ mip_cmd_result mip_3dm_load_sensor_range(struct mip_interface* device, mip_senso insert_mip_sensor_range_type(&serializer, sensor); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor) { @@ -5009,9 +5178,10 @@ mip_cmd_result mip_3dm_default_sensor_range(struct mip_interface* device, mip_se insert_mip_sensor_range_type(&serializer, sensor); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_3dm_calibrated_sensor_ranges_command(mip_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command* self) { @@ -5027,8 +5197,8 @@ void extract_mip_3dm_calibrated_sensor_ranges_command(mip_serializer* serializer void insert_mip_3dm_calibrated_sensor_ranges_response(mip_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_response* self) { insert_mip_sensor_range_type(serializer, self->sensor); - - insert_u8(serializer, self->num_ranges); + + microstrain_insert_u8(serializer, self->num_ranges); for(unsigned int i=0; i < self->num_ranges; i++) @@ -5040,7 +5210,7 @@ void extract_mip_3dm_calibrated_sensor_ranges_response(mip_serializer* serialize extract_mip_sensor_range_type(serializer, &self->sensor); assert(self->num_ranges); - extract_count(serializer, &self->num_ranges, sizeof(self->ranges)/sizeof(self->ranges[0])); + microstrain_extract_count(serializer, &self->num_ranges, sizeof(self->ranges) / sizeof(self->ranges[0])); for(unsigned int i=0; i < self->num_ranges; i++) extract_mip_3dm_calibrated_sensor_ranges_command_entry(serializer, &self->ranges[i]); @@ -5049,16 +5219,16 @@ void extract_mip_3dm_calibrated_sensor_ranges_response(mip_serializer* serialize void insert_mip_3dm_calibrated_sensor_ranges_command_entry(mip_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command_entry* self) { - insert_u8(serializer, self->setting); - - insert_float(serializer, self->range); + microstrain_insert_u8(serializer, self->setting); + + microstrain_insert_float(serializer, self->range); } void extract_mip_3dm_calibrated_sensor_ranges_command_entry(mip_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command_entry* self) { - extract_u8(serializer, &self->setting); - - extract_float(serializer, &self->range); + microstrain_extract_u8(serializer, &self->setting); + + microstrain_extract_float(serializer, &self->range); } @@ -5070,10 +5240,11 @@ mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mi insert_mip_sensor_range_type(&serializer, sensor); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CALIBRATED_RANGES, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_CALIBRATED_RANGES, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CALIBRATED_RANGES, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_CALIBRATED_RANGES, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5083,13 +5254,13 @@ mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mi extract_mip_sensor_range_type(&deserializer, &sensor); assert(num_ranges_out); - extract_count(&deserializer, num_ranges_out, num_ranges_out_max); + microstrain_extract_count(&deserializer, num_ranges_out, num_ranges_out_max); assert(ranges_out || (num_ranges_out == 0)); for(unsigned int i=0; i < *num_ranges_out; i++) extract_mip_3dm_calibrated_sensor_ranges_command_entry(&deserializer, &ranges_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -5097,64 +5268,64 @@ mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mi void insert_mip_3dm_lowpass_filter_command(mip_serializer* serializer, const mip_3dm_lowpass_filter_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->desc_set); - - insert_u8(serializer, self->field_desc); + + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u8(serializer, self->field_desc); if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->enable); - - insert_bool(serializer, self->manual); - - insert_float(serializer, self->frequency); + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_bool(serializer, self->manual); + + microstrain_insert_float(serializer, self->frequency); } } void extract_mip_3dm_lowpass_filter_command(mip_serializer* serializer, mip_3dm_lowpass_filter_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->desc_set); - - extract_u8(serializer, &self->field_desc); + + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_u8(serializer, &self->field_desc); if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->enable); - - extract_bool(serializer, &self->manual); - - extract_float(serializer, &self->frequency); + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_bool(serializer, &self->manual); + + microstrain_extract_float(serializer, &self->frequency); } } void insert_mip_3dm_lowpass_filter_response(mip_serializer* serializer, const mip_3dm_lowpass_filter_response* self) { - insert_u8(serializer, self->desc_set); - - insert_u8(serializer, self->field_desc); - - insert_bool(serializer, self->enable); - - insert_bool(serializer, self->manual); - - insert_float(serializer, self->frequency); + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u8(serializer, self->field_desc); + + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_bool(serializer, self->manual); + + microstrain_insert_float(serializer, self->frequency); } void extract_mip_3dm_lowpass_filter_response(mip_serializer* serializer, mip_3dm_lowpass_filter_response* self) { - extract_u8(serializer, &self->desc_set); - - extract_u8(serializer, &self->field_desc); - - extract_bool(serializer, &self->enable); - - extract_bool(serializer, &self->manual); - - extract_float(serializer, &self->frequency); + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_u8(serializer, &self->field_desc); + + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_bool(serializer, &self->manual); + + microstrain_extract_float(serializer, &self->frequency); } @@ -5165,20 +5336,21 @@ mip_cmd_result mip_3dm_write_lowpass_filter(struct mip_interface* device, uint8_ mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, desc_set); + + microstrain_insert_u8(&serializer, field_desc); + + microstrain_insert_bool(&serializer, enable); + + microstrain_insert_bool(&serializer, manual); + + microstrain_insert_float(&serializer, frequency); - insert_u8(&serializer, desc_set); - - insert_u8(&serializer, field_desc); - - insert_bool(&serializer, enable); - - insert_bool(&serializer, manual); - - insert_float(&serializer, frequency); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_read_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool* enable_out, bool* manual_out, float* frequency_out) { @@ -5187,35 +5359,36 @@ mip_cmd_result mip_3dm_read_lowpass_filter(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, desc_set); + + microstrain_insert_u8(&serializer, field_desc); - insert_u8(&serializer, desc_set); - - insert_u8(&serializer, field_desc); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_3DM_LOWPASS_FILTER, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_3DM_LOWPASS_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &desc_set); - - extract_u8(&deserializer, &field_desc); + + microstrain_extract_u8(&deserializer, &desc_set); + + microstrain_extract_u8(&deserializer, &field_desc); assert(enable_out); - extract_bool(&deserializer, enable_out); + microstrain_extract_bool(&deserializer, enable_out); assert(manual_out); - extract_bool(&deserializer, manual_out); + microstrain_extract_bool(&deserializer, manual_out); assert(frequency_out); - extract_float(&deserializer, frequency_out); + microstrain_extract_float(&deserializer, frequency_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -5227,14 +5400,15 @@ mip_cmd_result mip_3dm_save_lowpass_filter(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, desc_set); + + microstrain_insert_u8(&serializer, field_desc); - insert_u8(&serializer, desc_set); - - insert_u8(&serializer, field_desc); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_load_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) { @@ -5243,14 +5417,15 @@ mip_cmd_result mip_3dm_load_lowpass_filter(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, desc_set); + + microstrain_insert_u8(&serializer, field_desc); - insert_u8(&serializer, desc_set); - - insert_u8(&serializer, field_desc); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_3dm_default_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) { @@ -5259,14 +5434,15 @@ mip_cmd_result mip_3dm_default_lowpass_filter(struct mip_interface* device, uint mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, desc_set); + + microstrain_insert_u8(&serializer, field_desc); - insert_u8(&serializer, desc_set); - - insert_u8(&serializer, field_desc); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } #ifdef __cplusplus diff --git a/src/mip/definitions/commands_3dm.cpp b/src/mip/definitions/commands_3dm.cpp index 477119d41..48e6186a1 100644 --- a/src/mip/definitions/commands_3dm.cpp +++ b/src/mip/definitions/commands_3dm.cpp @@ -1,7 +1,7 @@ #include "commands_3dm.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/commands_aiding.c b/src/mip/definitions/commands_aiding.c index b6ff74621..c917ce24d 100644 --- a/src/mip/definitions/commands_aiding.c +++ b/src/mip/definitions/commands_aiding.c @@ -1,7 +1,7 @@ #include "commands_aiding.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -25,30 +25,30 @@ struct mip_field; void insert_mip_time(mip_serializer* serializer, const mip_time* self) { insert_mip_time_timebase(serializer, self->timebase); - - insert_u8(serializer, self->reserved); - - insert_u64(serializer, self->nanoseconds); + + microstrain_insert_u8(serializer, self->reserved); + + microstrain_insert_u64(serializer, self->nanoseconds); } void extract_mip_time(mip_serializer* serializer, mip_time* self) { extract_mip_time_timebase(serializer, &self->timebase); - - extract_u8(serializer, &self->reserved); - - extract_u64(serializer, &self->nanoseconds); + + microstrain_extract_u8(serializer, &self->reserved); + + microstrain_extract_u64(serializer, &self->nanoseconds); } void insert_mip_time_timebase(struct mip_serializer* serializer, const mip_time_timebase self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_time_timebase(struct mip_serializer* serializer, mip_time_timebase* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -60,8 +60,8 @@ void extract_mip_time_timebase(struct mip_serializer* serializer, mip_time_timeb void insert_mip_aiding_frame_config_command(mip_serializer* serializer, const mip_aiding_frame_config_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->frame_id); + + microstrain_insert_u8(serializer, self->frame_id); if( self->function == MIP_FUNCTION_WRITE || self->function == MIP_FUNCTION_READ ) { @@ -70,10 +70,10 @@ void insert_mip_aiding_frame_config_command(mip_serializer* serializer, const mi } if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->tracking_enabled); + microstrain_insert_bool(serializer, self->tracking_enabled); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->translation[i]); + microstrain_insert_float(serializer, self->translation[i]); if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) { @@ -90,8 +90,8 @@ void insert_mip_aiding_frame_config_command(mip_serializer* serializer, const mi void extract_mip_aiding_frame_config_command(mip_serializer* serializer, mip_aiding_frame_config_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->frame_id); + + microstrain_extract_u8(serializer, &self->frame_id); if( self->function == MIP_FUNCTION_WRITE || self->function == MIP_FUNCTION_READ ) { @@ -100,10 +100,10 @@ void extract_mip_aiding_frame_config_command(mip_serializer* serializer, mip_aid } if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->tracking_enabled); + microstrain_extract_bool(serializer, &self->tracking_enabled); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->translation[i]); + microstrain_extract_float(serializer, &self->translation[i]); if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) { @@ -120,14 +120,14 @@ void extract_mip_aiding_frame_config_command(mip_serializer* serializer, mip_aid void insert_mip_aiding_frame_config_response(mip_serializer* serializer, const mip_aiding_frame_config_response* self) { - insert_u8(serializer, self->frame_id); + microstrain_insert_u8(serializer, self->frame_id); insert_mip_aiding_frame_config_command_format(serializer, self->format); - - insert_bool(serializer, self->tracking_enabled); + + microstrain_insert_bool(serializer, self->tracking_enabled); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->translation[i]); + microstrain_insert_float(serializer, self->translation[i]); if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) { @@ -142,14 +142,14 @@ void insert_mip_aiding_frame_config_response(mip_serializer* serializer, const m } void extract_mip_aiding_frame_config_response(mip_serializer* serializer, mip_aiding_frame_config_response* self) { - extract_u8(serializer, &self->frame_id); + microstrain_extract_u8(serializer, &self->frame_id); extract_mip_aiding_frame_config_command_format(serializer, &self->format); - - extract_bool(serializer, &self->tracking_enabled); + + microstrain_extract_bool(serializer, &self->tracking_enabled); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->translation[i]); + microstrain_extract_float(serializer, &self->translation[i]); if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) { @@ -165,12 +165,12 @@ void extract_mip_aiding_frame_config_response(mip_serializer* serializer, mip_ai void insert_mip_aiding_frame_config_command_format(struct mip_serializer* serializer, const mip_aiding_frame_config_command_format self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_aiding_frame_config_command_format(struct mip_serializer* serializer, mip_aiding_frame_config_command_format* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -181,16 +181,16 @@ mip_cmd_result mip_aiding_write_frame_config(struct mip_interface* device, uint8 mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, frame_id); + + microstrain_insert_u8(&serializer, frame_id); insert_mip_aiding_frame_config_command_format(&serializer, format); - - insert_bool(&serializer, tracking_enabled); + + microstrain_insert_bool(&serializer, tracking_enabled); assert(translation || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, translation[i]); + microstrain_insert_float(&serializer, translation[i]); if( format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) { @@ -202,9 +202,10 @@ mip_cmd_result mip_aiding_write_frame_config(struct mip_interface* device, uint8 insert_mip_quatf(&serializer, rotation->quaternion); } - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool* tracking_enabled_out, float* translation_out, mip_aiding_frame_config_command_rotation* rotation_out) { @@ -213,31 +214,32 @@ mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_ mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - - insert_u8(&serializer, frame_id); + + microstrain_insert_u8(&serializer, frame_id); insert_mip_aiding_frame_config_command_format(&serializer, format); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_AIDING_FRAME_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_AIDING_FRAME_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &frame_id); + + microstrain_extract_u8(&deserializer, &frame_id); extract_mip_aiding_frame_config_command_format(&deserializer, &format); assert(tracking_enabled_out); - extract_bool(&deserializer, tracking_enabled_out); + microstrain_extract_bool(&deserializer, tracking_enabled_out); assert(translation_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &translation_out[i]); + microstrain_extract_float(&deserializer, &translation_out[i]); if( format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) { @@ -249,7 +251,7 @@ mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_ extract_mip_quatf(&deserializer, rotation_out->quaternion); } - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -261,12 +263,13 @@ mip_cmd_result mip_aiding_save_frame_config(struct mip_interface* device, uint8_ mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, frame_id); - insert_u8(&serializer, frame_id); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_aiding_load_frame_config(struct mip_interface* device, uint8_t frame_id) { @@ -275,12 +278,13 @@ mip_cmd_result mip_aiding_load_frame_config(struct mip_interface* device, uint8_ mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, frame_id); - insert_u8(&serializer, frame_id); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_aiding_default_frame_config(struct mip_interface* device, uint8_t frame_id) { @@ -289,12 +293,13 @@ mip_cmd_result mip_aiding_default_frame_config(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, frame_id); - insert_u8(&serializer, frame_id); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_aiding_echo_control_command(mip_serializer* serializer, const mip_aiding_aiding_echo_control_command* self) { @@ -330,12 +335,12 @@ void extract_mip_aiding_aiding_echo_control_response(mip_serializer* serializer, void insert_mip_aiding_aiding_echo_control_command_mode(struct mip_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_aiding_aiding_echo_control_command_mode(struct mip_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -349,9 +354,10 @@ mip_cmd_result mip_aiding_write_aiding_echo_control(struct mip_interface* device insert_mip_aiding_aiding_echo_control_command_mode(&serializer, mode); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out) { @@ -361,10 +367,11 @@ mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_AIDING_ECHO_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_AIDING_ECHO_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -374,7 +381,7 @@ mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, assert(mode_out); extract_mip_aiding_aiding_echo_control_command_mode(&deserializer, mode_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -387,9 +394,10 @@ mip_cmd_result mip_aiding_save_aiding_echo_control(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_aiding_load_aiding_echo_control(struct mip_interface* device) { @@ -399,9 +407,10 @@ mip_cmd_result mip_aiding_load_aiding_echo_control(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_aiding_default_aiding_echo_control(struct mip_interface* device) { @@ -411,21 +420,22 @@ mip_cmd_result mip_aiding_default_aiding_echo_control(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_ecef_pos_command(mip_serializer* serializer, const mip_aiding_ecef_pos_command* self) { insert_mip_time(serializer, &self->time); - - insert_u8(serializer, self->frame_id); + + microstrain_insert_u8(serializer, self->frame_id); for(unsigned int i=0; i < 3; i++) - insert_double(serializer, self->position[i]); + microstrain_insert_double(serializer, self->position[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->uncertainty[i]); + microstrain_insert_float(serializer, self->uncertainty[i]); insert_mip_aiding_ecef_pos_command_valid_flags(serializer, self->valid_flags); @@ -433,14 +443,14 @@ void insert_mip_aiding_ecef_pos_command(mip_serializer* serializer, const mip_ai void extract_mip_aiding_ecef_pos_command(mip_serializer* serializer, mip_aiding_ecef_pos_command* self) { extract_mip_time(serializer, &self->time); - - extract_u8(serializer, &self->frame_id); + + microstrain_extract_u8(serializer, &self->frame_id); for(unsigned int i=0; i < 3; i++) - extract_double(serializer, &self->position[i]); + microstrain_extract_double(serializer, &self->position[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->uncertainty[i]); + microstrain_extract_float(serializer, &self->uncertainty[i]); extract_mip_aiding_ecef_pos_command_valid_flags(serializer, &self->valid_flags); @@ -448,12 +458,12 @@ void extract_mip_aiding_ecef_pos_command(mip_serializer* serializer, mip_aiding_ void insert_mip_aiding_ecef_pos_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_aiding_ecef_pos_command_valid_flags(struct mip_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -465,37 +475,38 @@ mip_cmd_result mip_aiding_ecef_pos(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); - - insert_u8(&serializer, frame_id); + + microstrain_insert_u8(&serializer, frame_id); assert(position || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_double(&serializer, position[i]); + microstrain_insert_double(&serializer, position[i]); assert(uncertainty || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, uncertainty[i]); + microstrain_insert_float(&serializer, uncertainty[i]); insert_mip_aiding_ecef_pos_command_valid_flags(&serializer, valid_flags); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_ECEF, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_ECEF, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_llh_pos_command(mip_serializer* serializer, const mip_aiding_llh_pos_command* self) { insert_mip_time(serializer, &self->time); - - insert_u8(serializer, self->frame_id); - - insert_double(serializer, self->latitude); - - insert_double(serializer, self->longitude); - - insert_double(serializer, self->height); + + microstrain_insert_u8(serializer, self->frame_id); + + microstrain_insert_double(serializer, self->latitude); + + microstrain_insert_double(serializer, self->longitude); + + microstrain_insert_double(serializer, self->height); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->uncertainty[i]); + microstrain_insert_float(serializer, self->uncertainty[i]); insert_mip_aiding_llh_pos_command_valid_flags(serializer, self->valid_flags); @@ -503,17 +514,17 @@ void insert_mip_aiding_llh_pos_command(mip_serializer* serializer, const mip_aid void extract_mip_aiding_llh_pos_command(mip_serializer* serializer, mip_aiding_llh_pos_command* self) { extract_mip_time(serializer, &self->time); - - extract_u8(serializer, &self->frame_id); - - extract_double(serializer, &self->latitude); - - extract_double(serializer, &self->longitude); - - extract_double(serializer, &self->height); + + microstrain_extract_u8(serializer, &self->frame_id); + + microstrain_extract_double(serializer, &self->latitude); + + microstrain_extract_double(serializer, &self->longitude); + + microstrain_extract_double(serializer, &self->height); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->uncertainty[i]); + microstrain_extract_float(serializer, &self->uncertainty[i]); extract_mip_aiding_llh_pos_command_valid_flags(serializer, &self->valid_flags); @@ -521,12 +532,12 @@ void extract_mip_aiding_llh_pos_command(mip_serializer* serializer, mip_aiding_l void insert_mip_aiding_llh_pos_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_aiding_llh_pos_command_valid_flags(struct mip_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -538,49 +549,50 @@ mip_cmd_result mip_aiding_llh_pos(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); - - insert_u8(&serializer, frame_id); - - insert_double(&serializer, latitude); - - insert_double(&serializer, longitude); - - insert_double(&serializer, height); + + microstrain_insert_u8(&serializer, frame_id); + + microstrain_insert_double(&serializer, latitude); + + microstrain_insert_double(&serializer, longitude); + + microstrain_insert_double(&serializer, height); assert(uncertainty || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, uncertainty[i]); + microstrain_insert_float(&serializer, uncertainty[i]); insert_mip_aiding_llh_pos_command_valid_flags(&serializer, valid_flags); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_height_command(mip_serializer* serializer, const mip_aiding_height_command* self) { insert_mip_time(serializer, &self->time); - - insert_u8(serializer, self->frame_id); - - insert_float(serializer, self->height); - - insert_float(serializer, self->uncertainty); - - insert_u16(serializer, self->valid_flags); + + microstrain_insert_u8(serializer, self->frame_id); + + microstrain_insert_float(serializer, self->height); + + microstrain_insert_float(serializer, self->uncertainty); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_aiding_height_command(mip_serializer* serializer, mip_aiding_height_command* self) { extract_mip_time(serializer, &self->time); - - extract_u8(serializer, &self->frame_id); - - extract_float(serializer, &self->height); - - extract_float(serializer, &self->uncertainty); - - extract_u16(serializer, &self->valid_flags); + + microstrain_extract_u8(serializer, &self->frame_id); + + microstrain_extract_float(serializer, &self->height); + + microstrain_extract_float(serializer, &self->uncertainty); + + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -592,30 +604,31 @@ mip_cmd_result mip_aiding_height(struct mip_interface* device, const mip_time* t assert(time); insert_mip_time(&serializer, time); + + microstrain_insert_u8(&serializer, frame_id); + + microstrain_insert_float(&serializer, height); + + microstrain_insert_float(&serializer, uncertainty); + + microstrain_insert_u16(&serializer, valid_flags); - insert_u8(&serializer, frame_id); - - insert_float(&serializer, height); - - insert_float(&serializer, uncertainty); - - insert_u16(&serializer, valid_flags); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_ecef_vel_command(mip_serializer* serializer, const mip_aiding_ecef_vel_command* self) { insert_mip_time(serializer, &self->time); - - insert_u8(serializer, self->frame_id); + + microstrain_insert_u8(serializer, self->frame_id); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->velocity[i]); + microstrain_insert_float(serializer, self->velocity[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->uncertainty[i]); + microstrain_insert_float(serializer, self->uncertainty[i]); insert_mip_aiding_ecef_vel_command_valid_flags(serializer, self->valid_flags); @@ -623,14 +636,14 @@ void insert_mip_aiding_ecef_vel_command(mip_serializer* serializer, const mip_ai void extract_mip_aiding_ecef_vel_command(mip_serializer* serializer, mip_aiding_ecef_vel_command* self) { extract_mip_time(serializer, &self->time); - - extract_u8(serializer, &self->frame_id); + + microstrain_extract_u8(serializer, &self->frame_id); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->velocity[i]); + microstrain_extract_float(serializer, &self->velocity[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->uncertainty[i]); + microstrain_extract_float(serializer, &self->uncertainty[i]); extract_mip_aiding_ecef_vel_command_valid_flags(serializer, &self->valid_flags); @@ -638,12 +651,12 @@ void extract_mip_aiding_ecef_vel_command(mip_serializer* serializer, mip_aiding_ void insert_mip_aiding_ecef_vel_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_aiding_ecef_vel_command_valid_flags(struct mip_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -655,34 +668,35 @@ mip_cmd_result mip_aiding_ecef_vel(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); - - insert_u8(&serializer, frame_id); + + microstrain_insert_u8(&serializer, frame_id); assert(velocity || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, velocity[i]); + microstrain_insert_float(&serializer, velocity[i]); assert(uncertainty || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, uncertainty[i]); + microstrain_insert_float(&serializer, uncertainty[i]); insert_mip_aiding_ecef_vel_command_valid_flags(&serializer, valid_flags); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ECEF, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ECEF, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_ned_vel_command(mip_serializer* serializer, const mip_aiding_ned_vel_command* self) { insert_mip_time(serializer, &self->time); - - insert_u8(serializer, self->frame_id); + + microstrain_insert_u8(serializer, self->frame_id); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->velocity[i]); + microstrain_insert_float(serializer, self->velocity[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->uncertainty[i]); + microstrain_insert_float(serializer, self->uncertainty[i]); insert_mip_aiding_ned_vel_command_valid_flags(serializer, self->valid_flags); @@ -690,14 +704,14 @@ void insert_mip_aiding_ned_vel_command(mip_serializer* serializer, const mip_aid void extract_mip_aiding_ned_vel_command(mip_serializer* serializer, mip_aiding_ned_vel_command* self) { extract_mip_time(serializer, &self->time); - - extract_u8(serializer, &self->frame_id); + + microstrain_extract_u8(serializer, &self->frame_id); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->velocity[i]); + microstrain_extract_float(serializer, &self->velocity[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->uncertainty[i]); + microstrain_extract_float(serializer, &self->uncertainty[i]); extract_mip_aiding_ned_vel_command_valid_flags(serializer, &self->valid_flags); @@ -705,12 +719,12 @@ void extract_mip_aiding_ned_vel_command(mip_serializer* serializer, mip_aiding_n void insert_mip_aiding_ned_vel_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_aiding_ned_vel_command_valid_flags(struct mip_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -722,34 +736,35 @@ mip_cmd_result mip_aiding_ned_vel(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); - - insert_u8(&serializer, frame_id); + + microstrain_insert_u8(&serializer, frame_id); assert(velocity || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, velocity[i]); + microstrain_insert_float(&serializer, velocity[i]); assert(uncertainty || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, uncertainty[i]); + microstrain_insert_float(&serializer, uncertainty[i]); insert_mip_aiding_ned_vel_command_valid_flags(&serializer, valid_flags); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_vehicle_fixed_frame_velocity_command(mip_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self) { insert_mip_time(serializer, &self->time); - - insert_u8(serializer, self->frame_id); + + microstrain_insert_u8(serializer, self->frame_id); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->velocity[i]); + microstrain_insert_float(serializer, self->velocity[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->uncertainty[i]); + microstrain_insert_float(serializer, self->uncertainty[i]); insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, self->valid_flags); @@ -757,14 +772,14 @@ void insert_mip_aiding_vehicle_fixed_frame_velocity_command(mip_serializer* seri void extract_mip_aiding_vehicle_fixed_frame_velocity_command(mip_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self) { extract_mip_time(serializer, &self->time); - - extract_u8(serializer, &self->frame_id); + + microstrain_extract_u8(serializer, &self->frame_id); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->velocity[i]); + microstrain_extract_float(serializer, &self->velocity[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->uncertainty[i]); + microstrain_extract_float(serializer, &self->uncertainty[i]); extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, &self->valid_flags); @@ -772,12 +787,12 @@ void extract_mip_aiding_vehicle_fixed_frame_velocity_command(mip_serializer* ser void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct mip_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -789,47 +804,48 @@ mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(struct mip_interface* dev assert(time); insert_mip_time(&serializer, time); - - insert_u8(&serializer, frame_id); + + microstrain_insert_u8(&serializer, frame_id); assert(velocity || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, velocity[i]); + microstrain_insert_float(&serializer, velocity[i]); assert(uncertainty || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, uncertainty[i]); + microstrain_insert_float(&serializer, uncertainty[i]); insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(&serializer, valid_flags); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ODOM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ODOM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_true_heading_command(mip_serializer* serializer, const mip_aiding_true_heading_command* self) { insert_mip_time(serializer, &self->time); - - insert_u8(serializer, self->frame_id); - - insert_float(serializer, self->heading); - - insert_float(serializer, self->uncertainty); - - insert_u16(serializer, self->valid_flags); + + microstrain_insert_u8(serializer, self->frame_id); + + microstrain_insert_float(serializer, self->heading); + + microstrain_insert_float(serializer, self->uncertainty); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_aiding_true_heading_command(mip_serializer* serializer, mip_aiding_true_heading_command* self) { extract_mip_time(serializer, &self->time); - - extract_u8(serializer, &self->frame_id); - - extract_float(serializer, &self->heading); - - extract_float(serializer, &self->uncertainty); - - extract_u16(serializer, &self->valid_flags); + + microstrain_extract_u8(serializer, &self->frame_id); + + microstrain_extract_float(serializer, &self->heading); + + microstrain_extract_float(serializer, &self->uncertainty); + + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -841,30 +857,31 @@ mip_cmd_result mip_aiding_true_heading(struct mip_interface* device, const mip_t assert(time); insert_mip_time(&serializer, time); + + microstrain_insert_u8(&serializer, frame_id); + + microstrain_insert_float(&serializer, heading); + + microstrain_insert_float(&serializer, uncertainty); + + microstrain_insert_u16(&serializer, valid_flags); - insert_u8(&serializer, frame_id); - - insert_float(&serializer, heading); - - insert_float(&serializer, uncertainty); - - insert_u16(&serializer, valid_flags); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEADING_TRUE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEADING_TRUE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_magnetic_field_command(mip_serializer* serializer, const mip_aiding_magnetic_field_command* self) { insert_mip_time(serializer, &self->time); - - insert_u8(serializer, self->frame_id); + + microstrain_insert_u8(serializer, self->frame_id); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->magnetic_field[i]); + microstrain_insert_float(serializer, self->magnetic_field[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->uncertainty[i]); + microstrain_insert_float(serializer, self->uncertainty[i]); insert_mip_aiding_magnetic_field_command_valid_flags(serializer, self->valid_flags); @@ -872,14 +889,14 @@ void insert_mip_aiding_magnetic_field_command(mip_serializer* serializer, const void extract_mip_aiding_magnetic_field_command(mip_serializer* serializer, mip_aiding_magnetic_field_command* self) { extract_mip_time(serializer, &self->time); - - extract_u8(serializer, &self->frame_id); + + microstrain_extract_u8(serializer, &self->frame_id); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->magnetic_field[i]); + microstrain_extract_float(serializer, &self->magnetic_field[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->uncertainty[i]); + microstrain_extract_float(serializer, &self->uncertainty[i]); extract_mip_aiding_magnetic_field_command_valid_flags(serializer, &self->valid_flags); @@ -887,12 +904,12 @@ void extract_mip_aiding_magnetic_field_command(mip_serializer* serializer, mip_a void insert_mip_aiding_magnetic_field_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_aiding_magnetic_field_command_valid_flags(struct mip_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -904,47 +921,48 @@ mip_cmd_result mip_aiding_magnetic_field(struct mip_interface* device, const mip assert(time); insert_mip_time(&serializer, time); - - insert_u8(&serializer, frame_id); + + microstrain_insert_u8(&serializer, frame_id); assert(magnetic_field || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, magnetic_field[i]); + microstrain_insert_float(&serializer, magnetic_field[i]); assert(uncertainty || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, uncertainty[i]); + microstrain_insert_float(&serializer, uncertainty[i]); insert_mip_aiding_magnetic_field_command_valid_flags(&serializer, valid_flags); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_MAGNETIC_FIELD, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_MAGNETIC_FIELD, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_aiding_pressure_command(mip_serializer* serializer, const mip_aiding_pressure_command* self) { insert_mip_time(serializer, &self->time); - - insert_u8(serializer, self->frame_id); - - insert_float(serializer, self->pressure); - - insert_float(serializer, self->uncertainty); - - insert_u16(serializer, self->valid_flags); + + microstrain_insert_u8(serializer, self->frame_id); + + microstrain_insert_float(serializer, self->pressure); + + microstrain_insert_float(serializer, self->uncertainty); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_aiding_pressure_command(mip_serializer* serializer, mip_aiding_pressure_command* self) { extract_mip_time(serializer, &self->time); - - extract_u8(serializer, &self->frame_id); - - extract_float(serializer, &self->pressure); - - extract_float(serializer, &self->uncertainty); - - extract_u16(serializer, &self->valid_flags); + + microstrain_extract_u8(serializer, &self->frame_id); + + microstrain_extract_float(serializer, &self->pressure); + + microstrain_extract_float(serializer, &self->uncertainty); + + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -956,18 +974,19 @@ mip_cmd_result mip_aiding_pressure(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); + + microstrain_insert_u8(&serializer, frame_id); + + microstrain_insert_float(&serializer, pressure); + + microstrain_insert_float(&serializer, uncertainty); + + microstrain_insert_u16(&serializer, valid_flags); - insert_u8(&serializer, frame_id); - - insert_float(&serializer, pressure); - - insert_float(&serializer, uncertainty); - - insert_u16(&serializer, valid_flags); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_PRESSURE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_PRESSURE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } #ifdef __cplusplus diff --git a/src/mip/definitions/commands_aiding.cpp b/src/mip/definitions/commands_aiding.cpp index 4b9240e49..f619e07f9 100644 --- a/src/mip/definitions/commands_aiding.cpp +++ b/src/mip/definitions/commands_aiding.cpp @@ -1,7 +1,7 @@ #include "commands_aiding.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/commands_base.c b/src/mip/definitions/commands_base.c index fd72ea2fa..ca9919e91 100644 --- a/src/mip/definitions/commands_base.c +++ b/src/mip/definitions/commands_base.c @@ -1,7 +1,7 @@ #include "commands_base.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -24,64 +24,64 @@ struct mip_field; void insert_mip_base_device_info(mip_serializer* serializer, const mip_base_device_info* self) { - insert_u16(serializer, self->firmware_version); + microstrain_insert_u16(serializer, self->firmware_version); for(unsigned int i=0; i < 16; i++) - insert_char(serializer, self->model_name[i]); + microstrain_insert_char(serializer, self->model_name[i]); for(unsigned int i=0; i < 16; i++) - insert_char(serializer, self->model_number[i]); + microstrain_insert_char(serializer, self->model_number[i]); for(unsigned int i=0; i < 16; i++) - insert_char(serializer, self->serial_number[i]); + microstrain_insert_char(serializer, self->serial_number[i]); for(unsigned int i=0; i < 16; i++) - insert_char(serializer, self->lot_number[i]); + microstrain_insert_char(serializer, self->lot_number[i]); for(unsigned int i=0; i < 16; i++) - insert_char(serializer, self->device_options[i]); + microstrain_insert_char(serializer, self->device_options[i]); } void extract_mip_base_device_info(mip_serializer* serializer, mip_base_device_info* self) { - extract_u16(serializer, &self->firmware_version); + microstrain_extract_u16(serializer, &self->firmware_version); for(unsigned int i=0; i < 16; i++) - extract_char(serializer, &self->model_name[i]); + microstrain_extract_char(serializer, &self->model_name[i]); for(unsigned int i=0; i < 16; i++) - extract_char(serializer, &self->model_number[i]); + microstrain_extract_char(serializer, &self->model_number[i]); for(unsigned int i=0; i < 16; i++) - extract_char(serializer, &self->serial_number[i]); + microstrain_extract_char(serializer, &self->serial_number[i]); for(unsigned int i=0; i < 16; i++) - extract_char(serializer, &self->lot_number[i]); + microstrain_extract_char(serializer, &self->lot_number[i]); for(unsigned int i=0; i < 16; i++) - extract_char(serializer, &self->device_options[i]); + microstrain_extract_char(serializer, &self->device_options[i]); } void insert_mip_time_format(struct mip_serializer* serializer, const mip_time_format self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_time_format(struct mip_serializer* serializer, mip_time_format* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_commanded_test_bits_gq7(struct mip_serializer* serializer, const mip_commanded_test_bits_gq7 self) { - insert_u32(serializer, (uint32_t)(self)); + microstrain_insert_u32(serializer, (uint32_t) (self)); } void extract_mip_commanded_test_bits_gq7(struct mip_serializer* serializer, mip_commanded_test_bits_gq7* self) { uint32_t tmp = 0; - extract_u32(serializer, &tmp); + microstrain_extract_u32(serializer, &tmp); *self = tmp; } @@ -113,7 +113,7 @@ mip_cmd_result mip_base_get_device_info(struct mip_interface* device, mip_base_d assert(device_info_out); extract_mip_base_device_info(&deserializer, device_info_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -130,10 +130,11 @@ mip_cmd_result mip_base_get_device_descriptors(struct mip_interface* device, uin mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && (mip_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) - extract_u16(&deserializer, &descriptors_out[*descriptors_out_count]); + for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && ( + microstrain_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) + microstrain_extract_u16(&deserializer, &descriptors_out[*descriptors_out_count]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -151,9 +152,9 @@ mip_cmd_result mip_base_built_in_test(struct mip_interface* device, uint32_t* re mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(result_out); - extract_u32(&deserializer, result_out); + microstrain_extract_u32(&deserializer, result_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -174,10 +175,11 @@ mip_cmd_result mip_base_get_extended_descriptors(struct mip_interface* device, u mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && (mip_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) - extract_u16(&deserializer, &descriptors_out[*descriptors_out_count]); + for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && ( + microstrain_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) + microstrain_extract_u16(&deserializer, &descriptors_out[*descriptors_out_count]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -196,9 +198,9 @@ mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* re assert(result_out || (16 == 0)); for(unsigned int i=0; i < 16; i++) - extract_u8(&deserializer, &result_out[i]); + microstrain_extract_u8(&deserializer, &result_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -206,40 +208,40 @@ mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* re void insert_mip_base_comm_speed_command(mip_serializer* serializer, const mip_base_comm_speed_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->port); + + microstrain_insert_u8(serializer, self->port); if( self->function == MIP_FUNCTION_WRITE ) { - insert_u32(serializer, self->baud); + microstrain_insert_u32(serializer, self->baud); } } void extract_mip_base_comm_speed_command(mip_serializer* serializer, mip_base_comm_speed_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->port); + + microstrain_extract_u8(serializer, &self->port); if( self->function == MIP_FUNCTION_WRITE ) { - extract_u32(serializer, &self->baud); + microstrain_extract_u32(serializer, &self->baud); } } void insert_mip_base_comm_speed_response(mip_serializer* serializer, const mip_base_comm_speed_response* self) { - insert_u8(serializer, self->port); - - insert_u32(serializer, self->baud); + microstrain_insert_u8(serializer, self->port); + + microstrain_insert_u32(serializer, self->baud); } void extract_mip_base_comm_speed_response(mip_serializer* serializer, mip_base_comm_speed_response* self) { - extract_u8(serializer, &self->port); - - extract_u32(serializer, &self->baud); + microstrain_extract_u8(serializer, &self->port); + + microstrain_extract_u32(serializer, &self->baud); } @@ -250,14 +252,15 @@ mip_cmd_result mip_base_write_comm_speed(struct mip_interface* device, uint8_t p mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, port); + + microstrain_insert_u32(&serializer, baud); - insert_u8(&serializer, port); - - insert_u32(&serializer, baud); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_base_read_comm_speed(struct mip_interface* device, uint8_t port, uint32_t* baud_out) { @@ -266,25 +269,26 @@ mip_cmd_result mip_base_read_comm_speed(struct mip_interface* device, uint8_t po mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, port); - insert_u8(&serializer, port); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_BASE_COMM_SPEED, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_BASE_COMM_SPEED, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &port); + + microstrain_extract_u8(&deserializer, &port); assert(baud_out); - extract_u32(&deserializer, baud_out); + microstrain_extract_u32(&deserializer, baud_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -296,12 +300,13 @@ mip_cmd_result mip_base_save_comm_speed(struct mip_interface* device, uint8_t po mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, port); - insert_u8(&serializer, port); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_base_load_comm_speed(struct mip_interface* device, uint8_t port) { @@ -310,12 +315,13 @@ mip_cmd_result mip_base_load_comm_speed(struct mip_interface* device, uint8_t po mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, port); - insert_u8(&serializer, port); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_base_default_comm_speed(struct mip_interface* device, uint8_t port) { @@ -324,12 +330,13 @@ mip_cmd_result mip_base_default_comm_speed(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, port); - insert_u8(&serializer, port); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_base_gps_time_update_command(mip_serializer* serializer, const mip_base_gps_time_update_command* self) { @@ -338,8 +345,8 @@ void insert_mip_base_gps_time_update_command(mip_serializer* serializer, const m if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_base_gps_time_update_command_field_id(serializer, self->field_id); - - insert_u32(serializer, self->value); + + microstrain_insert_u32(serializer, self->value); } } @@ -350,20 +357,20 @@ void extract_mip_base_gps_time_update_command(mip_serializer* serializer, mip_ba if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_base_gps_time_update_command_field_id(serializer, &self->field_id); - - extract_u32(serializer, &self->value); + + microstrain_extract_u32(serializer, &self->value); } } void insert_mip_base_gps_time_update_command_field_id(struct mip_serializer* serializer, const mip_base_gps_time_update_command_field_id self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_base_gps_time_update_command_field_id(struct mip_serializer* serializer, mip_base_gps_time_update_command_field_id* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -376,12 +383,13 @@ mip_cmd_result mip_base_write_gps_time_update(struct mip_interface* device, mip_ insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_base_gps_time_update_command_field_id(&serializer, field_id); + + microstrain_insert_u32(&serializer, value); - insert_u32(&serializer, value); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_GPS_TIME_UPDATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_GPS_TIME_UPDATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_base_soft_reset(struct mip_interface* device) { diff --git a/src/mip/definitions/commands_base.cpp b/src/mip/definitions/commands_base.cpp index 35965b4cb..0c4a53034 100644 --- a/src/mip/definitions/commands_base.cpp +++ b/src/mip/definitions/commands_base.cpp @@ -1,7 +1,7 @@ #include "commands_base.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/commands_filter.c b/src/mip/definitions/commands_filter.c index 7cc6aed8f..6c21204ac 100644 --- a/src/mip/definitions/commands_filter.c +++ b/src/mip/definitions/commands_filter.c @@ -1,7 +1,7 @@ #include "commands_filter.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -24,34 +24,34 @@ struct mip_field; void insert_mip_filter_reference_frame(struct mip_serializer* serializer, const mip_filter_reference_frame self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_reference_frame(struct mip_serializer* serializer, mip_filter_reference_frame* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_filter_mag_param_source(struct mip_serializer* serializer, const mip_filter_mag_param_source self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_mag_param_source(struct mip_serializer* serializer, mip_filter_mag_param_source* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_filter_adaptive_measurement(struct mip_serializer* serializer, const mip_filter_adaptive_measurement self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_adaptive_measurement(struct mip_serializer* serializer, mip_filter_adaptive_measurement* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -66,20 +66,20 @@ mip_cmd_result mip_filter_reset(struct mip_interface* device) } void insert_mip_filter_set_initial_attitude_command(mip_serializer* serializer, const mip_filter_set_initial_attitude_command* self) { - insert_float(serializer, self->roll); - - insert_float(serializer, self->pitch); - - insert_float(serializer, self->heading); + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->heading); } void extract_mip_filter_set_initial_attitude_command(mip_serializer* serializer, mip_filter_set_initial_attitude_command* self) { - extract_float(serializer, &self->roll); - - extract_float(serializer, &self->pitch); - - extract_float(serializer, &self->heading); + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->heading); } @@ -88,16 +88,17 @@ mip_cmd_result mip_filter_set_initial_attitude(struct mip_interface* device, flo mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + microstrain_insert_float(&serializer, roll); + + microstrain_insert_float(&serializer, pitch); + + microstrain_insert_float(&serializer, heading); - insert_float(&serializer, roll); - - insert_float(&serializer, pitch); - - insert_float(&serializer, heading); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SET_INITIAL_ATTITUDE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SET_INITIAL_ATTITUDE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_estimation_control_command(mip_serializer* serializer, const mip_filter_estimation_control_command* self) { @@ -133,12 +134,12 @@ void extract_mip_filter_estimation_control_response(mip_serializer* serializer, void insert_mip_filter_estimation_control_command_enable_flags(struct mip_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_filter_estimation_control_command_enable_flags(struct mip_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -152,9 +153,10 @@ mip_cmd_result mip_filter_write_estimation_control(struct mip_interface* device, insert_mip_filter_estimation_control_command_enable_flags(&serializer, enable); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags* enable_out) { @@ -164,10 +166,11 @@ mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -177,7 +180,7 @@ mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, assert(enable_out); extract_mip_filter_estimation_control_command_enable_flags(&deserializer, enable_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -190,9 +193,10 @@ mip_cmd_result mip_filter_save_estimation_control(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_estimation_control(struct mip_interface* device) { @@ -202,9 +206,10 @@ mip_cmd_result mip_filter_load_estimation_control(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_estimation_control(struct mip_interface* device) { @@ -214,52 +219,53 @@ mip_cmd_result mip_filter_default_estimation_control(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_external_gnss_update_command(mip_serializer* serializer, const mip_filter_external_gnss_update_command* self) { - insert_double(serializer, self->gps_time); - - insert_u16(serializer, self->gps_week); - - insert_double(serializer, self->latitude); - - insert_double(serializer, self->longitude); - - insert_double(serializer, self->height); + microstrain_insert_double(serializer, self->gps_time); + + microstrain_insert_u16(serializer, self->gps_week); + + microstrain_insert_double(serializer, self->latitude); + + microstrain_insert_double(serializer, self->longitude); + + microstrain_insert_double(serializer, self->height); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->velocity[i]); + microstrain_insert_float(serializer, self->velocity[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->pos_uncertainty[i]); + microstrain_insert_float(serializer, self->pos_uncertainty[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->vel_uncertainty[i]); + microstrain_insert_float(serializer, self->vel_uncertainty[i]); } void extract_mip_filter_external_gnss_update_command(mip_serializer* serializer, mip_filter_external_gnss_update_command* self) { - extract_double(serializer, &self->gps_time); - - extract_u16(serializer, &self->gps_week); - - extract_double(serializer, &self->latitude); - - extract_double(serializer, &self->longitude); - - extract_double(serializer, &self->height); + microstrain_extract_double(serializer, &self->gps_time); + + microstrain_extract_u16(serializer, &self->gps_week); + + microstrain_extract_double(serializer, &self->latitude); + + microstrain_extract_double(serializer, &self->longitude); + + microstrain_extract_double(serializer, &self->height); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->velocity[i]); + microstrain_extract_float(serializer, &self->velocity[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->pos_uncertainty[i]); + microstrain_extract_float(serializer, &self->pos_uncertainty[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->vel_uncertainty[i]); + microstrain_extract_float(serializer, &self->vel_uncertainty[i]); } @@ -268,49 +274,50 @@ mip_cmd_result mip_filter_external_gnss_update(struct mip_interface* device, dou mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_double(&serializer, gps_time); - - insert_u16(&serializer, gps_week); - - insert_double(&serializer, latitude); - - insert_double(&serializer, longitude); - - insert_double(&serializer, height); + + microstrain_insert_double(&serializer, gps_time); + + microstrain_insert_u16(&serializer, gps_week); + + microstrain_insert_double(&serializer, latitude); + + microstrain_insert_double(&serializer, longitude); + + microstrain_insert_double(&serializer, height); assert(velocity || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, velocity[i]); + microstrain_insert_float(&serializer, velocity[i]); assert(pos_uncertainty || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, pos_uncertainty[i]); + microstrain_insert_float(&serializer, pos_uncertainty[i]); assert(vel_uncertainty || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, vel_uncertainty[i]); + microstrain_insert_float(&serializer, vel_uncertainty[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_external_heading_update_command(mip_serializer* serializer, const mip_filter_external_heading_update_command* self) { - insert_float(serializer, self->heading); - - insert_float(serializer, self->heading_uncertainty); - - insert_u8(serializer, self->type); + microstrain_insert_float(serializer, self->heading); + + microstrain_insert_float(serializer, self->heading_uncertainty); + + microstrain_insert_u8(serializer, self->type); } void extract_mip_filter_external_heading_update_command(mip_serializer* serializer, mip_filter_external_heading_update_command* self) { - extract_float(serializer, &self->heading); - - extract_float(serializer, &self->heading_uncertainty); - - extract_u8(serializer, &self->type); + microstrain_extract_float(serializer, &self->heading); + + microstrain_extract_float(serializer, &self->heading_uncertainty); + + microstrain_extract_u8(serializer, &self->type); } @@ -319,41 +326,42 @@ mip_cmd_result mip_filter_external_heading_update(struct mip_interface* device, mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + microstrain_insert_float(&serializer, heading); + + microstrain_insert_float(&serializer, heading_uncertainty); + + microstrain_insert_u8(&serializer, type); - insert_float(&serializer, heading); - - insert_float(&serializer, heading_uncertainty); - - insert_u8(&serializer, type); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_external_heading_update_with_time_command(mip_serializer* serializer, const mip_filter_external_heading_update_with_time_command* self) { - insert_double(serializer, self->gps_time); - - insert_u16(serializer, self->gps_week); - - insert_float(serializer, self->heading); - - insert_float(serializer, self->heading_uncertainty); - - insert_u8(serializer, self->type); + microstrain_insert_double(serializer, self->gps_time); + + microstrain_insert_u16(serializer, self->gps_week); + + microstrain_insert_float(serializer, self->heading); + + microstrain_insert_float(serializer, self->heading_uncertainty); + + microstrain_insert_u8(serializer, self->type); } void extract_mip_filter_external_heading_update_with_time_command(mip_serializer* serializer, mip_filter_external_heading_update_with_time_command* self) { - extract_double(serializer, &self->gps_time); - - extract_u16(serializer, &self->gps_week); - - extract_float(serializer, &self->heading); - - extract_float(serializer, &self->heading_uncertainty); - - extract_u8(serializer, &self->type); + microstrain_extract_double(serializer, &self->gps_time); + + microstrain_extract_u16(serializer, &self->gps_week); + + microstrain_extract_float(serializer, &self->heading); + + microstrain_extract_float(serializer, &self->heading_uncertainty); + + microstrain_extract_u8(serializer, &self->type); } @@ -362,20 +370,21 @@ mip_cmd_result mip_filter_external_heading_update_with_time(struct mip_interface mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + microstrain_insert_double(&serializer, gps_time); + + microstrain_insert_u16(&serializer, gps_week); + + microstrain_insert_float(&serializer, heading); + + microstrain_insert_float(&serializer, heading_uncertainty); + + microstrain_insert_u8(&serializer, type); - insert_double(&serializer, gps_time); - - insert_u16(&serializer, gps_week); - - insert_float(&serializer, heading); - - insert_float(&serializer, heading_uncertainty); - - insert_u8(&serializer, type); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_tare_orientation_command(mip_serializer* serializer, const mip_filter_tare_orientation_command* self) { @@ -411,12 +420,12 @@ void extract_mip_filter_tare_orientation_response(mip_serializer* serializer, mi void insert_mip_filter_tare_orientation_command_mip_tare_axes(struct mip_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_tare_orientation_command_mip_tare_axes(struct mip_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -430,9 +439,10 @@ mip_cmd_result mip_filter_write_tare_orientation(struct mip_interface* device, m insert_mip_filter_tare_orientation_command_mip_tare_axes(&serializer, axes); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes* axes_out) { @@ -442,10 +452,11 @@ mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mi insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_TARE_ORIENTATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_TARE_ORIENTATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -455,7 +466,7 @@ mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mi assert(axes_out); extract_mip_filter_tare_orientation_command_mip_tare_axes(&deserializer, axes_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -468,9 +479,10 @@ mip_cmd_result mip_filter_save_tare_orientation(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_tare_orientation(struct mip_interface* device) { @@ -480,9 +492,10 @@ mip_cmd_result mip_filter_load_tare_orientation(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_tare_orientation(struct mip_interface* device) { @@ -492,9 +505,10 @@ mip_cmd_result mip_filter_default_tare_orientation(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_vehicle_dynamics_mode_command(mip_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self) { @@ -530,12 +544,12 @@ void extract_mip_filter_vehicle_dynamics_mode_response(mip_serializer* serialize void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct mip_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct mip_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -549,9 +563,10 @@ mip_cmd_result mip_filter_write_vehicle_dynamics_mode(struct mip_interface* devi insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(&serializer, mode); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* mode_out) { @@ -561,10 +576,11 @@ mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -574,7 +590,7 @@ mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* devic assert(mode_out); extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(&deserializer, mode_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -587,9 +603,10 @@ mip_cmd_result mip_filter_save_vehicle_dynamics_mode(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_vehicle_dynamics_mode(struct mip_interface* device) { @@ -599,9 +616,10 @@ mip_cmd_result mip_filter_load_vehicle_dynamics_mode(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_vehicle_dynamics_mode(struct mip_interface* device) { @@ -611,9 +629,10 @@ mip_cmd_result mip_filter_default_vehicle_dynamics_mode(struct mip_interface* de insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self) { @@ -621,11 +640,11 @@ void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(mip_serializer* if( self->function == MIP_FUNCTION_WRITE ) { - insert_float(serializer, self->roll); - - insert_float(serializer, self->pitch); - - insert_float(serializer, self->yaw); + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->yaw); } } @@ -635,31 +654,31 @@ void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(mip_serializer* if( self->function == MIP_FUNCTION_WRITE ) { - extract_float(serializer, &self->roll); - - extract_float(serializer, &self->pitch); - - extract_float(serializer, &self->yaw); + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->yaw); } } void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self) { - insert_float(serializer, self->roll); - - insert_float(serializer, self->pitch); - - insert_float(serializer, self->yaw); + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->yaw); } void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self) { - extract_float(serializer, &self->roll); - - extract_float(serializer, &self->pitch); - - extract_float(serializer, &self->yaw); + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->yaw); } @@ -670,16 +689,17 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(struct mip_inte mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_float(&serializer, roll); + + microstrain_insert_float(&serializer, pitch); + + microstrain_insert_float(&serializer, yaw); - insert_float(&serializer, roll); - - insert_float(&serializer, pitch); - - insert_float(&serializer, yaw); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out) { @@ -689,10 +709,11 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_inter insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -700,15 +721,15 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_inter mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(roll_out); - extract_float(&deserializer, roll_out); + microstrain_extract_float(&deserializer, roll_out); assert(pitch_out); - extract_float(&deserializer, pitch_out); + microstrain_extract_float(&deserializer, pitch_out); assert(yaw_out); - extract_float(&deserializer, yaw_out); + microstrain_extract_float(&deserializer, yaw_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -721,9 +742,10 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_euler(struct mip_inter insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_euler(struct mip_interface* device) { @@ -733,9 +755,10 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_euler(struct mip_inter insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(struct mip_interface* device) { @@ -745,9 +768,10 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(struct mip_in insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_command* self) { @@ -756,7 +780,7 @@ void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(mip_serializer* se if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->dcm[i]); + microstrain_insert_float(serializer, self->dcm[i]); } } @@ -767,7 +791,7 @@ void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(mip_serializer* s if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->dcm[i]); + microstrain_extract_float(serializer, &self->dcm[i]); } } @@ -775,13 +799,13 @@ void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(mip_serializer* s void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->dcm[i]); + microstrain_insert_float(serializer, self->dcm[i]); } void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->dcm[i]); + microstrain_extract_float(serializer, &self->dcm[i]); } @@ -795,11 +819,12 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(struct mip_interf assert(dcm || (9 == 0)); for(unsigned int i=0; i < 9; i++) - insert_float(&serializer, dcm[i]); + microstrain_insert_float(&serializer, dcm[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, float* dcm_out) { @@ -809,10 +834,11 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interfa insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -821,9 +847,9 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interfa assert(dcm_out || (9 == 0)); for(unsigned int i=0; i < 9; i++) - extract_float(&deserializer, &dcm_out[i]); + microstrain_extract_float(&deserializer, &dcm_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -836,9 +862,10 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_dcm(struct mip_interfa insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_dcm(struct mip_interface* device) { @@ -848,9 +875,10 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_dcm(struct mip_interfa insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(struct mip_interface* device) { @@ -860,9 +888,10 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(struct mip_inte insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_command* self) { @@ -871,7 +900,7 @@ void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(mip_seriali if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 4; i++) - insert_float(serializer, self->quat[i]); + microstrain_insert_float(serializer, self->quat[i]); } } @@ -882,7 +911,7 @@ void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(mip_serial if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 4; i++) - extract_float(serializer, &self->quat[i]); + microstrain_extract_float(serializer, &self->quat[i]); } } @@ -890,13 +919,13 @@ void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(mip_serial void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) { for(unsigned int i=0; i < 4; i++) - insert_float(serializer, self->quat[i]); + microstrain_insert_float(serializer, self->quat[i]); } void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) { for(unsigned int i=0; i < 4; i++) - extract_float(serializer, &self->quat[i]); + microstrain_extract_float(serializer, &self->quat[i]); } @@ -910,11 +939,12 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(struct mip assert(quat || (4 == 0)); for(unsigned int i=0; i < 4; i++) - insert_float(&serializer, quat[i]); + microstrain_insert_float(&serializer, quat[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, float* quat_out) { @@ -924,10 +954,11 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_ insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -936,9 +967,9 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_ assert(quat_out || (4 == 0)); for(unsigned int i=0; i < 4; i++) - extract_float(&deserializer, &quat_out[i]); + microstrain_extract_float(&deserializer, &quat_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -951,9 +982,10 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_quaternion(struct mip_ insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device) { @@ -963,9 +995,10 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_quaternion(struct mip_ insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device) { @@ -975,9 +1008,10 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(struct m insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_sensor_to_vehicle_offset_command(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_command* self) { @@ -986,7 +1020,7 @@ void insert_mip_filter_sensor_to_vehicle_offset_command(mip_serializer* serializ if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset[i]); + microstrain_insert_float(serializer, self->offset[i]); } } @@ -997,7 +1031,7 @@ void extract_mip_filter_sensor_to_vehicle_offset_command(mip_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset[i]); + microstrain_extract_float(serializer, &self->offset[i]); } } @@ -1005,13 +1039,13 @@ void extract_mip_filter_sensor_to_vehicle_offset_command(mip_serializer* seriali void insert_mip_filter_sensor_to_vehicle_offset_response(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset[i]); + microstrain_insert_float(serializer, self->offset[i]); } void extract_mip_filter_sensor_to_vehicle_offset_response(mip_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset[i]); + microstrain_extract_float(serializer, &self->offset[i]); } @@ -1025,11 +1059,12 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(struct mip_interface* d assert(offset || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, offset[i]); + microstrain_insert_float(&serializer, offset[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* device, float* offset_out) { @@ -1039,10 +1074,11 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* de insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1051,9 +1087,9 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* de assert(offset_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &offset_out[i]); + microstrain_extract_float(&deserializer, &offset_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1066,9 +1102,10 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_offset(struct mip_interface* de insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_sensor_to_vehicle_offset(struct mip_interface* device) { @@ -1078,9 +1115,10 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_offset(struct mip_interface* de insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(struct mip_interface* device) { @@ -1090,9 +1128,10 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_antenna_offset_command(mip_serializer* serializer, const mip_filter_antenna_offset_command* self) { @@ -1101,7 +1140,7 @@ void insert_mip_filter_antenna_offset_command(mip_serializer* serializer, const if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset[i]); + microstrain_insert_float(serializer, self->offset[i]); } } @@ -1112,7 +1151,7 @@ void extract_mip_filter_antenna_offset_command(mip_serializer* serializer, mip_f if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset[i]); + microstrain_extract_float(serializer, &self->offset[i]); } } @@ -1120,13 +1159,13 @@ void extract_mip_filter_antenna_offset_command(mip_serializer* serializer, mip_f void insert_mip_filter_antenna_offset_response(mip_serializer* serializer, const mip_filter_antenna_offset_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset[i]); + microstrain_insert_float(serializer, self->offset[i]); } void extract_mip_filter_antenna_offset_response(mip_serializer* serializer, mip_filter_antenna_offset_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset[i]); + microstrain_extract_float(serializer, &self->offset[i]); } @@ -1140,11 +1179,12 @@ mip_cmd_result mip_filter_write_antenna_offset(struct mip_interface* device, con assert(offset || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, offset[i]); + microstrain_insert_float(&serializer, offset[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, float* offset_out) { @@ -1154,10 +1194,11 @@ mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, floa insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ANTENNA_OFFSET, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1166,9 +1207,9 @@ mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, floa assert(offset_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &offset_out[i]); + microstrain_extract_float(&deserializer, &offset_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1181,9 +1222,10 @@ mip_cmd_result mip_filter_save_antenna_offset(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_antenna_offset(struct mip_interface* device) { @@ -1193,9 +1235,10 @@ mip_cmd_result mip_filter_load_antenna_offset(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_antenna_offset(struct mip_interface* device) { @@ -1205,9 +1248,10 @@ mip_cmd_result mip_filter_default_antenna_offset(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_gnss_source_command(mip_serializer* serializer, const mip_filter_gnss_source_command* self) { @@ -1243,12 +1287,12 @@ void extract_mip_filter_gnss_source_response(mip_serializer* serializer, mip_fil void insert_mip_filter_gnss_source_command_source(struct mip_serializer* serializer, const mip_filter_gnss_source_command_source self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_gnss_source_command_source(struct mip_serializer* serializer, mip_filter_gnss_source_command_source* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -1262,9 +1306,10 @@ mip_cmd_result mip_filter_write_gnss_source(struct mip_interface* device, mip_fi insert_mip_filter_gnss_source_command_source(&serializer, source); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source* source_out) { @@ -1274,10 +1319,11 @@ mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_fil insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1287,7 +1333,7 @@ mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_fil assert(source_out); extract_mip_filter_gnss_source_command_source(&deserializer, source_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1300,9 +1346,10 @@ mip_cmd_result mip_filter_save_gnss_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_gnss_source(struct mip_interface* device) { @@ -1312,9 +1359,10 @@ mip_cmd_result mip_filter_load_gnss_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_gnss_source(struct mip_interface* device) { @@ -1324,9 +1372,10 @@ mip_cmd_result mip_filter_default_gnss_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_heading_source_command(mip_serializer* serializer, const mip_filter_heading_source_command* self) { @@ -1362,12 +1411,12 @@ void extract_mip_filter_heading_source_response(mip_serializer* serializer, mip_ void insert_mip_filter_heading_source_command_source(struct mip_serializer* serializer, const mip_filter_heading_source_command_source self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_heading_source_command_source(struct mip_serializer* serializer, mip_filter_heading_source_command_source* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -1381,9 +1430,10 @@ mip_cmd_result mip_filter_write_heading_source(struct mip_interface* device, mip insert_mip_filter_heading_source_command_source(&serializer, source); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source* source_out) { @@ -1393,10 +1443,11 @@ mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_ insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1406,7 +1457,7 @@ mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_ assert(source_out); extract_mip_filter_heading_source_command_source(&deserializer, source_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1419,9 +1470,10 @@ mip_cmd_result mip_filter_save_heading_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_heading_source(struct mip_interface* device) { @@ -1431,9 +1483,10 @@ mip_cmd_result mip_filter_load_heading_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_heading_source(struct mip_interface* device) { @@ -1443,9 +1496,10 @@ mip_cmd_result mip_filter_default_heading_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_auto_init_control_command(mip_serializer* serializer, const mip_filter_auto_init_control_command* self) { @@ -1453,7 +1507,7 @@ void insert_mip_filter_auto_init_control_command(mip_serializer* serializer, con if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable); + microstrain_insert_u8(serializer, self->enable); } } @@ -1463,19 +1517,19 @@ void extract_mip_filter_auto_init_control_command(mip_serializer* serializer, mi if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable); + microstrain_extract_u8(serializer, &self->enable); } } void insert_mip_filter_auto_init_control_response(mip_serializer* serializer, const mip_filter_auto_init_control_response* self) { - insert_u8(serializer, self->enable); + microstrain_insert_u8(serializer, self->enable); } void extract_mip_filter_auto_init_control_response(mip_serializer* serializer, mip_filter_auto_init_control_response* self) { - extract_u8(serializer, &self->enable); + microstrain_extract_u8(serializer, &self->enable); } @@ -1486,12 +1540,13 @@ mip_cmd_result mip_filter_write_auto_init_control(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, enable); - insert_u8(&serializer, enable); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, uint8_t* enable_out) { @@ -1501,10 +1556,11 @@ mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, u insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_AUTOINIT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_AUTOINIT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1512,9 +1568,9 @@ mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, u mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_u8(&deserializer, enable_out); + microstrain_extract_u8(&deserializer, enable_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1527,9 +1583,10 @@ mip_cmd_result mip_filter_save_auto_init_control(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_auto_init_control(struct mip_interface* device) { @@ -1539,9 +1596,10 @@ mip_cmd_result mip_filter_load_auto_init_control(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_auto_init_control(struct mip_interface* device) { @@ -1551,9 +1609,10 @@ mip_cmd_result mip_filter_default_auto_init_control(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_accel_noise_command(mip_serializer* serializer, const mip_filter_accel_noise_command* self) { @@ -1562,7 +1621,7 @@ void insert_mip_filter_accel_noise_command(mip_serializer* serializer, const mip if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } } @@ -1573,7 +1632,7 @@ void extract_mip_filter_accel_noise_command(mip_serializer* serializer, mip_filt if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } } @@ -1581,13 +1640,13 @@ void extract_mip_filter_accel_noise_command(mip_serializer* serializer, mip_filt void insert_mip_filter_accel_noise_response(mip_serializer* serializer, const mip_filter_accel_noise_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } void extract_mip_filter_accel_noise_response(mip_serializer* serializer, mip_filter_accel_noise_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } @@ -1601,11 +1660,12 @@ mip_cmd_result mip_filter_write_accel_noise(struct mip_interface* device, const assert(noise || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, noise[i]); + microstrain_insert_float(&serializer, noise[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* noise_out) { @@ -1615,10 +1675,11 @@ mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ACCEL_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_ACCEL_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1627,9 +1688,9 @@ mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &noise_out[i]); + microstrain_extract_float(&deserializer, &noise_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1642,9 +1703,10 @@ mip_cmd_result mip_filter_save_accel_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_accel_noise(struct mip_interface* device) { @@ -1654,9 +1716,10 @@ mip_cmd_result mip_filter_load_accel_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_accel_noise(struct mip_interface* device) { @@ -1666,9 +1729,10 @@ mip_cmd_result mip_filter_default_accel_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_gyro_noise_command(mip_serializer* serializer, const mip_filter_gyro_noise_command* self) { @@ -1677,7 +1741,7 @@ void insert_mip_filter_gyro_noise_command(mip_serializer* serializer, const mip_ if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } } @@ -1688,7 +1752,7 @@ void extract_mip_filter_gyro_noise_command(mip_serializer* serializer, mip_filte if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } } @@ -1696,13 +1760,13 @@ void extract_mip_filter_gyro_noise_command(mip_serializer* serializer, mip_filte void insert_mip_filter_gyro_noise_response(mip_serializer* serializer, const mip_filter_gyro_noise_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } void extract_mip_filter_gyro_noise_response(mip_serializer* serializer, mip_filter_gyro_noise_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } @@ -1716,11 +1780,12 @@ mip_cmd_result mip_filter_write_gyro_noise(struct mip_interface* device, const f assert(noise || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, noise[i]); + microstrain_insert_float(&serializer, noise[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* noise_out) { @@ -1730,10 +1795,11 @@ mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* n insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_GYRO_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_GYRO_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1742,9 +1808,9 @@ mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* n assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &noise_out[i]); + microstrain_extract_float(&deserializer, &noise_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1757,9 +1823,10 @@ mip_cmd_result mip_filter_save_gyro_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_gyro_noise(struct mip_interface* device) { @@ -1769,9 +1836,10 @@ mip_cmd_result mip_filter_load_gyro_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_gyro_noise(struct mip_interface* device) { @@ -1781,9 +1849,10 @@ mip_cmd_result mip_filter_default_gyro_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_accel_bias_model_command(mip_serializer* serializer, const mip_filter_accel_bias_model_command* self) { @@ -1792,10 +1861,10 @@ void insert_mip_filter_accel_bias_model_command(mip_serializer* serializer, cons if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->beta[i]); + microstrain_insert_float(serializer, self->beta[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } } @@ -1806,10 +1875,10 @@ void extract_mip_filter_accel_bias_model_command(mip_serializer* serializer, mip if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->beta[i]); + microstrain_extract_float(serializer, &self->beta[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } } @@ -1817,19 +1886,19 @@ void extract_mip_filter_accel_bias_model_command(mip_serializer* serializer, mip void insert_mip_filter_accel_bias_model_response(mip_serializer* serializer, const mip_filter_accel_bias_model_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->beta[i]); + microstrain_insert_float(serializer, self->beta[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } void extract_mip_filter_accel_bias_model_response(mip_serializer* serializer, mip_filter_accel_bias_model_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->beta[i]); + microstrain_extract_float(serializer, &self->beta[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } @@ -1843,15 +1912,16 @@ mip_cmd_result mip_filter_write_accel_bias_model(struct mip_interface* device, c assert(beta || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, beta[i]); + microstrain_insert_float(&serializer, beta[i]); assert(noise || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, noise[i]); + microstrain_insert_float(&serializer, noise[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, float* beta_out, float* noise_out) { @@ -1861,10 +1931,11 @@ mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, fl insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1873,13 +1944,13 @@ mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, fl assert(beta_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &beta_out[i]); + microstrain_extract_float(&deserializer, &beta_out[i]); assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &noise_out[i]); + microstrain_extract_float(&deserializer, &noise_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -1892,9 +1963,10 @@ mip_cmd_result mip_filter_save_accel_bias_model(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_accel_bias_model(struct mip_interface* device) { @@ -1904,9 +1976,10 @@ mip_cmd_result mip_filter_load_accel_bias_model(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_accel_bias_model(struct mip_interface* device) { @@ -1916,9 +1989,10 @@ mip_cmd_result mip_filter_default_accel_bias_model(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_gyro_bias_model_command(mip_serializer* serializer, const mip_filter_gyro_bias_model_command* self) { @@ -1927,10 +2001,10 @@ void insert_mip_filter_gyro_bias_model_command(mip_serializer* serializer, const if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->beta[i]); + microstrain_insert_float(serializer, self->beta[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } } @@ -1941,10 +2015,10 @@ void extract_mip_filter_gyro_bias_model_command(mip_serializer* serializer, mip_ if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->beta[i]); + microstrain_extract_float(serializer, &self->beta[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } } @@ -1952,19 +2026,19 @@ void extract_mip_filter_gyro_bias_model_command(mip_serializer* serializer, mip_ void insert_mip_filter_gyro_bias_model_response(mip_serializer* serializer, const mip_filter_gyro_bias_model_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->beta[i]); + microstrain_insert_float(serializer, self->beta[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } void extract_mip_filter_gyro_bias_model_response(mip_serializer* serializer, mip_filter_gyro_bias_model_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->beta[i]); + microstrain_extract_float(serializer, &self->beta[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } @@ -1978,15 +2052,16 @@ mip_cmd_result mip_filter_write_gyro_bias_model(struct mip_interface* device, co assert(beta || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, beta[i]); + microstrain_insert_float(&serializer, beta[i]); assert(noise || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, noise[i]); + microstrain_insert_float(&serializer, noise[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, float* beta_out, float* noise_out) { @@ -1996,10 +2071,11 @@ mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, flo insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_GYRO_BIAS_MODEL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_GYRO_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2008,13 +2084,13 @@ mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, flo assert(beta_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &beta_out[i]); + microstrain_extract_float(&deserializer, &beta_out[i]); assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &noise_out[i]); + microstrain_extract_float(&deserializer, &noise_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2027,9 +2103,10 @@ mip_cmd_result mip_filter_save_gyro_bias_model(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_gyro_bias_model(struct mip_interface* device) { @@ -2039,9 +2116,10 @@ mip_cmd_result mip_filter_load_gyro_bias_model(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_gyro_bias_model(struct mip_interface* device) { @@ -2051,9 +2129,10 @@ mip_cmd_result mip_filter_default_gyro_bias_model(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_altitude_aiding_command(mip_serializer* serializer, const mip_filter_altitude_aiding_command* self) { @@ -2089,12 +2168,12 @@ void extract_mip_filter_altitude_aiding_response(mip_serializer* serializer, mip void insert_mip_filter_altitude_aiding_command_aiding_selector(struct mip_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_altitude_aiding_command_aiding_selector(struct mip_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -2108,9 +2187,10 @@ mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, mi insert_mip_filter_altitude_aiding_command_aiding_selector(&serializer, selector); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector* selector_out) { @@ -2120,10 +2200,11 @@ mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2133,7 +2214,7 @@ mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip assert(selector_out); extract_mip_filter_altitude_aiding_command_aiding_selector(&deserializer, selector_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2146,9 +2227,10 @@ mip_cmd_result mip_filter_save_altitude_aiding(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device) { @@ -2158,9 +2240,10 @@ mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device) { @@ -2170,9 +2253,10 @@ mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_pitch_roll_aiding_command(mip_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self) { @@ -2208,12 +2292,12 @@ void extract_mip_filter_pitch_roll_aiding_response(mip_serializer* serializer, m void insert_mip_filter_pitch_roll_aiding_command_aiding_source(struct mip_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_pitch_roll_aiding_command_aiding_source(struct mip_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -2227,9 +2311,10 @@ mip_cmd_result mip_filter_write_pitch_roll_aiding(struct mip_interface* device, insert_mip_filter_pitch_roll_aiding_command_aiding_source(&serializer, source); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source* source_out) { @@ -2239,10 +2324,11 @@ mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, m insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2252,7 +2338,7 @@ mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, m assert(source_out); extract_mip_filter_pitch_roll_aiding_command_aiding_source(&deserializer, source_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2265,9 +2351,10 @@ mip_cmd_result mip_filter_save_pitch_roll_aiding(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_pitch_roll_aiding(struct mip_interface* device) { @@ -2277,9 +2364,10 @@ mip_cmd_result mip_filter_load_pitch_roll_aiding(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_pitch_roll_aiding(struct mip_interface* device) { @@ -2289,9 +2377,10 @@ mip_cmd_result mip_filter_default_pitch_roll_aiding(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_auto_zupt_command(mip_serializer* serializer, const mip_filter_auto_zupt_command* self) { @@ -2299,9 +2388,9 @@ void insert_mip_filter_auto_zupt_command(mip_serializer* serializer, const mip_f if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable); - - insert_float(serializer, self->threshold); + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_float(serializer, self->threshold); } } @@ -2311,25 +2400,25 @@ void extract_mip_filter_auto_zupt_command(mip_serializer* serializer, mip_filter if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable); - - extract_float(serializer, &self->threshold); + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->threshold); } } void insert_mip_filter_auto_zupt_response(mip_serializer* serializer, const mip_filter_auto_zupt_response* self) { - insert_u8(serializer, self->enable); - - insert_float(serializer, self->threshold); + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_float(serializer, self->threshold); } void extract_mip_filter_auto_zupt_response(mip_serializer* serializer, mip_filter_auto_zupt_response* self) { - extract_u8(serializer, &self->enable); - - extract_float(serializer, &self->threshold); + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->threshold); } @@ -2340,14 +2429,15 @@ mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, enable); + + microstrain_insert_float(&serializer, threshold); - insert_u8(&serializer, enable); - - insert_float(&serializer, threshold); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out) { @@ -2357,10 +2447,11 @@ mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ZUPT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2368,12 +2459,12 @@ mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_u8(&deserializer, enable_out); + microstrain_extract_u8(&deserializer, enable_out); assert(threshold_out); - extract_float(&deserializer, threshold_out); + microstrain_extract_float(&deserializer, threshold_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2386,9 +2477,10 @@ mip_cmd_result mip_filter_save_auto_zupt(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device) { @@ -2398,9 +2490,10 @@ mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device) { @@ -2410,9 +2503,10 @@ mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, const mip_filter_auto_angular_zupt_command* self) { @@ -2420,9 +2514,9 @@ void insert_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, con if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable); - - insert_float(serializer, self->threshold); + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_float(serializer, self->threshold); } } @@ -2432,25 +2526,25 @@ void extract_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, mi if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable); - - extract_float(serializer, &self->threshold); + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->threshold); } } void insert_mip_filter_auto_angular_zupt_response(mip_serializer* serializer, const mip_filter_auto_angular_zupt_response* self) { - insert_u8(serializer, self->enable); - - insert_float(serializer, self->threshold); + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_float(serializer, self->threshold); } void extract_mip_filter_auto_angular_zupt_response(mip_serializer* serializer, mip_filter_auto_angular_zupt_response* self) { - extract_u8(serializer, &self->enable); - - extract_float(serializer, &self->threshold); + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->threshold); } @@ -2461,14 +2555,15 @@ mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, enable); + + microstrain_insert_float(&serializer, threshold); - insert_u8(&serializer, enable); - - insert_float(&serializer, threshold); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out) { @@ -2478,10 +2573,11 @@ mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, u insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2489,12 +2585,12 @@ mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, u mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_u8(&deserializer, enable_out); + microstrain_extract_u8(&deserializer, enable_out); assert(threshold_out); - extract_float(&deserializer, threshold_out); + microstrain_extract_float(&deserializer, threshold_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2507,9 +2603,10 @@ mip_cmd_result mip_filter_save_auto_angular_zupt(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device) { @@ -2519,9 +2616,10 @@ mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device) { @@ -2531,9 +2629,10 @@ mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_commanded_zupt(struct mip_interface* device) { @@ -2562,9 +2661,10 @@ mip_cmd_result mip_filter_write_mag_capture_auto_cal(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device) { @@ -2574,9 +2674,10 @@ mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_gravity_noise_command(mip_serializer* serializer, const mip_filter_gravity_noise_command* self) { @@ -2585,7 +2686,7 @@ void insert_mip_filter_gravity_noise_command(mip_serializer* serializer, const m if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } } @@ -2596,7 +2697,7 @@ void extract_mip_filter_gravity_noise_command(mip_serializer* serializer, mip_fi if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } } @@ -2604,13 +2705,13 @@ void extract_mip_filter_gravity_noise_command(mip_serializer* serializer, mip_fi void insert_mip_filter_gravity_noise_response(mip_serializer* serializer, const mip_filter_gravity_noise_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } void extract_mip_filter_gravity_noise_response(mip_serializer* serializer, mip_filter_gravity_noise_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } @@ -2624,11 +2725,12 @@ mip_cmd_result mip_filter_write_gravity_noise(struct mip_interface* device, cons assert(noise || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, noise[i]); + microstrain_insert_float(&serializer, noise[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float* noise_out) { @@ -2638,10 +2740,11 @@ mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_GRAVITY_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_GRAVITY_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2650,9 +2753,9 @@ mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &noise_out[i]); + microstrain_extract_float(&deserializer, &noise_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2665,9 +2768,10 @@ mip_cmd_result mip_filter_save_gravity_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_gravity_noise(struct mip_interface* device) { @@ -2677,9 +2781,10 @@ mip_cmd_result mip_filter_load_gravity_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_gravity_noise(struct mip_interface* device) { @@ -2689,9 +2794,10 @@ mip_cmd_result mip_filter_default_gravity_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_pressure_altitude_noise_command(mip_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self) { @@ -2699,7 +2805,7 @@ void insert_mip_filter_pressure_altitude_noise_command(mip_serializer* serialize if( self->function == MIP_FUNCTION_WRITE ) { - insert_float(serializer, self->noise); + microstrain_insert_float(serializer, self->noise); } } @@ -2709,19 +2815,19 @@ void extract_mip_filter_pressure_altitude_noise_command(mip_serializer* serializ if( self->function == MIP_FUNCTION_WRITE ) { - extract_float(serializer, &self->noise); + microstrain_extract_float(serializer, &self->noise); } } void insert_mip_filter_pressure_altitude_noise_response(mip_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self) { - insert_float(serializer, self->noise); + microstrain_insert_float(serializer, self->noise); } void extract_mip_filter_pressure_altitude_noise_response(mip_serializer* serializer, mip_filter_pressure_altitude_noise_response* self) { - extract_float(serializer, &self->noise); + microstrain_extract_float(serializer, &self->noise); } @@ -2732,12 +2838,13 @@ mip_cmd_result mip_filter_write_pressure_altitude_noise(struct mip_interface* de mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_float(&serializer, noise); - insert_float(&serializer, noise); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* device, float* noise_out) { @@ -2747,10 +2854,11 @@ mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* dev insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_PRESSURE_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_PRESSURE_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2758,9 +2866,9 @@ mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* dev mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(noise_out); - extract_float(&deserializer, noise_out); + microstrain_extract_float(&deserializer, noise_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2773,9 +2881,10 @@ mip_cmd_result mip_filter_save_pressure_altitude_noise(struct mip_interface* dev insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_pressure_altitude_noise(struct mip_interface* device) { @@ -2785,9 +2894,10 @@ mip_cmd_result mip_filter_load_pressure_altitude_noise(struct mip_interface* dev insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_pressure_altitude_noise(struct mip_interface* device) { @@ -2797,9 +2907,10 @@ mip_cmd_result mip_filter_default_pressure_altitude_noise(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_hard_iron_offset_noise_command(mip_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self) { @@ -2808,7 +2919,7 @@ void insert_mip_filter_hard_iron_offset_noise_command(mip_serializer* serializer if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } } @@ -2819,7 +2930,7 @@ void extract_mip_filter_hard_iron_offset_noise_command(mip_serializer* serialize if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } } @@ -2827,13 +2938,13 @@ void extract_mip_filter_hard_iron_offset_noise_command(mip_serializer* serialize void insert_mip_filter_hard_iron_offset_noise_response(mip_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } void extract_mip_filter_hard_iron_offset_noise_response(mip_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } @@ -2847,11 +2958,12 @@ mip_cmd_result mip_filter_write_hard_iron_offset_noise(struct mip_interface* dev assert(noise || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, noise[i]); + microstrain_insert_float(&serializer, noise[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* device, float* noise_out) { @@ -2861,10 +2973,11 @@ mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2873,9 +2986,9 @@ mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* devi assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &noise_out[i]); + microstrain_extract_float(&deserializer, &noise_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2888,9 +3001,10 @@ mip_cmd_result mip_filter_save_hard_iron_offset_noise(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_hard_iron_offset_noise(struct mip_interface* device) { @@ -2900,9 +3014,10 @@ mip_cmd_result mip_filter_load_hard_iron_offset_noise(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_hard_iron_offset_noise(struct mip_interface* device) { @@ -2912,9 +3027,10 @@ mip_cmd_result mip_filter_default_hard_iron_offset_noise(struct mip_interface* d insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self) { @@ -2923,7 +3039,7 @@ void insert_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serializer if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } } @@ -2934,7 +3050,7 @@ void extract_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serialize if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } } @@ -2942,13 +3058,13 @@ void extract_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serialize void insert_mip_filter_soft_iron_matrix_noise_response(mip_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } void extract_mip_filter_soft_iron_matrix_noise_response(mip_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } @@ -2962,11 +3078,12 @@ mip_cmd_result mip_filter_write_soft_iron_matrix_noise(struct mip_interface* dev assert(noise || (9 == 0)); for(unsigned int i=0; i < 9; i++) - insert_float(&serializer, noise[i]); + microstrain_insert_float(&serializer, noise[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* device, float* noise_out) { @@ -2976,10 +3093,11 @@ mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2988,9 +3106,9 @@ mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* devi assert(noise_out || (9 == 0)); for(unsigned int i=0; i < 9; i++) - extract_float(&deserializer, &noise_out[i]); + microstrain_extract_float(&deserializer, &noise_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3003,9 +3121,10 @@ mip_cmd_result mip_filter_save_soft_iron_matrix_noise(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_soft_iron_matrix_noise(struct mip_interface* device) { @@ -3015,9 +3134,10 @@ mip_cmd_result mip_filter_load_soft_iron_matrix_noise(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_soft_iron_matrix_noise(struct mip_interface* device) { @@ -3027,9 +3147,10 @@ mip_cmd_result mip_filter_default_soft_iron_matrix_noise(struct mip_interface* d insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_mag_noise_command(mip_serializer* serializer, const mip_filter_mag_noise_command* self) { @@ -3038,7 +3159,7 @@ void insert_mip_filter_mag_noise_command(mip_serializer* serializer, const mip_f if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } } @@ -3049,7 +3170,7 @@ void extract_mip_filter_mag_noise_command(mip_serializer* serializer, mip_filter if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } } @@ -3057,13 +3178,13 @@ void extract_mip_filter_mag_noise_command(mip_serializer* serializer, mip_filter void insert_mip_filter_mag_noise_response(mip_serializer* serializer, const mip_filter_mag_noise_response* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->noise[i]); + microstrain_insert_float(serializer, self->noise[i]); } void extract_mip_filter_mag_noise_response(mip_serializer* serializer, mip_filter_mag_noise_response* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->noise[i]); + microstrain_extract_float(serializer, &self->noise[i]); } @@ -3077,11 +3198,12 @@ mip_cmd_result mip_filter_write_mag_noise(struct mip_interface* device, const fl assert(noise || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, noise[i]); + microstrain_insert_float(&serializer, noise[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* noise_out) { @@ -3091,10 +3213,11 @@ mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* no insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MAG_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_MAG_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3103,9 +3226,9 @@ mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* no assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &noise_out[i]); + microstrain_extract_float(&deserializer, &noise_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3118,9 +3241,10 @@ mip_cmd_result mip_filter_save_mag_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_mag_noise(struct mip_interface* device) { @@ -3130,9 +3254,10 @@ mip_cmd_result mip_filter_load_mag_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_mag_noise(struct mip_interface* device) { @@ -3142,9 +3267,10 @@ mip_cmd_result mip_filter_default_mag_noise(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_inclination_source_command(mip_serializer* serializer, const mip_filter_inclination_source_command* self) { @@ -3153,8 +3279,8 @@ void insert_mip_filter_inclination_source_command(mip_serializer* serializer, co if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_mag_param_source(serializer, self->source); - - insert_float(serializer, self->inclination); + + microstrain_insert_float(serializer, self->inclination); } } @@ -3165,8 +3291,8 @@ void extract_mip_filter_inclination_source_command(mip_serializer* serializer, m if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_mag_param_source(serializer, &self->source); - - extract_float(serializer, &self->inclination); + + microstrain_extract_float(serializer, &self->inclination); } } @@ -3174,15 +3300,15 @@ void extract_mip_filter_inclination_source_command(mip_serializer* serializer, m void insert_mip_filter_inclination_source_response(mip_serializer* serializer, const mip_filter_inclination_source_response* self) { insert_mip_filter_mag_param_source(serializer, self->source); - - insert_float(serializer, self->inclination); + + microstrain_insert_float(serializer, self->inclination); } void extract_mip_filter_inclination_source_response(mip_serializer* serializer, mip_filter_inclination_source_response* self) { extract_mip_filter_mag_param_source(serializer, &self->source); - - extract_float(serializer, &self->inclination); + + microstrain_extract_float(serializer, &self->inclination); } @@ -3195,12 +3321,13 @@ mip_cmd_result mip_filter_write_inclination_source(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_mag_param_source(&serializer, source); + + microstrain_insert_float(&serializer, inclination); - insert_float(&serializer, inclination); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* inclination_out) { @@ -3210,10 +3337,11 @@ mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_INCLINATION_SOURCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_INCLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3224,9 +3352,9 @@ mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, extract_mip_filter_mag_param_source(&deserializer, source_out); assert(inclination_out); - extract_float(&deserializer, inclination_out); + microstrain_extract_float(&deserializer, inclination_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3239,9 +3367,10 @@ mip_cmd_result mip_filter_save_inclination_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_inclination_source(struct mip_interface* device) { @@ -3251,9 +3380,10 @@ mip_cmd_result mip_filter_load_inclination_source(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_inclination_source(struct mip_interface* device) { @@ -3263,9 +3393,10 @@ mip_cmd_result mip_filter_default_inclination_source(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_magnetic_declination_source_command(mip_serializer* serializer, const mip_filter_magnetic_declination_source_command* self) { @@ -3274,8 +3405,8 @@ void insert_mip_filter_magnetic_declination_source_command(mip_serializer* seria if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_mag_param_source(serializer, self->source); - - insert_float(serializer, self->declination); + + microstrain_insert_float(serializer, self->declination); } } @@ -3286,8 +3417,8 @@ void extract_mip_filter_magnetic_declination_source_command(mip_serializer* seri if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_mag_param_source(serializer, &self->source); - - extract_float(serializer, &self->declination); + + microstrain_extract_float(serializer, &self->declination); } } @@ -3295,15 +3426,15 @@ void extract_mip_filter_magnetic_declination_source_command(mip_serializer* seri void insert_mip_filter_magnetic_declination_source_response(mip_serializer* serializer, const mip_filter_magnetic_declination_source_response* self) { insert_mip_filter_mag_param_source(serializer, self->source); - - insert_float(serializer, self->declination); + + microstrain_insert_float(serializer, self->declination); } void extract_mip_filter_magnetic_declination_source_response(mip_serializer* serializer, mip_filter_magnetic_declination_source_response* self) { extract_mip_filter_mag_param_source(serializer, &self->source); - - extract_float(serializer, &self->declination); + + microstrain_extract_float(serializer, &self->declination); } @@ -3316,12 +3447,13 @@ mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_mag_param_source(&serializer, source); + + microstrain_insert_float(&serializer, declination); - insert_float(&serializer, declination); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* declination_out) { @@ -3331,10 +3463,11 @@ mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_DECLINATION_SOURCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_DECLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3345,9 +3478,9 @@ mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* extract_mip_filter_mag_param_source(&deserializer, source_out); assert(declination_out); - extract_float(&deserializer, declination_out); + microstrain_extract_float(&deserializer, declination_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3360,9 +3493,10 @@ mip_cmd_result mip_filter_save_magnetic_declination_source(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_magnetic_declination_source(struct mip_interface* device) { @@ -3372,9 +3506,10 @@ mip_cmd_result mip_filter_load_magnetic_declination_source(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_magnetic_declination_source(struct mip_interface* device) { @@ -3384,9 +3519,10 @@ mip_cmd_result mip_filter_default_magnetic_declination_source(struct mip_interfa insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_mag_field_magnitude_source_command(mip_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self) { @@ -3395,8 +3531,8 @@ void insert_mip_filter_mag_field_magnitude_source_command(mip_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_mag_param_source(serializer, self->source); - - insert_float(serializer, self->magnitude); + + microstrain_insert_float(serializer, self->magnitude); } } @@ -3407,8 +3543,8 @@ void extract_mip_filter_mag_field_magnitude_source_command(mip_serializer* seria if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_mag_param_source(serializer, &self->source); - - extract_float(serializer, &self->magnitude); + + microstrain_extract_float(serializer, &self->magnitude); } } @@ -3416,15 +3552,15 @@ void extract_mip_filter_mag_field_magnitude_source_command(mip_serializer* seria void insert_mip_filter_mag_field_magnitude_source_response(mip_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self) { insert_mip_filter_mag_param_source(serializer, self->source); - - insert_float(serializer, self->magnitude); + + microstrain_insert_float(serializer, self->magnitude); } void extract_mip_filter_mag_field_magnitude_source_response(mip_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self) { extract_mip_filter_mag_param_source(serializer, &self->source); - - extract_float(serializer, &self->magnitude); + + microstrain_extract_float(serializer, &self->magnitude); } @@ -3437,12 +3573,13 @@ mip_cmd_result mip_filter_write_mag_field_magnitude_source(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_mag_param_source(&serializer, source); + + microstrain_insert_float(&serializer, magnitude); - insert_float(&serializer, magnitude); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* magnitude_out) { @@ -3452,10 +3589,11 @@ mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3466,9 +3604,9 @@ mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* extract_mip_filter_mag_param_source(&deserializer, source_out); assert(magnitude_out); - extract_float(&deserializer, magnitude_out); + microstrain_extract_float(&deserializer, magnitude_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3481,9 +3619,10 @@ mip_cmd_result mip_filter_save_mag_field_magnitude_source(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_mag_field_magnitude_source(struct mip_interface* device) { @@ -3493,9 +3632,10 @@ mip_cmd_result mip_filter_load_mag_field_magnitude_source(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_mag_field_magnitude_source(struct mip_interface* device) { @@ -3505,9 +3645,10 @@ mip_cmd_result mip_filter_default_mag_field_magnitude_source(struct mip_interfac insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_reference_position_command(mip_serializer* serializer, const mip_filter_reference_position_command* self) { @@ -3515,13 +3656,13 @@ void insert_mip_filter_reference_position_command(mip_serializer* serializer, co if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->enable); - - insert_double(serializer, self->latitude); - - insert_double(serializer, self->longitude); - - insert_double(serializer, self->altitude); + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_double(serializer, self->latitude); + + microstrain_insert_double(serializer, self->longitude); + + microstrain_insert_double(serializer, self->altitude); } } @@ -3531,37 +3672,37 @@ void extract_mip_filter_reference_position_command(mip_serializer* serializer, m if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->enable); - - extract_double(serializer, &self->latitude); - - extract_double(serializer, &self->longitude); - - extract_double(serializer, &self->altitude); + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_double(serializer, &self->latitude); + + microstrain_extract_double(serializer, &self->longitude); + + microstrain_extract_double(serializer, &self->altitude); } } void insert_mip_filter_reference_position_response(mip_serializer* serializer, const mip_filter_reference_position_response* self) { - insert_bool(serializer, self->enable); - - insert_double(serializer, self->latitude); - - insert_double(serializer, self->longitude); - - insert_double(serializer, self->altitude); + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_double(serializer, self->latitude); + + microstrain_insert_double(serializer, self->longitude); + + microstrain_insert_double(serializer, self->altitude); } void extract_mip_filter_reference_position_response(mip_serializer* serializer, mip_filter_reference_position_response* self) { - extract_bool(serializer, &self->enable); - - extract_double(serializer, &self->latitude); - - extract_double(serializer, &self->longitude); - - extract_double(serializer, &self->altitude); + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_double(serializer, &self->latitude); + + microstrain_extract_double(serializer, &self->longitude); + + microstrain_extract_double(serializer, &self->altitude); } @@ -3572,18 +3713,19 @@ mip_cmd_result mip_filter_write_reference_position(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_bool(&serializer, enable); + + microstrain_insert_double(&serializer, latitude); + + microstrain_insert_double(&serializer, longitude); + + microstrain_insert_double(&serializer, altitude); - insert_bool(&serializer, enable); - - insert_double(&serializer, latitude); - - insert_double(&serializer, longitude); - - insert_double(&serializer, altitude); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, bool* enable_out, double* latitude_out, double* longitude_out, double* altitude_out) { @@ -3593,10 +3735,11 @@ mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_REFERENCE_POSITION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_REFERENCE_POSITION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3604,18 +3747,18 @@ mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_bool(&deserializer, enable_out); + microstrain_extract_bool(&deserializer, enable_out); assert(latitude_out); - extract_double(&deserializer, latitude_out); + microstrain_extract_double(&deserializer, latitude_out); assert(longitude_out); - extract_double(&deserializer, longitude_out); + microstrain_extract_double(&deserializer, longitude_out); assert(altitude_out); - extract_double(&deserializer, altitude_out); + microstrain_extract_double(&deserializer, altitude_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3628,9 +3771,10 @@ mip_cmd_result mip_filter_save_reference_position(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_reference_position(struct mip_interface* device) { @@ -3640,9 +3784,10 @@ mip_cmd_result mip_filter_load_reference_position(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_reference_position(struct mip_interface* device) { @@ -3652,9 +3797,10 @@ mip_cmd_result mip_filter_default_reference_position(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self) { @@ -3663,18 +3809,18 @@ void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_se if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - - insert_float(serializer, self->frequency); - - insert_float(serializer, self->low_limit); - - insert_float(serializer, self->high_limit); - - insert_float(serializer, self->low_limit_uncertainty); - - insert_float(serializer, self->high_limit_uncertainty); - - insert_float(serializer, self->minimum_uncertainty); + + microstrain_insert_float(serializer, self->frequency); + + microstrain_insert_float(serializer, self->low_limit); + + microstrain_insert_float(serializer, self->high_limit); + + microstrain_insert_float(serializer, self->low_limit_uncertainty); + + microstrain_insert_float(serializer, self->high_limit_uncertainty); + + microstrain_insert_float(serializer, self->minimum_uncertainty); } } @@ -3685,18 +3831,18 @@ void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_s if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - - extract_float(serializer, &self->frequency); - - extract_float(serializer, &self->low_limit); - - extract_float(serializer, &self->high_limit); - - extract_float(serializer, &self->low_limit_uncertainty); - - extract_float(serializer, &self->high_limit_uncertainty); - - extract_float(serializer, &self->minimum_uncertainty); + + microstrain_extract_float(serializer, &self->frequency); + + microstrain_extract_float(serializer, &self->low_limit); + + microstrain_extract_float(serializer, &self->high_limit); + + microstrain_extract_float(serializer, &self->low_limit_uncertainty); + + microstrain_extract_float(serializer, &self->high_limit_uncertainty); + + microstrain_extract_float(serializer, &self->minimum_uncertainty); } } @@ -3704,35 +3850,35 @@ void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_s void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self) { insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - - insert_float(serializer, self->frequency); - - insert_float(serializer, self->low_limit); - - insert_float(serializer, self->high_limit); - - insert_float(serializer, self->low_limit_uncertainty); - - insert_float(serializer, self->high_limit_uncertainty); - - insert_float(serializer, self->minimum_uncertainty); + + microstrain_insert_float(serializer, self->frequency); + + microstrain_insert_float(serializer, self->low_limit); + + microstrain_insert_float(serializer, self->high_limit); + + microstrain_insert_float(serializer, self->low_limit_uncertainty); + + microstrain_insert_float(serializer, self->high_limit_uncertainty); + + microstrain_insert_float(serializer, self->minimum_uncertainty); } void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self) { extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - - extract_float(serializer, &self->frequency); - - extract_float(serializer, &self->low_limit); - - extract_float(serializer, &self->high_limit); - - extract_float(serializer, &self->low_limit_uncertainty); - - extract_float(serializer, &self->high_limit_uncertainty); - - extract_float(serializer, &self->minimum_uncertainty); + + microstrain_extract_float(serializer, &self->frequency); + + microstrain_extract_float(serializer, &self->low_limit); + + microstrain_extract_float(serializer, &self->high_limit); + + microstrain_extract_float(serializer, &self->low_limit_uncertainty); + + microstrain_extract_float(serializer, &self->high_limit_uncertainty); + + microstrain_extract_float(serializer, &self->minimum_uncertainty); } @@ -3745,22 +3891,23 @@ mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(struc insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_adaptive_measurement(&serializer, adaptive_measurement); + + microstrain_insert_float(&serializer, frequency); + + microstrain_insert_float(&serializer, low_limit); + + microstrain_insert_float(&serializer, high_limit); + + microstrain_insert_float(&serializer, low_limit_uncertainty); + + microstrain_insert_float(&serializer, high_limit_uncertainty); + + microstrain_insert_float(&serializer, minimum_uncertainty); - insert_float(&serializer, frequency); - - insert_float(&serializer, low_limit); - - insert_float(&serializer, high_limit); - - insert_float(&serializer, low_limit_uncertainty); - - insert_float(&serializer, high_limit_uncertainty); - - insert_float(&serializer, minimum_uncertainty); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) { @@ -3770,10 +3917,11 @@ mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3784,24 +3932,24 @@ mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct extract_mip_filter_adaptive_measurement(&deserializer, adaptive_measurement_out); assert(frequency_out); - extract_float(&deserializer, frequency_out); + microstrain_extract_float(&deserializer, frequency_out); assert(low_limit_out); - extract_float(&deserializer, low_limit_out); + microstrain_extract_float(&deserializer, low_limit_out); assert(high_limit_out); - extract_float(&deserializer, high_limit_out); + microstrain_extract_float(&deserializer, high_limit_out); assert(low_limit_uncertainty_out); - extract_float(&deserializer, low_limit_uncertainty_out); + microstrain_extract_float(&deserializer, low_limit_uncertainty_out); assert(high_limit_uncertainty_out); - extract_float(&deserializer, high_limit_uncertainty_out); + microstrain_extract_float(&deserializer, high_limit_uncertainty_out); assert(minimum_uncertainty_out); - extract_float(&deserializer, minimum_uncertainty_out); + microstrain_extract_float(&deserializer, minimum_uncertainty_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3814,9 +3962,10 @@ mip_cmd_result mip_filter_save_accel_magnitude_error_adaptive_measurement(struct insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) { @@ -3826,9 +3975,10 @@ mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(struct insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) { @@ -3838,9 +3988,10 @@ mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(str insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self) { @@ -3849,18 +4000,18 @@ void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_seri if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - - insert_float(serializer, self->frequency); - - insert_float(serializer, self->low_limit); - - insert_float(serializer, self->high_limit); - - insert_float(serializer, self->low_limit_uncertainty); - - insert_float(serializer, self->high_limit_uncertainty); - - insert_float(serializer, self->minimum_uncertainty); + + microstrain_insert_float(serializer, self->frequency); + + microstrain_insert_float(serializer, self->low_limit); + + microstrain_insert_float(serializer, self->high_limit); + + microstrain_insert_float(serializer, self->low_limit_uncertainty); + + microstrain_insert_float(serializer, self->high_limit_uncertainty); + + microstrain_insert_float(serializer, self->minimum_uncertainty); } } @@ -3871,18 +4022,18 @@ void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_ser if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - - extract_float(serializer, &self->frequency); - - extract_float(serializer, &self->low_limit); - - extract_float(serializer, &self->high_limit); - - extract_float(serializer, &self->low_limit_uncertainty); - - extract_float(serializer, &self->high_limit_uncertainty); - - extract_float(serializer, &self->minimum_uncertainty); + + microstrain_extract_float(serializer, &self->frequency); + + microstrain_extract_float(serializer, &self->low_limit); + + microstrain_extract_float(serializer, &self->high_limit); + + microstrain_extract_float(serializer, &self->low_limit_uncertainty); + + microstrain_extract_float(serializer, &self->high_limit_uncertainty); + + microstrain_extract_float(serializer, &self->minimum_uncertainty); } } @@ -3890,35 +4041,35 @@ void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_ser void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self) { insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - - insert_float(serializer, self->frequency); - - insert_float(serializer, self->low_limit); - - insert_float(serializer, self->high_limit); - - insert_float(serializer, self->low_limit_uncertainty); - - insert_float(serializer, self->high_limit_uncertainty); - - insert_float(serializer, self->minimum_uncertainty); + + microstrain_insert_float(serializer, self->frequency); + + microstrain_insert_float(serializer, self->low_limit); + + microstrain_insert_float(serializer, self->high_limit); + + microstrain_insert_float(serializer, self->low_limit_uncertainty); + + microstrain_insert_float(serializer, self->high_limit_uncertainty); + + microstrain_insert_float(serializer, self->minimum_uncertainty); } void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self) { extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - - extract_float(serializer, &self->frequency); - - extract_float(serializer, &self->low_limit); - - extract_float(serializer, &self->high_limit); - - extract_float(serializer, &self->low_limit_uncertainty); - - extract_float(serializer, &self->high_limit_uncertainty); - - extract_float(serializer, &self->minimum_uncertainty); + + microstrain_extract_float(serializer, &self->frequency); + + microstrain_extract_float(serializer, &self->low_limit); + + microstrain_extract_float(serializer, &self->high_limit); + + microstrain_extract_float(serializer, &self->low_limit_uncertainty); + + microstrain_extract_float(serializer, &self->high_limit_uncertainty); + + microstrain_extract_float(serializer, &self->minimum_uncertainty); } @@ -3931,22 +4082,23 @@ mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(struct insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_adaptive_measurement(&serializer, adaptive_measurement); + + microstrain_insert_float(&serializer, frequency); + + microstrain_insert_float(&serializer, low_limit); + + microstrain_insert_float(&serializer, high_limit); + + microstrain_insert_float(&serializer, low_limit_uncertainty); + + microstrain_insert_float(&serializer, high_limit_uncertainty); + + microstrain_insert_float(&serializer, minimum_uncertainty); - insert_float(&serializer, frequency); - - insert_float(&serializer, low_limit); - - insert_float(&serializer, high_limit); - - insert_float(&serializer, low_limit_uncertainty); - - insert_float(&serializer, high_limit_uncertainty); - - insert_float(&serializer, minimum_uncertainty); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) { @@ -3956,10 +4108,11 @@ mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct m insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3970,24 +4123,24 @@ mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct m extract_mip_filter_adaptive_measurement(&deserializer, adaptive_measurement_out); assert(frequency_out); - extract_float(&deserializer, frequency_out); + microstrain_extract_float(&deserializer, frequency_out); assert(low_limit_out); - extract_float(&deserializer, low_limit_out); + microstrain_extract_float(&deserializer, low_limit_out); assert(high_limit_out); - extract_float(&deserializer, high_limit_out); + microstrain_extract_float(&deserializer, high_limit_out); assert(low_limit_uncertainty_out); - extract_float(&deserializer, low_limit_uncertainty_out); + microstrain_extract_float(&deserializer, low_limit_uncertainty_out); assert(high_limit_uncertainty_out); - extract_float(&deserializer, high_limit_uncertainty_out); + microstrain_extract_float(&deserializer, high_limit_uncertainty_out); assert(minimum_uncertainty_out); - extract_float(&deserializer, minimum_uncertainty_out); + microstrain_extract_float(&deserializer, minimum_uncertainty_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4000,9 +4153,10 @@ mip_cmd_result mip_filter_save_mag_magnitude_error_adaptive_measurement(struct m insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) { @@ -4012,9 +4166,10 @@ mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(struct m insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) { @@ -4024,9 +4179,10 @@ mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(struc insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(mip_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self) { @@ -4034,15 +4190,15 @@ void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(mip_seri if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->enable); - - insert_float(serializer, self->frequency); - - insert_float(serializer, self->high_limit); - - insert_float(serializer, self->high_limit_uncertainty); - - insert_float(serializer, self->minimum_uncertainty); + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_float(serializer, self->frequency); + + microstrain_insert_float(serializer, self->high_limit); + + microstrain_insert_float(serializer, self->high_limit_uncertainty); + + microstrain_insert_float(serializer, self->minimum_uncertainty); } } @@ -4052,43 +4208,43 @@ void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(mip_ser if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->enable); - - extract_float(serializer, &self->frequency); - - extract_float(serializer, &self->high_limit); - - extract_float(serializer, &self->high_limit_uncertainty); - - extract_float(serializer, &self->minimum_uncertainty); + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->frequency); + + microstrain_extract_float(serializer, &self->high_limit); + + microstrain_extract_float(serializer, &self->high_limit_uncertainty); + + microstrain_extract_float(serializer, &self->minimum_uncertainty); } } void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(mip_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) { - insert_bool(serializer, self->enable); - - insert_float(serializer, self->frequency); - - insert_float(serializer, self->high_limit); - - insert_float(serializer, self->high_limit_uncertainty); - - insert_float(serializer, self->minimum_uncertainty); + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_float(serializer, self->frequency); + + microstrain_insert_float(serializer, self->high_limit); + + microstrain_insert_float(serializer, self->high_limit_uncertainty); + + microstrain_insert_float(serializer, self->minimum_uncertainty); } void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(mip_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) { - extract_bool(serializer, &self->enable); - - extract_float(serializer, &self->frequency); - - extract_float(serializer, &self->high_limit); - - extract_float(serializer, &self->high_limit_uncertainty); - - extract_float(serializer, &self->minimum_uncertainty); + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->frequency); + + microstrain_extract_float(serializer, &self->high_limit); + + microstrain_extract_float(serializer, &self->high_limit_uncertainty); + + microstrain_extract_float(serializer, &self->minimum_uncertainty); } @@ -4099,20 +4255,21 @@ mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(struct mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_bool(&serializer, enable); + + microstrain_insert_float(&serializer, frequency); + + microstrain_insert_float(&serializer, high_limit); + + microstrain_insert_float(&serializer, high_limit_uncertainty); + + microstrain_insert_float(&serializer, minimum_uncertainty); - insert_bool(&serializer, enable); - - insert_float(&serializer, frequency); - - insert_float(&serializer, high_limit); - - insert_float(&serializer, high_limit_uncertainty); - - insert_float(&serializer, minimum_uncertainty); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool* enable_out, float* frequency_out, float* high_limit_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) { @@ -4122,10 +4279,11 @@ mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct m insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4133,21 +4291,21 @@ mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct m mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_bool(&deserializer, enable_out); + microstrain_extract_bool(&deserializer, enable_out); assert(frequency_out); - extract_float(&deserializer, frequency_out); + microstrain_extract_float(&deserializer, frequency_out); assert(high_limit_out); - extract_float(&deserializer, high_limit_out); + microstrain_extract_float(&deserializer, high_limit_out); assert(high_limit_uncertainty_out); - extract_float(&deserializer, high_limit_uncertainty_out); + microstrain_extract_float(&deserializer, high_limit_uncertainty_out); assert(minimum_uncertainty_out); - extract_float(&deserializer, minimum_uncertainty_out); + microstrain_extract_float(&deserializer, minimum_uncertainty_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4160,9 +4318,10 @@ mip_cmd_result mip_filter_save_mag_dip_angle_error_adaptive_measurement(struct m insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) { @@ -4172,9 +4331,10 @@ mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(struct m insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) { @@ -4184,9 +4344,10 @@ mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(struc insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_aiding_measurement_enable_command(mip_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self) { @@ -4196,7 +4357,7 @@ void insert_mip_filter_aiding_measurement_enable_command(mip_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { - insert_bool(serializer, self->enable); + microstrain_insert_bool(serializer, self->enable); } } @@ -4208,7 +4369,7 @@ void extract_mip_filter_aiding_measurement_enable_command(mip_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { - extract_bool(serializer, &self->enable); + microstrain_extract_bool(serializer, &self->enable); } } @@ -4216,26 +4377,26 @@ void extract_mip_filter_aiding_measurement_enable_command(mip_serializer* serial void insert_mip_filter_aiding_measurement_enable_response(mip_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self) { insert_mip_filter_aiding_measurement_enable_command_aiding_source(serializer, self->aiding_source); - - insert_bool(serializer, self->enable); + + microstrain_insert_bool(serializer, self->enable); } void extract_mip_filter_aiding_measurement_enable_response(mip_serializer* serializer, mip_filter_aiding_measurement_enable_response* self) { extract_mip_filter_aiding_measurement_enable_command_aiding_source(serializer, &self->aiding_source); - - extract_bool(serializer, &self->enable); + + microstrain_extract_bool(serializer, &self->enable); } void insert_mip_filter_aiding_measurement_enable_command_aiding_source(struct mip_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_filter_aiding_measurement_enable_command_aiding_source(struct mip_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -4248,12 +4409,13 @@ mip_cmd_result mip_filter_write_aiding_measurement_enable(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_aiding_measurement_enable_command_aiding_source(&serializer, aiding_source); + + microstrain_insert_bool(&serializer, enable); - insert_bool(&serializer, enable); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool* enable_out) { @@ -4265,10 +4427,11 @@ mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* d insert_mip_filter_aiding_measurement_enable_command_aiding_source(&serializer, aiding_source); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4278,9 +4441,9 @@ mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* d extract_mip_filter_aiding_measurement_enable_command_aiding_source(&deserializer, &aiding_source); assert(enable_out); - extract_bool(&deserializer, enable_out); + microstrain_extract_bool(&deserializer, enable_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4295,9 +4458,10 @@ mip_cmd_result mip_filter_save_aiding_measurement_enable(struct mip_interface* d insert_mip_filter_aiding_measurement_enable_command_aiding_source(&serializer, aiding_source); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) { @@ -4309,9 +4473,10 @@ mip_cmd_result mip_filter_load_aiding_measurement_enable(struct mip_interface* d insert_mip_filter_aiding_measurement_enable_command_aiding_source(&serializer, aiding_source); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) { @@ -4323,9 +4488,10 @@ mip_cmd_result mip_filter_default_aiding_measurement_enable(struct mip_interface insert_mip_filter_aiding_measurement_enable_command_aiding_source(&serializer, aiding_source); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_run(struct mip_interface* device) { @@ -4337,11 +4503,11 @@ void insert_mip_filter_kinematic_constraint_command(mip_serializer* serializer, if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->acceleration_constraint_selection); - - insert_u8(serializer, self->velocity_constraint_selection); - - insert_u8(serializer, self->angular_constraint_selection); + microstrain_insert_u8(serializer, self->acceleration_constraint_selection); + + microstrain_insert_u8(serializer, self->velocity_constraint_selection); + + microstrain_insert_u8(serializer, self->angular_constraint_selection); } } @@ -4351,31 +4517,31 @@ void extract_mip_filter_kinematic_constraint_command(mip_serializer* serializer, if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->acceleration_constraint_selection); - - extract_u8(serializer, &self->velocity_constraint_selection); - - extract_u8(serializer, &self->angular_constraint_selection); + microstrain_extract_u8(serializer, &self->acceleration_constraint_selection); + + microstrain_extract_u8(serializer, &self->velocity_constraint_selection); + + microstrain_extract_u8(serializer, &self->angular_constraint_selection); } } void insert_mip_filter_kinematic_constraint_response(mip_serializer* serializer, const mip_filter_kinematic_constraint_response* self) { - insert_u8(serializer, self->acceleration_constraint_selection); - - insert_u8(serializer, self->velocity_constraint_selection); - - insert_u8(serializer, self->angular_constraint_selection); + microstrain_insert_u8(serializer, self->acceleration_constraint_selection); + + microstrain_insert_u8(serializer, self->velocity_constraint_selection); + + microstrain_insert_u8(serializer, self->angular_constraint_selection); } void extract_mip_filter_kinematic_constraint_response(mip_serializer* serializer, mip_filter_kinematic_constraint_response* self) { - extract_u8(serializer, &self->acceleration_constraint_selection); - - extract_u8(serializer, &self->velocity_constraint_selection); - - extract_u8(serializer, &self->angular_constraint_selection); + microstrain_extract_u8(serializer, &self->acceleration_constraint_selection); + + microstrain_extract_u8(serializer, &self->velocity_constraint_selection); + + microstrain_extract_u8(serializer, &self->angular_constraint_selection); } @@ -4386,16 +4552,17 @@ mip_cmd_result mip_filter_write_kinematic_constraint(struct mip_interface* devic mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, acceleration_constraint_selection); + + microstrain_insert_u8(&serializer, velocity_constraint_selection); + + microstrain_insert_u8(&serializer, angular_constraint_selection); - insert_u8(&serializer, acceleration_constraint_selection); - - insert_u8(&serializer, velocity_constraint_selection); - - insert_u8(&serializer, angular_constraint_selection); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device, uint8_t* acceleration_constraint_selection_out, uint8_t* velocity_constraint_selection_out, uint8_t* angular_constraint_selection_out) { @@ -4405,10 +4572,11 @@ mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4416,15 +4584,15 @@ mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(acceleration_constraint_selection_out); - extract_u8(&deserializer, acceleration_constraint_selection_out); + microstrain_extract_u8(&deserializer, acceleration_constraint_selection_out); assert(velocity_constraint_selection_out); - extract_u8(&deserializer, velocity_constraint_selection_out); + microstrain_extract_u8(&deserializer, velocity_constraint_selection_out); assert(angular_constraint_selection_out); - extract_u8(&deserializer, angular_constraint_selection_out); + microstrain_extract_u8(&deserializer, angular_constraint_selection_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4437,9 +4605,10 @@ mip_cmd_result mip_filter_save_kinematic_constraint(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_kinematic_constraint(struct mip_interface* device) { @@ -4449,9 +4618,10 @@ mip_cmd_result mip_filter_load_kinematic_constraint(struct mip_interface* device insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_kinematic_constraint(struct mip_interface* device) { @@ -4461,9 +4631,10 @@ mip_cmd_result mip_filter_default_kinematic_constraint(struct mip_interface* dev insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_initialization_configuration_command(mip_serializer* serializer, const mip_filter_initialization_configuration_command* self) { @@ -4471,23 +4642,23 @@ void insert_mip_filter_initialization_configuration_command(mip_serializer* seri if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->wait_for_run_command); + microstrain_insert_u8(serializer, self->wait_for_run_command); insert_mip_filter_initialization_configuration_command_initial_condition_source(serializer, self->initial_cond_src); insert_mip_filter_initialization_configuration_command_alignment_selector(serializer, self->auto_heading_alignment_selector); - - insert_float(serializer, self->initial_heading); - - insert_float(serializer, self->initial_pitch); - - insert_float(serializer, self->initial_roll); + + microstrain_insert_float(serializer, self->initial_heading); + + microstrain_insert_float(serializer, self->initial_pitch); + + microstrain_insert_float(serializer, self->initial_roll); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->initial_position[i]); + microstrain_insert_float(serializer, self->initial_position[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->initial_velocity[i]); + microstrain_insert_float(serializer, self->initial_velocity[i]); insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); @@ -4499,23 +4670,23 @@ void extract_mip_filter_initialization_configuration_command(mip_serializer* ser if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->wait_for_run_command); + microstrain_extract_u8(serializer, &self->wait_for_run_command); extract_mip_filter_initialization_configuration_command_initial_condition_source(serializer, &self->initial_cond_src); extract_mip_filter_initialization_configuration_command_alignment_selector(serializer, &self->auto_heading_alignment_selector); - - extract_float(serializer, &self->initial_heading); - - extract_float(serializer, &self->initial_pitch); - - extract_float(serializer, &self->initial_roll); + + microstrain_extract_float(serializer, &self->initial_heading); + + microstrain_extract_float(serializer, &self->initial_pitch); + + microstrain_extract_float(serializer, &self->initial_roll); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->initial_position[i]); + microstrain_extract_float(serializer, &self->initial_position[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->initial_velocity[i]); + microstrain_extract_float(serializer, &self->initial_velocity[i]); extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); @@ -4524,46 +4695,46 @@ void extract_mip_filter_initialization_configuration_command(mip_serializer* ser void insert_mip_filter_initialization_configuration_response(mip_serializer* serializer, const mip_filter_initialization_configuration_response* self) { - insert_u8(serializer, self->wait_for_run_command); + microstrain_insert_u8(serializer, self->wait_for_run_command); insert_mip_filter_initialization_configuration_command_initial_condition_source(serializer, self->initial_cond_src); insert_mip_filter_initialization_configuration_command_alignment_selector(serializer, self->auto_heading_alignment_selector); - - insert_float(serializer, self->initial_heading); - - insert_float(serializer, self->initial_pitch); - - insert_float(serializer, self->initial_roll); + + microstrain_insert_float(serializer, self->initial_heading); + + microstrain_insert_float(serializer, self->initial_pitch); + + microstrain_insert_float(serializer, self->initial_roll); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->initial_position[i]); + microstrain_insert_float(serializer, self->initial_position[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->initial_velocity[i]); + microstrain_insert_float(serializer, self->initial_velocity[i]); insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); } void extract_mip_filter_initialization_configuration_response(mip_serializer* serializer, mip_filter_initialization_configuration_response* self) { - extract_u8(serializer, &self->wait_for_run_command); + microstrain_extract_u8(serializer, &self->wait_for_run_command); extract_mip_filter_initialization_configuration_command_initial_condition_source(serializer, &self->initial_cond_src); extract_mip_filter_initialization_configuration_command_alignment_selector(serializer, &self->auto_heading_alignment_selector); - - extract_float(serializer, &self->initial_heading); - - extract_float(serializer, &self->initial_pitch); - - extract_float(serializer, &self->initial_roll); + + microstrain_extract_float(serializer, &self->initial_heading); + + microstrain_extract_float(serializer, &self->initial_pitch); + + microstrain_extract_float(serializer, &self->initial_roll); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->initial_position[i]); + microstrain_extract_float(serializer, &self->initial_position[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->initial_velocity[i]); + microstrain_extract_float(serializer, &self->initial_velocity[i]); extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); @@ -4571,23 +4742,23 @@ void extract_mip_filter_initialization_configuration_response(mip_serializer* se void insert_mip_filter_initialization_configuration_command_alignment_selector(struct mip_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_initialization_configuration_command_alignment_selector(struct mip_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_filter_initialization_configuration_command_initial_condition_source(struct mip_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_initialization_configuration_command_initial_condition_source(struct mip_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -4598,32 +4769,33 @@ mip_cmd_result mip_filter_write_initialization_configuration(struct mip_interfac mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, wait_for_run_command); + + microstrain_insert_u8(&serializer, wait_for_run_command); insert_mip_filter_initialization_configuration_command_initial_condition_source(&serializer, initial_cond_src); insert_mip_filter_initialization_configuration_command_alignment_selector(&serializer, auto_heading_alignment_selector); - - insert_float(&serializer, initial_heading); - - insert_float(&serializer, initial_pitch); - - insert_float(&serializer, initial_roll); + + microstrain_insert_float(&serializer, initial_heading); + + microstrain_insert_float(&serializer, initial_pitch); + + microstrain_insert_float(&serializer, initial_roll); assert(initial_position || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, initial_position[i]); + microstrain_insert_float(&serializer, initial_position[i]); assert(initial_velocity || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, initial_velocity[i]); + microstrain_insert_float(&serializer, initial_velocity[i]); insert_mip_filter_reference_frame(&serializer, reference_frame_selector); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface* device, uint8_t* wait_for_run_command_out, mip_filter_initialization_configuration_command_initial_condition_source* initial_cond_src_out, mip_filter_initialization_configuration_command_alignment_selector* auto_heading_alignment_selector_out, float* initial_heading_out, float* initial_pitch_out, float* initial_roll_out, float* initial_position_out, float* initial_velocity_out, mip_filter_reference_frame* reference_frame_selector_out) { @@ -4633,10 +4805,11 @@ mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4644,7 +4817,7 @@ mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(wait_for_run_command_out); - extract_u8(&deserializer, wait_for_run_command_out); + microstrain_extract_u8(&deserializer, wait_for_run_command_out); assert(initial_cond_src_out); extract_mip_filter_initialization_configuration_command_initial_condition_source(&deserializer, initial_cond_src_out); @@ -4653,26 +4826,26 @@ mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface extract_mip_filter_initialization_configuration_command_alignment_selector(&deserializer, auto_heading_alignment_selector_out); assert(initial_heading_out); - extract_float(&deserializer, initial_heading_out); + microstrain_extract_float(&deserializer, initial_heading_out); assert(initial_pitch_out); - extract_float(&deserializer, initial_pitch_out); + microstrain_extract_float(&deserializer, initial_pitch_out); assert(initial_roll_out); - extract_float(&deserializer, initial_roll_out); + microstrain_extract_float(&deserializer, initial_roll_out); assert(initial_position_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &initial_position_out[i]); + microstrain_extract_float(&deserializer, &initial_position_out[i]); assert(initial_velocity_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &initial_velocity_out[i]); + microstrain_extract_float(&deserializer, &initial_velocity_out[i]); assert(reference_frame_selector_out); extract_mip_filter_reference_frame(&deserializer, reference_frame_selector_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4685,9 +4858,10 @@ mip_cmd_result mip_filter_save_initialization_configuration(struct mip_interface insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_initialization_configuration(struct mip_interface* device) { @@ -4697,9 +4871,10 @@ mip_cmd_result mip_filter_load_initialization_configuration(struct mip_interface insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_initialization_configuration(struct mip_interface* device) { @@ -4709,9 +4884,10 @@ mip_cmd_result mip_filter_default_initialization_configuration(struct mip_interf insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_adaptive_filter_options_command(mip_serializer* serializer, const mip_filter_adaptive_filter_options_command* self) { @@ -4719,9 +4895,9 @@ void insert_mip_filter_adaptive_filter_options_command(mip_serializer* serialize if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->level); - - insert_u16(serializer, self->time_limit); + microstrain_insert_u8(serializer, self->level); + + microstrain_insert_u16(serializer, self->time_limit); } } @@ -4731,25 +4907,25 @@ void extract_mip_filter_adaptive_filter_options_command(mip_serializer* serializ if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->level); - - extract_u16(serializer, &self->time_limit); + microstrain_extract_u8(serializer, &self->level); + + microstrain_extract_u16(serializer, &self->time_limit); } } void insert_mip_filter_adaptive_filter_options_response(mip_serializer* serializer, const mip_filter_adaptive_filter_options_response* self) { - insert_u8(serializer, self->level); - - insert_u16(serializer, self->time_limit); + microstrain_insert_u8(serializer, self->level); + + microstrain_insert_u16(serializer, self->time_limit); } void extract_mip_filter_adaptive_filter_options_response(mip_serializer* serializer, mip_filter_adaptive_filter_options_response* self) { - extract_u8(serializer, &self->level); - - extract_u16(serializer, &self->time_limit); + microstrain_extract_u8(serializer, &self->level); + + microstrain_extract_u16(serializer, &self->time_limit); } @@ -4760,14 +4936,15 @@ mip_cmd_result mip_filter_write_adaptive_filter_options(struct mip_interface* de mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, level); + + microstrain_insert_u16(&serializer, time_limit); - insert_u8(&serializer, level); - - insert_u16(&serializer, time_limit); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* device, uint8_t* level_out, uint16_t* time_limit_out) { @@ -4777,10 +4954,11 @@ mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* dev insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4788,12 +4966,12 @@ mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* dev mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(level_out); - extract_u8(&deserializer, level_out); + microstrain_extract_u8(&deserializer, level_out); assert(time_limit_out); - extract_u16(&deserializer, time_limit_out); + microstrain_extract_u16(&deserializer, time_limit_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4806,9 +4984,10 @@ mip_cmd_result mip_filter_save_adaptive_filter_options(struct mip_interface* dev insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_adaptive_filter_options(struct mip_interface* device) { @@ -4818,9 +4997,10 @@ mip_cmd_result mip_filter_load_adaptive_filter_options(struct mip_interface* dev insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_adaptive_filter_options(struct mip_interface* device) { @@ -4830,51 +5010,52 @@ mip_cmd_result mip_filter_default_adaptive_filter_options(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_multi_antenna_offset_command(mip_serializer* serializer, const mip_filter_multi_antenna_offset_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->receiver_id); + + microstrain_insert_u8(serializer, self->receiver_id); if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->antenna_offset[i]); + microstrain_insert_float(serializer, self->antenna_offset[i]); } } void extract_mip_filter_multi_antenna_offset_command(mip_serializer* serializer, mip_filter_multi_antenna_offset_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->receiver_id); + + microstrain_extract_u8(serializer, &self->receiver_id); if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->antenna_offset[i]); + microstrain_extract_float(serializer, &self->antenna_offset[i]); } } void insert_mip_filter_multi_antenna_offset_response(mip_serializer* serializer, const mip_filter_multi_antenna_offset_response* self) { - insert_u8(serializer, self->receiver_id); + microstrain_insert_u8(serializer, self->receiver_id); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->antenna_offset[i]); + microstrain_insert_float(serializer, self->antenna_offset[i]); } void extract_mip_filter_multi_antenna_offset_response(mip_serializer* serializer, mip_filter_multi_antenna_offset_response* self) { - extract_u8(serializer, &self->receiver_id); + microstrain_extract_u8(serializer, &self->receiver_id); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->antenna_offset[i]); + microstrain_extract_float(serializer, &self->antenna_offset[i]); } @@ -4885,16 +5066,17 @@ mip_cmd_result mip_filter_write_multi_antenna_offset(struct mip_interface* devic mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, receiver_id); + + microstrain_insert_u8(&serializer, receiver_id); assert(antenna_offset || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, antenna_offset[i]); + microstrain_insert_float(&serializer, antenna_offset[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, float* antenna_offset_out) { @@ -4903,26 +5085,27 @@ mip_cmd_result mip_filter_read_multi_antenna_offset(struct mip_interface* device mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, receiver_id); - insert_u8(&serializer, receiver_id); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &receiver_id); + + microstrain_extract_u8(&deserializer, &receiver_id); assert(antenna_offset_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &antenna_offset_out[i]); + microstrain_extract_float(&deserializer, &antenna_offset_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4934,12 +5117,13 @@ mip_cmd_result mip_filter_save_multi_antenna_offset(struct mip_interface* device mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, receiver_id); - insert_u8(&serializer, receiver_id); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id) { @@ -4948,12 +5132,13 @@ mip_cmd_result mip_filter_load_multi_antenna_offset(struct mip_interface* device mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, receiver_id); - insert_u8(&serializer, receiver_id); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id) { @@ -4962,12 +5147,13 @@ mip_cmd_result mip_filter_default_multi_antenna_offset(struct mip_interface* dev mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, receiver_id); - insert_u8(&serializer, receiver_id); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_rel_pos_configuration_command(mip_serializer* serializer, const mip_filter_rel_pos_configuration_command* self) { @@ -4975,12 +5161,12 @@ void insert_mip_filter_rel_pos_configuration_command(mip_serializer* serializer, if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->source); + microstrain_insert_u8(serializer, self->source); insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); for(unsigned int i=0; i < 3; i++) - insert_double(serializer, self->reference_coordinates[i]); + microstrain_insert_double(serializer, self->reference_coordinates[i]); } } @@ -4990,34 +5176,34 @@ void extract_mip_filter_rel_pos_configuration_command(mip_serializer* serializer if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->source); + microstrain_extract_u8(serializer, &self->source); extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); for(unsigned int i=0; i < 3; i++) - extract_double(serializer, &self->reference_coordinates[i]); + microstrain_extract_double(serializer, &self->reference_coordinates[i]); } } void insert_mip_filter_rel_pos_configuration_response(mip_serializer* serializer, const mip_filter_rel_pos_configuration_response* self) { - insert_u8(serializer, self->source); + microstrain_insert_u8(serializer, self->source); insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); for(unsigned int i=0; i < 3; i++) - insert_double(serializer, self->reference_coordinates[i]); + microstrain_insert_double(serializer, self->reference_coordinates[i]); } void extract_mip_filter_rel_pos_configuration_response(mip_serializer* serializer, mip_filter_rel_pos_configuration_response* self) { - extract_u8(serializer, &self->source); + microstrain_extract_u8(serializer, &self->source); extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); for(unsigned int i=0; i < 3; i++) - extract_double(serializer, &self->reference_coordinates[i]); + microstrain_extract_double(serializer, &self->reference_coordinates[i]); } @@ -5028,18 +5214,19 @@ mip_cmd_result mip_filter_write_rel_pos_configuration(struct mip_interface* devi mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, source); + + microstrain_insert_u8(&serializer, source); insert_mip_filter_reference_frame(&serializer, reference_frame_selector); assert(reference_coordinates || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_double(&serializer, reference_coordinates[i]); + microstrain_insert_double(&serializer, reference_coordinates[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* device, uint8_t* source_out, mip_filter_reference_frame* reference_frame_selector_out, double* reference_coordinates_out) { @@ -5049,10 +5236,11 @@ mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_REL_POS_CONFIGURATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_REL_POS_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5060,16 +5248,16 @@ mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* devic mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(source_out); - extract_u8(&deserializer, source_out); + microstrain_extract_u8(&deserializer, source_out); assert(reference_frame_selector_out); extract_mip_filter_reference_frame(&deserializer, reference_frame_selector_out); assert(reference_coordinates_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_double(&deserializer, &reference_coordinates_out[i]); + microstrain_extract_double(&deserializer, &reference_coordinates_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -5082,9 +5270,10 @@ mip_cmd_result mip_filter_save_rel_pos_configuration(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_rel_pos_configuration(struct mip_interface* device) { @@ -5094,9 +5283,10 @@ mip_cmd_result mip_filter_load_rel_pos_configuration(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_rel_pos_configuration(struct mip_interface* device) { @@ -5106,9 +5296,10 @@ mip_cmd_result mip_filter_default_rel_pos_configuration(struct mip_interface* de insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_ref_point_lever_arm_command(mip_serializer* serializer, const mip_filter_ref_point_lever_arm_command* self) { @@ -5119,7 +5310,7 @@ void insert_mip_filter_ref_point_lever_arm_command(mip_serializer* serializer, c insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, self->ref_point_sel); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->lever_arm_offset[i]); + microstrain_insert_float(serializer, self->lever_arm_offset[i]); } } @@ -5132,7 +5323,7 @@ void extract_mip_filter_ref_point_lever_arm_command(mip_serializer* serializer, extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, &self->ref_point_sel); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->lever_arm_offset[i]); + microstrain_extract_float(serializer, &self->lever_arm_offset[i]); } } @@ -5142,7 +5333,7 @@ void insert_mip_filter_ref_point_lever_arm_response(mip_serializer* serializer, insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, self->ref_point_sel); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->lever_arm_offset[i]); + microstrain_insert_float(serializer, self->lever_arm_offset[i]); } void extract_mip_filter_ref_point_lever_arm_response(mip_serializer* serializer, mip_filter_ref_point_lever_arm_response* self) @@ -5150,18 +5341,18 @@ void extract_mip_filter_ref_point_lever_arm_response(mip_serializer* serializer, extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, &self->ref_point_sel); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->lever_arm_offset[i]); + microstrain_extract_float(serializer, &self->lever_arm_offset[i]); } void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct mip_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct mip_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -5177,11 +5368,12 @@ mip_cmd_result mip_filter_write_ref_point_lever_arm(struct mip_interface* device assert(lever_arm_offset || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, lever_arm_offset[i]); + microstrain_insert_float(&serializer, lever_arm_offset[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector* ref_point_sel_out, float* lever_arm_offset_out) { @@ -5191,10 +5383,11 @@ mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5206,9 +5399,9 @@ mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, assert(lever_arm_offset_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &lever_arm_offset_out[i]); + microstrain_extract_float(&deserializer, &lever_arm_offset_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -5221,9 +5414,10 @@ mip_cmd_result mip_filter_save_ref_point_lever_arm(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_ref_point_lever_arm(struct mip_interface* device) { @@ -5233,9 +5427,10 @@ mip_cmd_result mip_filter_load_ref_point_lever_arm(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_ref_point_lever_arm(struct mip_interface* device) { @@ -5245,30 +5440,31 @@ mip_cmd_result mip_filter_default_ref_point_lever_arm(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_speed_measurement_command(mip_serializer* serializer, const mip_filter_speed_measurement_command* self) { - insert_u8(serializer, self->source); - - insert_float(serializer, self->time_of_week); - - insert_float(serializer, self->speed); - - insert_float(serializer, self->speed_uncertainty); + microstrain_insert_u8(serializer, self->source); + + microstrain_insert_float(serializer, self->time_of_week); + + microstrain_insert_float(serializer, self->speed); + + microstrain_insert_float(serializer, self->speed_uncertainty); } void extract_mip_filter_speed_measurement_command(mip_serializer* serializer, mip_filter_speed_measurement_command* self) { - extract_u8(serializer, &self->source); - - extract_float(serializer, &self->time_of_week); - - extract_float(serializer, &self->speed); - - extract_float(serializer, &self->speed_uncertainty); + microstrain_extract_u8(serializer, &self->source); + + microstrain_extract_float(serializer, &self->time_of_week); + + microstrain_extract_float(serializer, &self->speed); + + microstrain_extract_float(serializer, &self->speed_uncertainty); } @@ -5277,60 +5473,61 @@ mip_cmd_result mip_filter_speed_measurement(struct mip_interface* device, uint8_ mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + microstrain_insert_u8(&serializer, source); + + microstrain_insert_float(&serializer, time_of_week); + + microstrain_insert_float(&serializer, speed); + + microstrain_insert_float(&serializer, speed_uncertainty); - insert_u8(&serializer, source); - - insert_float(&serializer, time_of_week); - - insert_float(&serializer, speed); - - insert_float(&serializer, speed_uncertainty); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_MEASUREMENT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_MEASUREMENT, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_speed_lever_arm_command(mip_serializer* serializer, const mip_filter_speed_lever_arm_command* self) { insert_mip_function_selector(serializer, self->function); - - insert_u8(serializer, self->source); + + microstrain_insert_u8(serializer, self->source); if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->lever_arm_offset[i]); + microstrain_insert_float(serializer, self->lever_arm_offset[i]); } } void extract_mip_filter_speed_lever_arm_command(mip_serializer* serializer, mip_filter_speed_lever_arm_command* self) { extract_mip_function_selector(serializer, &self->function); - - extract_u8(serializer, &self->source); + + microstrain_extract_u8(serializer, &self->source); if( self->function == MIP_FUNCTION_WRITE ) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->lever_arm_offset[i]); + microstrain_extract_float(serializer, &self->lever_arm_offset[i]); } } void insert_mip_filter_speed_lever_arm_response(mip_serializer* serializer, const mip_filter_speed_lever_arm_response* self) { - insert_u8(serializer, self->source); + microstrain_insert_u8(serializer, self->source); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->lever_arm_offset[i]); + microstrain_insert_float(serializer, self->lever_arm_offset[i]); } void extract_mip_filter_speed_lever_arm_response(mip_serializer* serializer, mip_filter_speed_lever_arm_response* self) { - extract_u8(serializer, &self->source); + microstrain_extract_u8(serializer, &self->source); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->lever_arm_offset[i]); + microstrain_extract_float(serializer, &self->lever_arm_offset[i]); } @@ -5341,16 +5538,17 @@ mip_cmd_result mip_filter_write_speed_lever_arm(struct mip_interface* device, ui mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, source); + + microstrain_insert_u8(&serializer, source); assert(lever_arm_offset || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_float(&serializer, lever_arm_offset[i]); + microstrain_insert_float(&serializer, lever_arm_offset[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_speed_lever_arm(struct mip_interface* device, uint8_t source, float* lever_arm_offset_out) { @@ -5359,26 +5557,27 @@ mip_cmd_result mip_filter_read_speed_lever_arm(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); + + microstrain_insert_u8(&serializer, source); - insert_u8(&serializer, source); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SPEED_LEVER_ARM, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_FILTER_SPEED_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { mip_serializer deserializer; mip_serializer_init_insertion(&deserializer, buffer, responseLength); - - extract_u8(&deserializer, &source); + + microstrain_extract_u8(&deserializer, &source); assert(lever_arm_offset_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_float(&deserializer, &lever_arm_offset_out[i]); + microstrain_extract_float(&deserializer, &lever_arm_offset_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -5390,12 +5589,13 @@ mip_cmd_result mip_filter_save_speed_lever_arm(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); + + microstrain_insert_u8(&serializer, source); - insert_u8(&serializer, source); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_speed_lever_arm(struct mip_interface* device, uint8_t source) { @@ -5404,12 +5604,13 @@ mip_cmd_result mip_filter_load_speed_lever_arm(struct mip_interface* device, uin mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); + + microstrain_insert_u8(&serializer, source); - insert_u8(&serializer, source); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_speed_lever_arm(struct mip_interface* device, uint8_t source) { @@ -5418,12 +5619,13 @@ mip_cmd_result mip_filter_default_speed_lever_arm(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); + + microstrain_insert_u8(&serializer, source); - insert_u8(&serializer, source); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_wheeled_vehicle_constraint_control_command(mip_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_command* self) { @@ -5431,7 +5633,7 @@ void insert_mip_filter_wheeled_vehicle_constraint_control_command(mip_serializer if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable); + microstrain_insert_u8(serializer, self->enable); } } @@ -5441,19 +5643,19 @@ void extract_mip_filter_wheeled_vehicle_constraint_control_command(mip_serialize if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable); + microstrain_extract_u8(serializer, &self->enable); } } void insert_mip_filter_wheeled_vehicle_constraint_control_response(mip_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self) { - insert_u8(serializer, self->enable); + microstrain_insert_u8(serializer, self->enable); } void extract_mip_filter_wheeled_vehicle_constraint_control_response(mip_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self) { - extract_u8(serializer, &self->enable); + microstrain_extract_u8(serializer, &self->enable); } @@ -5464,12 +5666,13 @@ mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(struct mip_in mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, enable); - insert_u8(&serializer, enable); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t* enable_out) { @@ -5479,10 +5682,11 @@ mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_int insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5490,9 +5694,9 @@ mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_int mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_u8(&deserializer, enable_out); + microstrain_extract_u8(&deserializer, enable_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -5505,9 +5709,10 @@ mip_cmd_result mip_filter_save_wheeled_vehicle_constraint_control(struct mip_int insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_wheeled_vehicle_constraint_control(struct mip_interface* device) { @@ -5517,9 +5722,10 @@ mip_cmd_result mip_filter_load_wheeled_vehicle_constraint_control(struct mip_int insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(struct mip_interface* device) { @@ -5529,9 +5735,10 @@ mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(struct mip_ insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_vertical_gyro_constraint_control_command(mip_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_command* self) { @@ -5539,7 +5746,7 @@ void insert_mip_filter_vertical_gyro_constraint_control_command(mip_serializer* if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable); + microstrain_insert_u8(serializer, self->enable); } } @@ -5549,19 +5756,19 @@ void extract_mip_filter_vertical_gyro_constraint_control_command(mip_serializer* if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable); + microstrain_extract_u8(serializer, &self->enable); } } void insert_mip_filter_vertical_gyro_constraint_control_response(mip_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self) { - insert_u8(serializer, self->enable); + microstrain_insert_u8(serializer, self->enable); } void extract_mip_filter_vertical_gyro_constraint_control_response(mip_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self) { - extract_u8(serializer, &self->enable); + microstrain_extract_u8(serializer, &self->enable); } @@ -5572,12 +5779,13 @@ mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(struct mip_inte mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, enable); - insert_u8(&serializer, enable); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t* enable_out) { @@ -5587,10 +5795,11 @@ mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_inter insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5598,9 +5807,9 @@ mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_inter mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_u8(&deserializer, enable_out); + microstrain_extract_u8(&deserializer, enable_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -5613,9 +5822,10 @@ mip_cmd_result mip_filter_save_vertical_gyro_constraint_control(struct mip_inter insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_vertical_gyro_constraint_control(struct mip_interface* device) { @@ -5625,9 +5835,10 @@ mip_cmd_result mip_filter_load_vertical_gyro_constraint_control(struct mip_inter insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(struct mip_interface* device) { @@ -5637,9 +5848,10 @@ mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(struct mip_in insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_gnss_antenna_cal_control_command(mip_serializer* serializer, const mip_filter_gnss_antenna_cal_control_command* self) { @@ -5647,9 +5859,9 @@ void insert_mip_filter_gnss_antenna_cal_control_command(mip_serializer* serializ if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable); - - insert_float(serializer, self->max_offset); + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_float(serializer, self->max_offset); } } @@ -5659,25 +5871,25 @@ void extract_mip_filter_gnss_antenna_cal_control_command(mip_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable); - - extract_float(serializer, &self->max_offset); + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->max_offset); } } void insert_mip_filter_gnss_antenna_cal_control_response(mip_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self) { - insert_u8(serializer, self->enable); - - insert_float(serializer, self->max_offset); + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_float(serializer, self->max_offset); } void extract_mip_filter_gnss_antenna_cal_control_response(mip_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self) { - extract_u8(serializer, &self->enable); - - extract_float(serializer, &self->max_offset); + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->max_offset); } @@ -5688,14 +5900,15 @@ mip_cmd_result mip_filter_write_gnss_antenna_cal_control(struct mip_interface* d mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, enable); + + microstrain_insert_float(&serializer, max_offset); - insert_u8(&serializer, enable); - - insert_float(&serializer, max_offset); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* device, uint8_t* enable_out, float* max_offset_out) { @@ -5705,10 +5918,11 @@ mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* de insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5716,12 +5930,12 @@ mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* de mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_u8(&deserializer, enable_out); + microstrain_extract_u8(&deserializer, enable_out); assert(max_offset_out); - extract_float(&deserializer, max_offset_out); + microstrain_extract_float(&deserializer, max_offset_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -5734,9 +5948,10 @@ mip_cmd_result mip_filter_save_gnss_antenna_cal_control(struct mip_interface* de insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_load_gnss_antenna_cal_control(struct mip_interface* device) { @@ -5746,9 +5961,10 @@ mip_cmd_result mip_filter_load_gnss_antenna_cal_control(struct mip_interface* de insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_filter_default_gnss_antenna_cal_control(struct mip_interface* device) { @@ -5758,18 +5974,19 @@ mip_cmd_result mip_filter_default_gnss_antenna_cal_control(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_filter_set_initial_heading_command(mip_serializer* serializer, const mip_filter_set_initial_heading_command* self) { - insert_float(serializer, self->heading); + microstrain_insert_float(serializer, self->heading); } void extract_mip_filter_set_initial_heading_command(mip_serializer* serializer, mip_filter_set_initial_heading_command* self) { - extract_float(serializer, &self->heading); + microstrain_extract_float(serializer, &self->heading); } @@ -5778,12 +5995,13 @@ mip_cmd_result mip_filter_set_initial_heading(struct mip_interface* device, floa mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + microstrain_insert_float(&serializer, heading); - insert_float(&serializer, heading); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SET_INITIAL_HEADING, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SET_INITIAL_HEADING, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } #ifdef __cplusplus diff --git a/src/mip/definitions/commands_filter.cpp b/src/mip/definitions/commands_filter.cpp index 7792142bf..527c23787 100644 --- a/src/mip/definitions/commands_filter.cpp +++ b/src/mip/definitions/commands_filter.cpp @@ -1,7 +1,7 @@ #include "commands_filter.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/commands_gnss.c b/src/mip/definitions/commands_gnss.c index cb41c03a3..179c66f9b 100644 --- a/src/mip/definitions/commands_gnss.c +++ b/src/mip/definitions/commands_gnss.c @@ -1,7 +1,7 @@ #include "commands_gnss.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -29,22 +29,22 @@ struct mip_field; void insert_mip_gnss_receiver_info_command_info(mip_serializer* serializer, const mip_gnss_receiver_info_command_info* self) { - insert_u8(serializer, self->receiver_id); - - insert_u8(serializer, self->mip_data_descriptor_set); + microstrain_insert_u8(serializer, self->receiver_id); + + microstrain_insert_u8(serializer, self->mip_data_descriptor_set); for(unsigned int i=0; i < 32; i++) - insert_char(serializer, self->description[i]); + microstrain_insert_char(serializer, self->description[i]); } void extract_mip_gnss_receiver_info_command_info(mip_serializer* serializer, mip_gnss_receiver_info_command_info* self) { - extract_u8(serializer, &self->receiver_id); - - extract_u8(serializer, &self->mip_data_descriptor_set); + microstrain_extract_u8(serializer, &self->receiver_id); + + microstrain_extract_u8(serializer, &self->mip_data_descriptor_set); for(unsigned int i=0; i < 32; i++) - extract_char(serializer, &self->description[i]); + microstrain_extract_char(serializer, &self->description[i]); } @@ -61,13 +61,13 @@ mip_cmd_result mip_gnss_receiver_info(struct mip_interface* device, uint8_t* num mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(num_receivers_out); - extract_count(&deserializer, num_receivers_out, num_receivers_out_max); + microstrain_extract_count(&deserializer, num_receivers_out, num_receivers_out_max); assert(receiver_info_out || (num_receivers_out == 0)); for(unsigned int i=0; i < *num_receivers_out; i++) extract_mip_gnss_receiver_info_command_info(&deserializer, &receiver_info_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -78,16 +78,16 @@ void insert_mip_gnss_signal_configuration_command(mip_serializer* serializer, co if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->gps_enable); - - insert_u8(serializer, self->glonass_enable); - - insert_u8(serializer, self->galileo_enable); - - insert_u8(serializer, self->beidou_enable); + microstrain_insert_u8(serializer, self->gps_enable); + + microstrain_insert_u8(serializer, self->glonass_enable); + + microstrain_insert_u8(serializer, self->galileo_enable); + + microstrain_insert_u8(serializer, self->beidou_enable); for(unsigned int i=0; i < 4; i++) - insert_u8(serializer, self->reserved[i]); + microstrain_insert_u8(serializer, self->reserved[i]); } } @@ -97,46 +97,46 @@ void extract_mip_gnss_signal_configuration_command(mip_serializer* serializer, m if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->gps_enable); - - extract_u8(serializer, &self->glonass_enable); - - extract_u8(serializer, &self->galileo_enable); - - extract_u8(serializer, &self->beidou_enable); + microstrain_extract_u8(serializer, &self->gps_enable); + + microstrain_extract_u8(serializer, &self->glonass_enable); + + microstrain_extract_u8(serializer, &self->galileo_enable); + + microstrain_extract_u8(serializer, &self->beidou_enable); for(unsigned int i=0; i < 4; i++) - extract_u8(serializer, &self->reserved[i]); + microstrain_extract_u8(serializer, &self->reserved[i]); } } void insert_mip_gnss_signal_configuration_response(mip_serializer* serializer, const mip_gnss_signal_configuration_response* self) { - insert_u8(serializer, self->gps_enable); - - insert_u8(serializer, self->glonass_enable); - - insert_u8(serializer, self->galileo_enable); - - insert_u8(serializer, self->beidou_enable); + microstrain_insert_u8(serializer, self->gps_enable); + + microstrain_insert_u8(serializer, self->glonass_enable); + + microstrain_insert_u8(serializer, self->galileo_enable); + + microstrain_insert_u8(serializer, self->beidou_enable); for(unsigned int i=0; i < 4; i++) - insert_u8(serializer, self->reserved[i]); + microstrain_insert_u8(serializer, self->reserved[i]); } void extract_mip_gnss_signal_configuration_response(mip_serializer* serializer, mip_gnss_signal_configuration_response* self) { - extract_u8(serializer, &self->gps_enable); - - extract_u8(serializer, &self->glonass_enable); - - extract_u8(serializer, &self->galileo_enable); - - extract_u8(serializer, &self->beidou_enable); + microstrain_extract_u8(serializer, &self->gps_enable); + + microstrain_extract_u8(serializer, &self->glonass_enable); + + microstrain_extract_u8(serializer, &self->galileo_enable); + + microstrain_extract_u8(serializer, &self->beidou_enable); for(unsigned int i=0; i < 4; i++) - extract_u8(serializer, &self->reserved[i]); + microstrain_extract_u8(serializer, &self->reserved[i]); } @@ -147,22 +147,23 @@ mip_cmd_result mip_gnss_write_signal_configuration(struct mip_interface* device, mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, gps_enable); - - insert_u8(&serializer, glonass_enable); - - insert_u8(&serializer, galileo_enable); - - insert_u8(&serializer, beidou_enable); + + microstrain_insert_u8(&serializer, gps_enable); + + microstrain_insert_u8(&serializer, glonass_enable); + + microstrain_insert_u8(&serializer, galileo_enable); + + microstrain_insert_u8(&serializer, beidou_enable); assert(reserved || (4 == 0)); for(unsigned int i=0; i < 4; i++) - insert_u8(&serializer, reserved[i]); + microstrain_insert_u8(&serializer, reserved[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, uint8_t* gps_enable_out, uint8_t* glonass_enable_out, uint8_t* galileo_enable_out, uint8_t* beidou_enable_out, uint8_t* reserved_out) { @@ -172,10 +173,11 @@ mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -183,22 +185,22 @@ mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(gps_enable_out); - extract_u8(&deserializer, gps_enable_out); + microstrain_extract_u8(&deserializer, gps_enable_out); assert(glonass_enable_out); - extract_u8(&deserializer, glonass_enable_out); + microstrain_extract_u8(&deserializer, glonass_enable_out); assert(galileo_enable_out); - extract_u8(&deserializer, galileo_enable_out); + microstrain_extract_u8(&deserializer, galileo_enable_out); assert(beidou_enable_out); - extract_u8(&deserializer, beidou_enable_out); + microstrain_extract_u8(&deserializer, beidou_enable_out); assert(reserved_out || (4 == 0)); for(unsigned int i=0; i < 4; i++) - extract_u8(&deserializer, &reserved_out[i]); + microstrain_extract_u8(&deserializer, &reserved_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -211,9 +213,10 @@ mip_cmd_result mip_gnss_save_signal_configuration(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_gnss_load_signal_configuration(struct mip_interface* device) { @@ -223,9 +226,10 @@ mip_cmd_result mip_gnss_load_signal_configuration(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_gnss_default_signal_configuration(struct mip_interface* device) { @@ -235,9 +239,10 @@ mip_cmd_result mip_gnss_default_signal_configuration(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_gnss_rtk_dongle_configuration_command(mip_serializer* serializer, const mip_gnss_rtk_dongle_configuration_command* self) { @@ -245,10 +250,10 @@ void insert_mip_gnss_rtk_dongle_configuration_command(mip_serializer* serializer if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->enable); + microstrain_insert_u8(serializer, self->enable); for(unsigned int i=0; i < 3; i++) - insert_u8(serializer, self->reserved[i]); + microstrain_insert_u8(serializer, self->reserved[i]); } } @@ -258,28 +263,28 @@ void extract_mip_gnss_rtk_dongle_configuration_command(mip_serializer* serialize if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->enable); + microstrain_extract_u8(serializer, &self->enable); for(unsigned int i=0; i < 3; i++) - extract_u8(serializer, &self->reserved[i]); + microstrain_extract_u8(serializer, &self->reserved[i]); } } void insert_mip_gnss_rtk_dongle_configuration_response(mip_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self) { - insert_u8(serializer, self->enable); + microstrain_insert_u8(serializer, self->enable); for(unsigned int i=0; i < 3; i++) - insert_u8(serializer, self->reserved[i]); + microstrain_insert_u8(serializer, self->reserved[i]); } void extract_mip_gnss_rtk_dongle_configuration_response(mip_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self) { - extract_u8(serializer, &self->enable); + microstrain_extract_u8(serializer, &self->enable); for(unsigned int i=0; i < 3; i++) - extract_u8(serializer, &self->reserved[i]); + microstrain_extract_u8(serializer, &self->reserved[i]); } @@ -290,16 +295,17 @@ mip_cmd_result mip_gnss_write_rtk_dongle_configuration(struct mip_interface* dev mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - insert_u8(&serializer, enable); + + microstrain_insert_u8(&serializer, enable); assert(reserved || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_u8(&serializer, reserved[i]); + microstrain_insert_u8(&serializer, reserved[i]); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* device, uint8_t* enable_out, uint8_t* reserved_out) { @@ -309,10 +315,11 @@ mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -320,13 +327,13 @@ mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* devi mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); - extract_u8(&deserializer, enable_out); + microstrain_extract_u8(&deserializer, enable_out); assert(reserved_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) - extract_u8(&deserializer, &reserved_out[i]); + microstrain_extract_u8(&deserializer, &reserved_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -339,9 +346,10 @@ mip_cmd_result mip_gnss_save_rtk_dongle_configuration(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_gnss_load_rtk_dongle_configuration(struct mip_interface* device) { @@ -351,9 +359,10 @@ mip_cmd_result mip_gnss_load_rtk_dongle_configuration(struct mip_interface* devi insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_gnss_default_rtk_dongle_configuration(struct mip_interface* device) { @@ -363,9 +372,10 @@ mip_cmd_result mip_gnss_default_rtk_dongle_configuration(struct mip_interface* d insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } #ifdef __cplusplus diff --git a/src/mip/definitions/commands_gnss.cpp b/src/mip/definitions/commands_gnss.cpp index f980f2e9c..4873acc0c 100644 --- a/src/mip/definitions/commands_gnss.cpp +++ b/src/mip/definitions/commands_gnss.cpp @@ -1,7 +1,7 @@ #include "commands_gnss.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/commands_rtk.c b/src/mip/definitions/commands_rtk.c index d1d1c153d..e77d060f1 100644 --- a/src/mip/definitions/commands_rtk.c +++ b/src/mip/definitions/commands_rtk.c @@ -1,7 +1,7 @@ #include "commands_rtk.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -24,23 +24,23 @@ struct mip_field; void insert_mip_media_selector(struct mip_serializer* serializer, const mip_media_selector self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_media_selector(struct mip_serializer* serializer, mip_media_selector* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_led_action(struct mip_serializer* serializer, const mip_led_action self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_led_action(struct mip_serializer* serializer, mip_led_action* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -51,23 +51,23 @@ void extract_mip_led_action(struct mip_serializer* serializer, mip_led_action* s void insert_mip_rtk_get_status_flags_command_status_flags_legacy(struct mip_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self) { - insert_u32(serializer, (uint32_t)(self)); + microstrain_insert_u32(serializer, (uint32_t) (self)); } void extract_mip_rtk_get_status_flags_command_status_flags_legacy(struct mip_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self) { uint32_t tmp = 0; - extract_u32(serializer, &tmp); + microstrain_extract_u32(serializer, &tmp); *self = tmp; } void insert_mip_rtk_get_status_flags_command_status_flags(struct mip_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self) { - insert_u32(serializer, (uint32_t)(self)); + microstrain_insert_u32(serializer, (uint32_t) (self)); } void extract_mip_rtk_get_status_flags_command_status_flags(struct mip_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self) { uint32_t tmp = 0; - extract_u32(serializer, &tmp); + microstrain_extract_u32(serializer, &tmp); *self = tmp; } @@ -86,7 +86,7 @@ mip_cmd_result mip_rtk_get_status_flags(struct mip_interface* device, mip_rtk_ge assert(flags_out); extract_mip_rtk_get_status_flags_command_status_flags(&deserializer, flags_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -105,9 +105,9 @@ mip_cmd_result mip_rtk_get_imei(struct mip_interface* device, char* imei_out) assert(imei_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) - extract_char(&deserializer, &imei_out[i]); + microstrain_extract_char(&deserializer, &imei_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -126,9 +126,9 @@ mip_cmd_result mip_rtk_get_imsi(struct mip_interface* device, char* imsi_out) assert(imsi_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) - extract_char(&deserializer, &imsi_out[i]); + microstrain_extract_char(&deserializer, &imsi_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -147,9 +147,9 @@ mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out) assert(iccid_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) - extract_char(&deserializer, &iccid_out[i]); + microstrain_extract_char(&deserializer, &iccid_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -188,12 +188,12 @@ void extract_mip_rtk_connected_device_type_response(mip_serializer* serializer, void insert_mip_rtk_connected_device_type_command_type(struct mip_serializer* serializer, const mip_rtk_connected_device_type_command_type self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_rtk_connected_device_type_command_type(struct mip_serializer* serializer, mip_rtk_connected_device_type_command_type* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -207,9 +207,10 @@ mip_cmd_result mip_rtk_write_connected_device_type(struct mip_interface* device, insert_mip_rtk_connected_device_type_command_type(&serializer, dev_type); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type* dev_type_out) { @@ -219,10 +220,11 @@ mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -232,7 +234,7 @@ mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, assert(dev_type_out); extract_mip_rtk_connected_device_type_command_type(&deserializer, dev_type_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -245,9 +247,10 @@ mip_cmd_result mip_rtk_save_connected_device_type(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_rtk_load_connected_device_type(struct mip_interface* device) { @@ -257,9 +260,10 @@ mip_cmd_result mip_rtk_load_connected_device_type(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_rtk_default_connected_device_type(struct mip_interface* device) { @@ -269,9 +273,10 @@ mip_cmd_result mip_rtk_default_connected_device_type(struct mip_interface* devic insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_rtk_get_act_code(struct mip_interface* device, char* activation_code_out) { @@ -287,9 +292,9 @@ mip_cmd_result mip_rtk_get_act_code(struct mip_interface* device, char* activati assert(activation_code_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) - extract_char(&deserializer, &activation_code_out[i]); + microstrain_extract_char(&deserializer, &activation_code_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -308,9 +313,9 @@ mip_cmd_result mip_rtk_get_modem_firmware_version(struct mip_interface* device, assert(modem_firmware_version_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) - extract_char(&deserializer, &modem_firmware_version_out[i]); + microstrain_extract_char(&deserializer, &modem_firmware_version_out[i]); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -328,65 +333,65 @@ mip_cmd_result mip_rtk_get_rssi(struct mip_interface* device, bool* valid_out, i mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(valid_out); - extract_bool(&deserializer, valid_out); + microstrain_extract_bool(&deserializer, valid_out); assert(rssi_out); - extract_s32(&deserializer, rssi_out); + microstrain_extract_s32(&deserializer, rssi_out); assert(signal_quality_out); - extract_s32(&deserializer, signal_quality_out); + microstrain_extract_s32(&deserializer, signal_quality_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } void insert_mip_rtk_service_status_command(mip_serializer* serializer, const mip_rtk_service_status_command* self) { - insert_u32(serializer, self->reserved1); - - insert_u32(serializer, self->reserved2); + microstrain_insert_u32(serializer, self->reserved1); + + microstrain_insert_u32(serializer, self->reserved2); } void extract_mip_rtk_service_status_command(mip_serializer* serializer, mip_rtk_service_status_command* self) { - extract_u32(serializer, &self->reserved1); - - extract_u32(serializer, &self->reserved2); + microstrain_extract_u32(serializer, &self->reserved1); + + microstrain_extract_u32(serializer, &self->reserved2); } void insert_mip_rtk_service_status_response(mip_serializer* serializer, const mip_rtk_service_status_response* self) { insert_mip_rtk_service_status_command_service_flags(serializer, self->flags); - - insert_u32(serializer, self->receivedBytes); - - insert_u32(serializer, self->lastBytes); - - insert_u64(serializer, self->lastBytesTime); + + microstrain_insert_u32(serializer, self->receivedBytes); + + microstrain_insert_u32(serializer, self->lastBytes); + + microstrain_insert_u64(serializer, self->lastBytesTime); } void extract_mip_rtk_service_status_response(mip_serializer* serializer, mip_rtk_service_status_response* self) { extract_mip_rtk_service_status_command_service_flags(serializer, &self->flags); - - extract_u32(serializer, &self->receivedBytes); - - extract_u32(serializer, &self->lastBytes); - - extract_u64(serializer, &self->lastBytesTime); + + microstrain_extract_u32(serializer, &self->receivedBytes); + + microstrain_extract_u32(serializer, &self->lastBytes); + + microstrain_extract_u64(serializer, &self->lastBytesTime); } void insert_mip_rtk_service_status_command_service_flags(struct mip_serializer* serializer, const mip_rtk_service_status_command_service_flags self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_rtk_service_status_command_service_flags(struct mip_serializer* serializer, mip_rtk_service_status_command_service_flags* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -395,15 +400,16 @@ mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t res mip_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + microstrain_insert_u32(&serializer, reserved1); + + microstrain_insert_u32(&serializer, reserved2); - insert_u32(&serializer, reserved1); - - insert_u32(&serializer, reserved2); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_SERVICE_STATUS, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_RTK_SERVICE_STATUS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_SERVICE_STATUS, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_RTK_SERVICE_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -414,15 +420,15 @@ mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t res extract_mip_rtk_service_status_command_service_flags(&deserializer, flags_out); assert(received_bytes_out); - extract_u32(&deserializer, received_bytes_out); + microstrain_extract_u32(&deserializer, received_bytes_out); assert(last_bytes_out); - extract_u32(&deserializer, last_bytes_out); + microstrain_extract_u32(&deserializer, last_bytes_out); assert(last_bytes_time_out); - extract_u64(&deserializer, last_bytes_time_out); + microstrain_extract_u64(&deserializer, last_bytes_time_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -446,34 +452,35 @@ mip_cmd_result mip_rtk_prod_erase_storage(struct mip_interface* device, mip_medi insert_mip_media_selector(&serializer, media); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_PROD_ERASE_STORAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_PROD_ERASE_STORAGE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } void insert_mip_rtk_led_control_command(mip_serializer* serializer, const mip_rtk_led_control_command* self) { for(unsigned int i=0; i < 3; i++) - insert_u8(serializer, self->primaryColor[i]); + microstrain_insert_u8(serializer, self->primaryColor[i]); for(unsigned int i=0; i < 3; i++) - insert_u8(serializer, self->altColor[i]); + microstrain_insert_u8(serializer, self->altColor[i]); insert_mip_led_action(serializer, self->act); - - insert_u32(serializer, self->period); + + microstrain_insert_u32(serializer, self->period); } void extract_mip_rtk_led_control_command(mip_serializer* serializer, mip_rtk_led_control_command* self) { for(unsigned int i=0; i < 3; i++) - extract_u8(serializer, &self->primaryColor[i]); + microstrain_extract_u8(serializer, &self->primaryColor[i]); for(unsigned int i=0; i < 3; i++) - extract_u8(serializer, &self->altColor[i]); + microstrain_extract_u8(serializer, &self->altColor[i]); extract_mip_led_action(serializer, &self->act); - - extract_u32(serializer, &self->period); + + microstrain_extract_u32(serializer, &self->period); } @@ -485,19 +492,20 @@ mip_cmd_result mip_rtk_led_control(struct mip_interface* device, const uint8_t* assert(primary_color || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_u8(&serializer, primary_color[i]); + microstrain_insert_u8(&serializer, primary_color[i]); assert(alt_color || (3 == 0)); for(unsigned int i=0; i < 3; i++) - insert_u8(&serializer, alt_color[i]); + microstrain_insert_u8(&serializer, alt_color[i]); insert_mip_led_action(&serializer, act); + + microstrain_insert_u32(&serializer, period); - insert_u32(&serializer, period); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_LED_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_LED_CONTROL, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_rtk_modem_hard_reset(struct mip_interface* device) { diff --git a/src/mip/definitions/commands_rtk.cpp b/src/mip/definitions/commands_rtk.cpp index 2ec4b6dd2..6c854c4db 100644 --- a/src/mip/definitions/commands_rtk.cpp +++ b/src/mip/definitions/commands_rtk.cpp @@ -1,7 +1,7 @@ #include "commands_rtk.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/commands_system.c b/src/mip/definitions/commands_system.c index e20d55a67..97fd45816 100644 --- a/src/mip/definitions/commands_system.c +++ b/src/mip/definitions/commands_system.c @@ -1,7 +1,7 @@ #include "commands_system.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -33,7 +33,7 @@ void insert_mip_system_comm_mode_command(mip_serializer* serializer, const mip_s if( self->function == MIP_FUNCTION_WRITE ) { - insert_u8(serializer, self->mode); + microstrain_insert_u8(serializer, self->mode); } } @@ -43,19 +43,19 @@ void extract_mip_system_comm_mode_command(mip_serializer* serializer, mip_system if( self->function == MIP_FUNCTION_WRITE ) { - extract_u8(serializer, &self->mode); + microstrain_extract_u8(serializer, &self->mode); } } void insert_mip_system_comm_mode_response(mip_serializer* serializer, const mip_system_comm_mode_response* self) { - insert_u8(serializer, self->mode); + microstrain_insert_u8(serializer, self->mode); } void extract_mip_system_comm_mode_response(mip_serializer* serializer, mip_system_comm_mode_response* self) { - extract_u8(serializer, &self->mode); + microstrain_extract_u8(serializer, &self->mode); } @@ -66,12 +66,13 @@ mip_cmd_result mip_system_write_comm_mode(struct mip_interface* device, uint8_t mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + microstrain_insert_u8(&serializer, mode); - insert_u8(&serializer, mode); - - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* mode_out) { @@ -81,10 +82,11 @@ mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t)mip_serializer_length(&serializer), MIP_REPLY_DESC_SYSTEM_COM_MODE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t) microstrain_serializer_length( + &serializer), MIP_REPLY_DESC_SYSTEM_COM_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -92,9 +94,9 @@ mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* mip_serializer_init_insertion(&deserializer, buffer, responseLength); assert(mode_out); - extract_u8(&deserializer, mode_out); + microstrain_extract_u8(&deserializer, mode_out); - if( mip_serializer_remaining(&deserializer) != 0 ) + if(microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -107,9 +109,10 @@ mip_cmd_result mip_system_default_comm_mode(struct mip_interface* device) insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - assert(mip_serializer_is_ok(&serializer)); + assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t) microstrain_serializer_length( + &serializer)); } #ifdef __cplusplus diff --git a/src/mip/definitions/commands_system.cpp b/src/mip/definitions/commands_system.cpp index 748a9c184..d1c11614a 100644 --- a/src/mip/definitions/commands_system.cpp +++ b/src/mip/definitions/commands_system.cpp @@ -1,7 +1,7 @@ #include "commands_system.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/common.c b/src/mip/definitions/common.c index 686d4885a..90023557c 100644 --- a/src/mip/definitions/common.c +++ b/src/mip/definitions/common.c @@ -1,19 +1,19 @@ #include "common.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" void insert_mip_descriptor_rate(mip_serializer* serializer, const mip_descriptor_rate* self) { - insert_u8(serializer, self->descriptor); - insert_u16(serializer, self->decimation); + microstrain_insert_u8(serializer, self->descriptor); + microstrain_insert_u16(serializer, self->decimation); } void extract_mip_descriptor_rate(mip_serializer* serializer, mip_descriptor_rate* self) { - extract_u8(serializer, &self->descriptor); - extract_u16(serializer, &self->decimation); + microstrain_extract_u8(serializer, &self->descriptor); + microstrain_extract_u16(serializer, &self->decimation); } #define IMPLEMENT_MIP_VECTOR_FUNCTIONS(n,type,name) \ diff --git a/src/mip/definitions/common.h b/src/mip/definitions/common.h index 869557c7c..29afecdad 100644 --- a/src/mip/definitions/common.h +++ b/src/mip/definitions/common.h @@ -3,7 +3,7 @@ #include #include #include -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #ifdef __cplusplus diff --git a/src/mip/definitions/data_filter.c b/src/mip/definitions/data_filter.c index 0e395aba8..28b6f9d9d 100644 --- a/src/mip/definitions/data_filter.c +++ b/src/mip/definitions/data_filter.c @@ -1,7 +1,7 @@ #include "data_filter.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -24,67 +24,67 @@ struct mip_field; void insert_mip_filter_mode(struct mip_serializer* serializer, const mip_filter_mode self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_filter_mode(struct mip_serializer* serializer, mip_filter_mode* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_filter_dynamics_mode(struct mip_serializer* serializer, const mip_filter_dynamics_mode self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_filter_dynamics_mode(struct mip_serializer* serializer, mip_filter_dynamics_mode* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_filter_status_flags(struct mip_serializer* serializer, const mip_filter_status_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_filter_status_flags(struct mip_serializer* serializer, mip_filter_status_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_filter_aiding_measurement_type(struct mip_serializer* serializer, const mip_filter_aiding_measurement_type self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_aiding_measurement_type(struct mip_serializer* serializer, mip_filter_aiding_measurement_type* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_filter_measurement_indicator(struct mip_serializer* serializer, const mip_filter_measurement_indicator self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_measurement_indicator(struct mip_serializer* serializer, mip_filter_measurement_indicator* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_aid_status_flags(struct mip_serializer* serializer, const mip_gnss_aid_status_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_aid_status_flags(struct mip_serializer* serializer, mip_gnss_aid_status_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -95,24 +95,24 @@ void extract_mip_gnss_aid_status_flags(struct mip_serializer* serializer, mip_gn void insert_mip_filter_position_llh_data(mip_serializer* serializer, const mip_filter_position_llh_data* self) { - insert_double(serializer, self->latitude); - - insert_double(serializer, self->longitude); - - insert_double(serializer, self->ellipsoid_height); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_double(serializer, self->latitude); + + microstrain_insert_double(serializer, self->longitude); + + microstrain_insert_double(serializer, self->ellipsoid_height); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_position_llh_data(mip_serializer* serializer, mip_filter_position_llh_data* self) { - extract_double(serializer, &self->latitude); - - extract_double(serializer, &self->longitude); - - extract_double(serializer, &self->ellipsoid_height); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_double(serializer, &self->latitude); + + microstrain_extract_double(serializer, &self->longitude); + + microstrain_extract_double(serializer, &self->ellipsoid_height); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_position_llh_data_from_field(const mip_field* field, void* ptr) @@ -122,29 +122,29 @@ bool extract_mip_filter_position_llh_data_from_field(const mip_field* field, voi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_position_llh_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_velocity_ned_data(mip_serializer* serializer, const mip_filter_velocity_ned_data* self) { - insert_float(serializer, self->north); - - insert_float(serializer, self->east); - - insert_float(serializer, self->down); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->north); + + microstrain_insert_float(serializer, self->east); + + microstrain_insert_float(serializer, self->down); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_velocity_ned_data(mip_serializer* serializer, mip_filter_velocity_ned_data* self) { - extract_float(serializer, &self->north); - - extract_float(serializer, &self->east); - - extract_float(serializer, &self->down); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->north); + + microstrain_extract_float(serializer, &self->east); + + microstrain_extract_float(serializer, &self->down); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_velocity_ned_data_from_field(const mip_field* field, void* ptr) @@ -154,23 +154,23 @@ bool extract_mip_filter_velocity_ned_data_from_field(const mip_field* field, voi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_velocity_ned_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_attitude_quaternion_data(mip_serializer* serializer, const mip_filter_attitude_quaternion_data* self) { for(unsigned int i=0; i < 4; i++) - insert_float(serializer, self->q[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->q[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_attitude_quaternion_data(mip_serializer* serializer, mip_filter_attitude_quaternion_data* self) { for(unsigned int i=0; i < 4; i++) - extract_float(serializer, &self->q[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->q[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field* field, void* ptr) @@ -180,23 +180,23 @@ bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field* fie struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_attitude_quaternion_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_attitude_dcm_data(mip_serializer* serializer, const mip_filter_attitude_dcm_data* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->dcm[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->dcm[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_attitude_dcm_data(mip_serializer* serializer, mip_filter_attitude_dcm_data* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->dcm[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->dcm[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_attitude_dcm_data_from_field(const mip_field* field, void* ptr) @@ -206,29 +206,29 @@ bool extract_mip_filter_attitude_dcm_data_from_field(const mip_field* field, voi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_attitude_dcm_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_euler_angles_data(mip_serializer* serializer, const mip_filter_euler_angles_data* self) { - insert_float(serializer, self->roll); - - insert_float(serializer, self->pitch); - - insert_float(serializer, self->yaw); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->yaw); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_euler_angles_data(mip_serializer* serializer, mip_filter_euler_angles_data* self) { - extract_float(serializer, &self->roll); - - extract_float(serializer, &self->pitch); - - extract_float(serializer, &self->yaw); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->yaw); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_euler_angles_data_from_field(const mip_field* field, void* ptr) @@ -238,23 +238,23 @@ bool extract_mip_filter_euler_angles_data_from_field(const mip_field* field, voi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_euler_angles_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_gyro_bias_data(mip_serializer* serializer, const mip_filter_gyro_bias_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->bias[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gyro_bias_data(mip_serializer* serializer, mip_filter_gyro_bias_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->bias[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_gyro_bias_data_from_field(const mip_field* field, void* ptr) @@ -264,23 +264,23 @@ bool extract_mip_filter_gyro_bias_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_bias_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_accel_bias_data(mip_serializer* serializer, const mip_filter_accel_bias_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->bias[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_accel_bias_data(mip_serializer* serializer, mip_filter_accel_bias_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->bias[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_accel_bias_data_from_field(const mip_field* field, void* ptr) @@ -290,29 +290,29 @@ bool extract_mip_filter_accel_bias_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_bias_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_position_llh_uncertainty_data(mip_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self) { - insert_float(serializer, self->north); - - insert_float(serializer, self->east); - - insert_float(serializer, self->down); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->north); + + microstrain_insert_float(serializer, self->east); + + microstrain_insert_float(serializer, self->down); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_position_llh_uncertainty_data(mip_serializer* serializer, mip_filter_position_llh_uncertainty_data* self) { - extract_float(serializer, &self->north); - - extract_float(serializer, &self->east); - - extract_float(serializer, &self->down); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->north); + + microstrain_extract_float(serializer, &self->east); + + microstrain_extract_float(serializer, &self->down); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_position_llh_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -322,29 +322,29 @@ bool extract_mip_filter_position_llh_uncertainty_data_from_field(const mip_field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_position_llh_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_velocity_ned_uncertainty_data(mip_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self) { - insert_float(serializer, self->north); - - insert_float(serializer, self->east); - - insert_float(serializer, self->down); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->north); + + microstrain_insert_float(serializer, self->east); + + microstrain_insert_float(serializer, self->down); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_velocity_ned_uncertainty_data(mip_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self) { - extract_float(serializer, &self->north); - - extract_float(serializer, &self->east); - - extract_float(serializer, &self->down); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->north); + + microstrain_extract_float(serializer, &self->east); + + microstrain_extract_float(serializer, &self->down); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -354,29 +354,29 @@ bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const mip_field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_velocity_ned_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_euler_angles_uncertainty_data(mip_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self) { - insert_float(serializer, self->roll); - - insert_float(serializer, self->pitch); - - insert_float(serializer, self->yaw); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->yaw); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_euler_angles_uncertainty_data(mip_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self) { - extract_float(serializer, &self->roll); - - extract_float(serializer, &self->pitch); - - extract_float(serializer, &self->yaw); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->yaw); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -386,23 +386,23 @@ bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const mip_field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_euler_angles_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_gyro_bias_uncertainty_data(mip_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias_uncert[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->bias_uncert[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gyro_bias_uncertainty_data(mip_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias_uncert[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->bias_uncert[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -412,23 +412,23 @@ bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const mip_field* f struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_bias_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_accel_bias_uncertainty_data(mip_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias_uncert[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->bias_uncert[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_accel_bias_uncertainty_data(mip_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias_uncert[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->bias_uncert[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -438,25 +438,25 @@ bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const mip_field* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_bias_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_timestamp_data(mip_serializer* serializer, const mip_filter_timestamp_data* self) { - insert_double(serializer, self->tow); - - insert_u16(serializer, self->week_number); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_double(serializer, self->tow); + + microstrain_insert_u16(serializer, self->week_number); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_timestamp_data(mip_serializer* serializer, mip_filter_timestamp_data* self) { - extract_double(serializer, &self->tow); - - extract_u16(serializer, &self->week_number); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_double(serializer, &self->tow); + + microstrain_extract_u16(serializer, &self->week_number); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_timestamp_data_from_field(const mip_field* field, void* ptr) @@ -466,7 +466,7 @@ bool extract_mip_filter_timestamp_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_timestamp_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_status_data(mip_serializer* serializer, const mip_filter_status_data* self) @@ -494,23 +494,23 @@ bool extract_mip_filter_status_data_from_field(const mip_field* field, void* ptr struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_linear_accel_data(mip_serializer* serializer, const mip_filter_linear_accel_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->accel[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->accel[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_linear_accel_data(mip_serializer* serializer, mip_filter_linear_accel_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->accel[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->accel[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_linear_accel_data_from_field(const mip_field* field, void* ptr) @@ -520,23 +520,23 @@ bool extract_mip_filter_linear_accel_data_from_field(const mip_field* field, voi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_linear_accel_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_gravity_vector_data(mip_serializer* serializer, const mip_filter_gravity_vector_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->gravity[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->gravity[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gravity_vector_data(mip_serializer* serializer, mip_filter_gravity_vector_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->gravity[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->gravity[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_gravity_vector_data_from_field(const mip_field* field, void* ptr) @@ -546,23 +546,23 @@ bool extract_mip_filter_gravity_vector_data_from_field(const mip_field* field, v struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_gravity_vector_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_comp_accel_data(mip_serializer* serializer, const mip_filter_comp_accel_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->accel[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->accel[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_comp_accel_data(mip_serializer* serializer, mip_filter_comp_accel_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->accel[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->accel[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_comp_accel_data_from_field(const mip_field* field, void* ptr) @@ -572,23 +572,23 @@ bool extract_mip_filter_comp_accel_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_comp_accel_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_comp_angular_rate_data(mip_serializer* serializer, const mip_filter_comp_angular_rate_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->gyro[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->gyro[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_comp_angular_rate_data(mip_serializer* serializer, mip_filter_comp_angular_rate_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->gyro[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->gyro[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_comp_angular_rate_data_from_field(const mip_field* field, void* ptr) @@ -598,23 +598,23 @@ bool extract_mip_filter_comp_angular_rate_data_from_field(const mip_field* field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_comp_angular_rate_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_quaternion_attitude_uncertainty_data(mip_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self) { for(unsigned int i=0; i < 4; i++) - insert_float(serializer, self->q[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->q[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_quaternion_attitude_uncertainty_data(mip_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self) { for(unsigned int i=0; i < 4; i++) - extract_float(serializer, &self->q[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->q[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -624,21 +624,21 @@ bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const mi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_quaternion_attitude_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_wgs84_gravity_mag_data(mip_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self) { - insert_float(serializer, self->magnitude); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->magnitude); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_wgs84_gravity_mag_data(mip_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self) { - extract_float(serializer, &self->magnitude); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->magnitude); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const mip_field* field, void* ptr) @@ -648,29 +648,29 @@ bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const mip_field* field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_wgs84_gravity_mag_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_heading_update_state_data(mip_serializer* serializer, const mip_filter_heading_update_state_data* self) { - insert_float(serializer, self->heading); - - insert_float(serializer, self->heading_1sigma); + microstrain_insert_float(serializer, self->heading); + + microstrain_insert_float(serializer, self->heading_1sigma); insert_mip_filter_heading_update_state_data_heading_source(serializer, self->source); - - insert_u16(serializer, self->valid_flags); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_heading_update_state_data(mip_serializer* serializer, mip_filter_heading_update_state_data* self) { - extract_float(serializer, &self->heading); - - extract_float(serializer, &self->heading_1sigma); + microstrain_extract_float(serializer, &self->heading); + + microstrain_extract_float(serializer, &self->heading_1sigma); extract_mip_filter_heading_update_state_data_heading_source(serializer, &self->source); - - extract_u16(serializer, &self->valid_flags); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_heading_update_state_data_from_field(const mip_field* field, void* ptr) @@ -680,48 +680,48 @@ bool extract_mip_filter_heading_update_state_data_from_field(const mip_field* fi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_heading_update_state_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_heading_update_state_data_heading_source(struct mip_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_filter_heading_update_state_data_heading_source(struct mip_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_filter_magnetic_model_data(mip_serializer* serializer, const mip_filter_magnetic_model_data* self) { - insert_float(serializer, self->intensity_north); - - insert_float(serializer, self->intensity_east); - - insert_float(serializer, self->intensity_down); - - insert_float(serializer, self->inclination); - - insert_float(serializer, self->declination); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->intensity_north); + + microstrain_insert_float(serializer, self->intensity_east); + + microstrain_insert_float(serializer, self->intensity_down); + + microstrain_insert_float(serializer, self->inclination); + + microstrain_insert_float(serializer, self->declination); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetic_model_data(mip_serializer* serializer, mip_filter_magnetic_model_data* self) { - extract_float(serializer, &self->intensity_north); - - extract_float(serializer, &self->intensity_east); - - extract_float(serializer, &self->intensity_down); - - extract_float(serializer, &self->inclination); - - extract_float(serializer, &self->declination); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->intensity_north); + + microstrain_extract_float(serializer, &self->intensity_east); + + microstrain_extract_float(serializer, &self->intensity_down); + + microstrain_extract_float(serializer, &self->inclination); + + microstrain_extract_float(serializer, &self->declination); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_magnetic_model_data_from_field(const mip_field* field, void* ptr) @@ -731,23 +731,23 @@ bool extract_mip_filter_magnetic_model_data_from_field(const mip_field* field, v struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetic_model_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_accel_scale_factor_data(mip_serializer* serializer, const mip_filter_accel_scale_factor_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->scale_factor[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->scale_factor[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_accel_scale_factor_data(mip_serializer* serializer, mip_filter_accel_scale_factor_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->scale_factor[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->scale_factor[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_accel_scale_factor_data_from_field(const mip_field* field, void* ptr) @@ -757,23 +757,23 @@ bool extract_mip_filter_accel_scale_factor_data_from_field(const mip_field* fiel struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_scale_factor_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_accel_scale_factor_uncertainty_data(mip_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->scale_factor_uncert[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->scale_factor_uncert[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_accel_scale_factor_uncertainty_data(mip_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->scale_factor_uncert[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->scale_factor_uncert[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -783,23 +783,23 @@ bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const mip struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_scale_factor_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_gyro_scale_factor_data(mip_serializer* serializer, const mip_filter_gyro_scale_factor_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->scale_factor[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->scale_factor[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gyro_scale_factor_data(mip_serializer* serializer, mip_filter_gyro_scale_factor_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->scale_factor[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->scale_factor[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_gyro_scale_factor_data_from_field(const mip_field* field, void* ptr) @@ -809,23 +809,23 @@ bool extract_mip_filter_gyro_scale_factor_data_from_field(const mip_field* field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_scale_factor_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_gyro_scale_factor_uncertainty_data(mip_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->scale_factor_uncert[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->scale_factor_uncert[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gyro_scale_factor_uncertainty_data(mip_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->scale_factor_uncert[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->scale_factor_uncert[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -835,23 +835,23 @@ bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const mip_ struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_scale_factor_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_mag_bias_data(mip_serializer* serializer, const mip_filter_mag_bias_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->bias[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_mag_bias_data(mip_serializer* serializer, mip_filter_mag_bias_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->bias[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_mag_bias_data_from_field(const mip_field* field, void* ptr) @@ -861,23 +861,23 @@ bool extract_mip_filter_mag_bias_data_from_field(const mip_field* field, void* p struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_mag_bias_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_mag_bias_uncertainty_data(mip_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->bias_uncert[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->bias_uncert[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_mag_bias_uncertainty_data(mip_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->bias_uncert[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->bias_uncert[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -887,37 +887,37 @@ bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const mip_field* fi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_mag_bias_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_standard_atmosphere_data(mip_serializer* serializer, const mip_filter_standard_atmosphere_data* self) { - insert_float(serializer, self->geometric_altitude); - - insert_float(serializer, self->geopotential_altitude); - - insert_float(serializer, self->standard_temperature); - - insert_float(serializer, self->standard_pressure); - - insert_float(serializer, self->standard_density); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->geometric_altitude); + + microstrain_insert_float(serializer, self->geopotential_altitude); + + microstrain_insert_float(serializer, self->standard_temperature); + + microstrain_insert_float(serializer, self->standard_pressure); + + microstrain_insert_float(serializer, self->standard_density); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_standard_atmosphere_data(mip_serializer* serializer, mip_filter_standard_atmosphere_data* self) { - extract_float(serializer, &self->geometric_altitude); - - extract_float(serializer, &self->geopotential_altitude); - - extract_float(serializer, &self->standard_temperature); - - extract_float(serializer, &self->standard_pressure); - - extract_float(serializer, &self->standard_density); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->geometric_altitude); + + microstrain_extract_float(serializer, &self->geopotential_altitude); + + microstrain_extract_float(serializer, &self->standard_temperature); + + microstrain_extract_float(serializer, &self->standard_pressure); + + microstrain_extract_float(serializer, &self->standard_density); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_standard_atmosphere_data_from_field(const mip_field* field, void* ptr) @@ -927,21 +927,21 @@ bool extract_mip_filter_standard_atmosphere_data_from_field(const mip_field* fie struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_standard_atmosphere_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_pressure_altitude_data(mip_serializer* serializer, const mip_filter_pressure_altitude_data* self) { - insert_float(serializer, self->pressure_altitude); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->pressure_altitude); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_pressure_altitude_data(mip_serializer* serializer, mip_filter_pressure_altitude_data* self) { - extract_float(serializer, &self->pressure_altitude); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->pressure_altitude); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_pressure_altitude_data_from_field(const mip_field* field, void* ptr) @@ -951,21 +951,21 @@ bool extract_mip_filter_pressure_altitude_data_from_field(const mip_field* field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_pressure_altitude_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_density_altitude_data(mip_serializer* serializer, const mip_filter_density_altitude_data* self) { - insert_float(serializer, self->density_altitude); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->density_altitude); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_density_altitude_data(mip_serializer* serializer, mip_filter_density_altitude_data* self) { - extract_float(serializer, &self->density_altitude); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->density_altitude); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_density_altitude_data_from_field(const mip_field* field, void* ptr) @@ -975,23 +975,23 @@ bool extract_mip_filter_density_altitude_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_density_altitude_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_antenna_offset_correction_data(mip_serializer* serializer, const mip_filter_antenna_offset_correction_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->offset[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_antenna_offset_correction_data(mip_serializer* serializer, mip_filter_antenna_offset_correction_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->offset[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_antenna_offset_correction_data_from_field(const mip_field* field, void* ptr) @@ -1001,23 +1001,23 @@ bool extract_mip_filter_antenna_offset_correction_data_from_field(const mip_fiel struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_antenna_offset_correction_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_antenna_offset_correction_uncertainty_data(mip_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset_uncert[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->offset_uncert[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_antenna_offset_correction_uncertainty_data(mip_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset_uncert[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->offset_uncert[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -1027,27 +1027,27 @@ bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(co struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_antenna_offset_correction_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_multi_antenna_offset_correction_data(mip_serializer* serializer, const mip_filter_multi_antenna_offset_correction_data* self) { - insert_u8(serializer, self->receiver_id); + microstrain_insert_u8(serializer, self->receiver_id); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->offset[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_multi_antenna_offset_correction_data(mip_serializer* serializer, mip_filter_multi_antenna_offset_correction_data* self) { - extract_u8(serializer, &self->receiver_id); + microstrain_extract_u8(serializer, &self->receiver_id); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->offset[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const mip_field* field, void* ptr) @@ -1057,27 +1057,27 @@ bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const mi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_multi_antenna_offset_correction_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(mip_serializer* serializer, const mip_filter_multi_antenna_offset_correction_uncertainty_data* self) { - insert_u8(serializer, self->receiver_id); + microstrain_insert_u8(serializer, self->receiver_id); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->offset_uncert[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->offset_uncert[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(mip_serializer* serializer, mip_filter_multi_antenna_offset_correction_uncertainty_data* self) { - extract_u8(serializer, &self->receiver_id); + microstrain_extract_u8(serializer, &self->receiver_id); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->offset_uncert[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->offset_uncert[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -1087,23 +1087,23 @@ bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_fi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_magnetometer_offset_data(mip_serializer* serializer, const mip_filter_magnetometer_offset_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->hard_iron[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->hard_iron[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_offset_data(mip_serializer* serializer, mip_filter_magnetometer_offset_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->hard_iron[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->hard_iron[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_magnetometer_offset_data_from_field(const mip_field* field, void* ptr) @@ -1113,23 +1113,23 @@ bool extract_mip_filter_magnetometer_offset_data_from_field(const mip_field* fie struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_offset_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_magnetometer_matrix_data(mip_serializer* serializer, const mip_filter_magnetometer_matrix_data* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->soft_iron[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->soft_iron[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_matrix_data(mip_serializer* serializer, mip_filter_magnetometer_matrix_data* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->soft_iron[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->soft_iron[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_magnetometer_matrix_data_from_field(const mip_field* field, void* ptr) @@ -1139,23 +1139,23 @@ bool extract_mip_filter_magnetometer_matrix_data_from_field(const mip_field* fie struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_matrix_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_magnetometer_offset_uncertainty_data(mip_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->hard_iron_uncertainty[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->hard_iron_uncertainty[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_offset_uncertainty_data(mip_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->hard_iron_uncertainty[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->hard_iron_uncertainty[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -1165,23 +1165,23 @@ bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const mi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_offset_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_magnetometer_matrix_uncertainty_data(mip_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->soft_iron_uncertainty[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->soft_iron_uncertainty[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_matrix_uncertainty_data(mip_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->soft_iron_uncertainty[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->soft_iron_uncertainty[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -1191,23 +1191,23 @@ bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const mi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_matrix_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_magnetometer_covariance_matrix_data(mip_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->covariance[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->covariance[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_covariance_matrix_data(mip_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->covariance[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->covariance[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const mip_field* field, void* ptr) @@ -1217,23 +1217,23 @@ bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const mip struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_covariance_matrix_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_magnetometer_residual_vector_data(mip_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->residual[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->residual[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_residual_vector_data(mip_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->residual[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->residual[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const mip_field* field, void* ptr) @@ -1243,29 +1243,29 @@ bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const mip_f struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_residual_vector_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_clock_correction_data(mip_serializer* serializer, const mip_filter_clock_correction_data* self) { - insert_u8(serializer, self->receiver_id); - - insert_float(serializer, self->bias); - - insert_float(serializer, self->bias_drift); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_u8(serializer, self->receiver_id); + + microstrain_insert_float(serializer, self->bias); + + microstrain_insert_float(serializer, self->bias_drift); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_clock_correction_data(mip_serializer* serializer, mip_filter_clock_correction_data* self) { - extract_u8(serializer, &self->receiver_id); - - extract_float(serializer, &self->bias); - - extract_float(serializer, &self->bias_drift); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_u8(serializer, &self->receiver_id); + + microstrain_extract_float(serializer, &self->bias); + + microstrain_extract_float(serializer, &self->bias_drift); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_clock_correction_data_from_field(const mip_field* field, void* ptr) @@ -1275,29 +1275,29 @@ bool extract_mip_filter_clock_correction_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_clock_correction_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_clock_correction_uncertainty_data(mip_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self) { - insert_u8(serializer, self->receiver_id); - - insert_float(serializer, self->bias_uncertainty); - - insert_float(serializer, self->bias_drift_uncertainty); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_u8(serializer, self->receiver_id); + + microstrain_insert_float(serializer, self->bias_uncertainty); + + microstrain_insert_float(serializer, self->bias_drift_uncertainty); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_clock_correction_uncertainty_data(mip_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self) { - extract_u8(serializer, &self->receiver_id); - - extract_float(serializer, &self->bias_uncertainty); - - extract_float(serializer, &self->bias_drift_uncertainty); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_u8(serializer, &self->receiver_id); + + microstrain_extract_float(serializer, &self->bias_uncertainty); + + microstrain_extract_float(serializer, &self->bias_drift_uncertainty); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -1307,31 +1307,31 @@ bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const mip_f struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_clock_correction_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_gnss_pos_aid_status_data(mip_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self) { - insert_u8(serializer, self->receiver_id); - - insert_float(serializer, self->time_of_week); + microstrain_insert_u8(serializer, self->receiver_id); + + microstrain_insert_float(serializer, self->time_of_week); insert_mip_gnss_aid_status_flags(serializer, self->status); for(unsigned int i=0; i < 8; i++) - insert_u8(serializer, self->reserved[i]); + microstrain_insert_u8(serializer, self->reserved[i]); } void extract_mip_filter_gnss_pos_aid_status_data(mip_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self) { - extract_u8(serializer, &self->receiver_id); - - extract_float(serializer, &self->time_of_week); + microstrain_extract_u8(serializer, &self->receiver_id); + + microstrain_extract_float(serializer, &self->time_of_week); extract_mip_gnss_aid_status_flags(serializer, &self->status); for(unsigned int i=0; i < 8; i++) - extract_u8(serializer, &self->reserved[i]); + microstrain_extract_u8(serializer, &self->reserved[i]); } bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const mip_field* field, void* ptr) @@ -1341,27 +1341,27 @@ bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const mip_field* fie struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_gnss_pos_aid_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_gnss_att_aid_status_data(mip_serializer* serializer, const mip_filter_gnss_att_aid_status_data* self) { - insert_float(serializer, self->time_of_week); + microstrain_insert_float(serializer, self->time_of_week); insert_mip_gnss_aid_status_flags(serializer, self->status); for(unsigned int i=0; i < 8; i++) - insert_u8(serializer, self->reserved[i]); + microstrain_insert_u8(serializer, self->reserved[i]); } void extract_mip_filter_gnss_att_aid_status_data(mip_serializer* serializer, mip_filter_gnss_att_aid_status_data* self) { - extract_float(serializer, &self->time_of_week); + microstrain_extract_float(serializer, &self->time_of_week); extract_mip_gnss_aid_status_flags(serializer, &self->status); for(unsigned int i=0; i < 8; i++) - extract_u8(serializer, &self->reserved[i]); + microstrain_extract_u8(serializer, &self->reserved[i]); } bool extract_mip_filter_gnss_att_aid_status_data_from_field(const mip_field* field, void* ptr) @@ -1371,27 +1371,27 @@ bool extract_mip_filter_gnss_att_aid_status_data_from_field(const mip_field* fie struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_gnss_att_aid_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_head_aid_status_data(mip_serializer* serializer, const mip_filter_head_aid_status_data* self) { - insert_float(serializer, self->time_of_week); + microstrain_insert_float(serializer, self->time_of_week); insert_mip_filter_head_aid_status_data_heading_aid_type(serializer, self->type); for(unsigned int i=0; i < 2; i++) - insert_float(serializer, self->reserved[i]); + microstrain_insert_float(serializer, self->reserved[i]); } void extract_mip_filter_head_aid_status_data(mip_serializer* serializer, mip_filter_head_aid_status_data* self) { - extract_float(serializer, &self->time_of_week); + microstrain_extract_float(serializer, &self->time_of_week); extract_mip_filter_head_aid_status_data_heading_aid_type(serializer, &self->type); for(unsigned int i=0; i < 2; i++) - extract_float(serializer, &self->reserved[i]); + microstrain_extract_float(serializer, &self->reserved[i]); } bool extract_mip_filter_head_aid_status_data_from_field(const mip_field* field, void* ptr) @@ -1401,34 +1401,34 @@ bool extract_mip_filter_head_aid_status_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_head_aid_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_head_aid_status_data_heading_aid_type(struct mip_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_head_aid_status_data_heading_aid_type(struct mip_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_filter_rel_pos_ned_data(mip_serializer* serializer, const mip_filter_rel_pos_ned_data* self) { for(unsigned int i=0; i < 3; i++) - insert_double(serializer, self->relative_position[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_double(serializer, self->relative_position[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_rel_pos_ned_data(mip_serializer* serializer, mip_filter_rel_pos_ned_data* self) { for(unsigned int i=0; i < 3; i++) - extract_double(serializer, &self->relative_position[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_double(serializer, &self->relative_position[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_rel_pos_ned_data_from_field(const mip_field* field, void* ptr) @@ -1438,23 +1438,23 @@ bool extract_mip_filter_rel_pos_ned_data_from_field(const mip_field* field, void struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_rel_pos_ned_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_ecef_pos_data(mip_serializer* serializer, const mip_filter_ecef_pos_data* self) { for(unsigned int i=0; i < 3; i++) - insert_double(serializer, self->position_ecef[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_double(serializer, self->position_ecef[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_ecef_pos_data(mip_serializer* serializer, mip_filter_ecef_pos_data* self) { for(unsigned int i=0; i < 3; i++) - extract_double(serializer, &self->position_ecef[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_double(serializer, &self->position_ecef[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_ecef_pos_data_from_field(const mip_field* field, void* ptr) @@ -1464,23 +1464,23 @@ bool extract_mip_filter_ecef_pos_data_from_field(const mip_field* field, void* p struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_pos_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_ecef_vel_data(mip_serializer* serializer, const mip_filter_ecef_vel_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->velocity_ecef[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->velocity_ecef[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_ecef_vel_data(mip_serializer* serializer, mip_filter_ecef_vel_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->velocity_ecef[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->velocity_ecef[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_ecef_vel_data_from_field(const mip_field* field, void* ptr) @@ -1490,23 +1490,23 @@ bool extract_mip_filter_ecef_vel_data_from_field(const mip_field* field, void* p struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_vel_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_ecef_pos_uncertainty_data(mip_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->pos_uncertainty[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->pos_uncertainty[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_ecef_pos_uncertainty_data(mip_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->pos_uncertainty[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->pos_uncertainty[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -1516,23 +1516,23 @@ bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const mip_field* fi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_pos_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_ecef_vel_uncertainty_data(mip_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->vel_uncertainty[i]); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->vel_uncertainty[i]); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_ecef_vel_uncertainty_data(mip_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->vel_uncertainty[i]); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->vel_uncertainty[i]); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -1542,14 +1542,14 @@ bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const mip_field* fi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_vel_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_aiding_measurement_summary_data(mip_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self) { - insert_float(serializer, self->time_of_week); - - insert_u8(serializer, self->source); + microstrain_insert_float(serializer, self->time_of_week); + + microstrain_insert_u8(serializer, self->source); insert_mip_filter_aiding_measurement_type(serializer, self->type); @@ -1558,9 +1558,9 @@ void insert_mip_filter_aiding_measurement_summary_data(mip_serializer* serialize } void extract_mip_filter_aiding_measurement_summary_data(mip_serializer* serializer, mip_filter_aiding_measurement_summary_data* self) { - extract_float(serializer, &self->time_of_week); - - extract_u8(serializer, &self->source); + microstrain_extract_float(serializer, &self->time_of_week); + + microstrain_extract_u8(serializer, &self->source); extract_mip_filter_aiding_measurement_type(serializer, &self->type); @@ -1574,21 +1574,21 @@ bool extract_mip_filter_aiding_measurement_summary_data_from_field(const mip_fie struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_aiding_measurement_summary_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_odometer_scale_factor_error_data(mip_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self) { - insert_float(serializer, self->scale_factor_error); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->scale_factor_error); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_odometer_scale_factor_error_data(mip_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self) { - extract_float(serializer, &self->scale_factor_error); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->scale_factor_error); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const mip_field* field, void* ptr) @@ -1598,21 +1598,21 @@ bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const mip_fi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_odometer_scale_factor_error_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(mip_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self) { - insert_float(serializer, self->scale_factor_error_uncertainty); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->scale_factor_error_uncertainty); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(mip_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self) { - extract_float(serializer, &self->scale_factor_error_uncertainty); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->scale_factor_error_uncertainty); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -1622,37 +1622,37 @@ bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field( struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_odometer_scale_factor_error_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_gnss_dual_antenna_status_data(mip_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self) { - insert_float(serializer, self->time_of_week); - - insert_float(serializer, self->heading); - - insert_float(serializer, self->heading_unc); + microstrain_insert_float(serializer, self->time_of_week); + + microstrain_insert_float(serializer, self->heading); + + microstrain_insert_float(serializer, self->heading_unc); insert_mip_filter_gnss_dual_antenna_status_data_fix_type(serializer, self->fix_type); insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(serializer, self->status_flags); - - insert_u16(serializer, self->valid_flags); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gnss_dual_antenna_status_data(mip_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self) { - extract_float(serializer, &self->time_of_week); - - extract_float(serializer, &self->heading); - - extract_float(serializer, &self->heading_unc); + microstrain_extract_float(serializer, &self->time_of_week); + + microstrain_extract_float(serializer, &self->heading); + + microstrain_extract_float(serializer, &self->heading_unc); extract_mip_filter_gnss_dual_antenna_status_data_fix_type(serializer, &self->fix_type); extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(serializer, &self->status_flags); - - extract_u16(serializer, &self->valid_flags); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const mip_field* field, void* ptr) @@ -1662,51 +1662,51 @@ bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const mip_field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_gnss_dual_antenna_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(struct mip_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(struct mip_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct mip_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct mip_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_filter_aiding_frame_config_error_data(mip_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self) { - insert_u8(serializer, self->frame_id); + microstrain_insert_u8(serializer, self->frame_id); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->translation[i]); + microstrain_insert_float(serializer, self->translation[i]); for(unsigned int i=0; i < 4; i++) - insert_float(serializer, self->attitude[i]); + microstrain_insert_float(serializer, self->attitude[i]); } void extract_mip_filter_aiding_frame_config_error_data(mip_serializer* serializer, mip_filter_aiding_frame_config_error_data* self) { - extract_u8(serializer, &self->frame_id); + microstrain_extract_u8(serializer, &self->frame_id); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->translation[i]); + microstrain_extract_float(serializer, &self->translation[i]); for(unsigned int i=0; i < 4; i++) - extract_float(serializer, &self->attitude[i]); + microstrain_extract_float(serializer, &self->attitude[i]); } bool extract_mip_filter_aiding_frame_config_error_data_from_field(const mip_field* field, void* ptr) @@ -1716,29 +1716,29 @@ bool extract_mip_filter_aiding_frame_config_error_data_from_field(const mip_fiel struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_aiding_frame_config_error_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_filter_aiding_frame_config_error_uncertainty_data(mip_serializer* serializer, const mip_filter_aiding_frame_config_error_uncertainty_data* self) { - insert_u8(serializer, self->frame_id); + microstrain_insert_u8(serializer, self->frame_id); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->translation_unc[i]); + microstrain_insert_float(serializer, self->translation_unc[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->attitude_unc[i]); + microstrain_insert_float(serializer, self->attitude_unc[i]); } void extract_mip_filter_aiding_frame_config_error_uncertainty_data(mip_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self) { - extract_u8(serializer, &self->frame_id); + microstrain_extract_u8(serializer, &self->frame_id); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->translation_unc[i]); + microstrain_extract_float(serializer, &self->translation_unc[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->attitude_unc[i]); + microstrain_extract_float(serializer, &self->attitude_unc[i]); } bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const mip_field* field, void* ptr) @@ -1748,7 +1748,7 @@ bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(co struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_filter_aiding_frame_config_error_uncertainty_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } diff --git a/src/mip/definitions/data_filter.cpp b/src/mip/definitions/data_filter.cpp index 50e8ae9ba..9ed9f9cb5 100644 --- a/src/mip/definitions/data_filter.cpp +++ b/src/mip/definitions/data_filter.cpp @@ -1,7 +1,7 @@ #include "data_filter.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/data_gnss.c b/src/mip/definitions/data_gnss.c index 2213a4bd9..7849b677b 100644 --- a/src/mip/definitions/data_gnss.c +++ b/src/mip/definitions/data_gnss.c @@ -1,7 +1,7 @@ #include "data_gnss.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -24,34 +24,34 @@ struct mip_field; void insert_mip_gnss_constellation_id(struct mip_serializer* serializer, const mip_gnss_constellation_id self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_constellation_id(struct mip_serializer* serializer, mip_gnss_constellation_id* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_signal_id(struct mip_serializer* serializer, const mip_gnss_signal_id self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_signal_id(struct mip_serializer* serializer, mip_gnss_signal_id* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_sbas_system(struct mip_serializer* serializer, const mip_sbas_system self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_sbas_system(struct mip_serializer* serializer, mip_sbas_system* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } @@ -62,34 +62,34 @@ void extract_mip_sbas_system(struct mip_serializer* serializer, mip_sbas_system* void insert_mip_gnss_pos_llh_data(mip_serializer* serializer, const mip_gnss_pos_llh_data* self) { - insert_double(serializer, self->latitude); - - insert_double(serializer, self->longitude); - - insert_double(serializer, self->ellipsoid_height); - - insert_double(serializer, self->msl_height); - - insert_float(serializer, self->horizontal_accuracy); - - insert_float(serializer, self->vertical_accuracy); + microstrain_insert_double(serializer, self->latitude); + + microstrain_insert_double(serializer, self->longitude); + + microstrain_insert_double(serializer, self->ellipsoid_height); + + microstrain_insert_double(serializer, self->msl_height); + + microstrain_insert_float(serializer, self->horizontal_accuracy); + + microstrain_insert_float(serializer, self->vertical_accuracy); insert_mip_gnss_pos_llh_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_pos_llh_data(mip_serializer* serializer, mip_gnss_pos_llh_data* self) { - extract_double(serializer, &self->latitude); - - extract_double(serializer, &self->longitude); - - extract_double(serializer, &self->ellipsoid_height); - - extract_double(serializer, &self->msl_height); - - extract_float(serializer, &self->horizontal_accuracy); - - extract_float(serializer, &self->vertical_accuracy); + microstrain_extract_double(serializer, &self->latitude); + + microstrain_extract_double(serializer, &self->longitude); + + microstrain_extract_double(serializer, &self->ellipsoid_height); + + microstrain_extract_double(serializer, &self->msl_height); + + microstrain_extract_float(serializer, &self->horizontal_accuracy); + + microstrain_extract_float(serializer, &self->vertical_accuracy); extract_mip_gnss_pos_llh_data_valid_flags(serializer, &self->valid_flags); @@ -101,26 +101,26 @@ bool extract_mip_gnss_pos_llh_data_from_field(const mip_field* field, void* ptr) struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_pos_llh_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_pos_llh_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_pos_llh_data_valid_flags(struct mip_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_pos_ecef_data(mip_serializer* serializer, const mip_gnss_pos_ecef_data* self) { for(unsigned int i=0; i < 3; i++) - insert_double(serializer, self->x[i]); - - insert_float(serializer, self->x_accuracy); + microstrain_insert_double(serializer, self->x[i]); + + microstrain_insert_float(serializer, self->x_accuracy); insert_mip_gnss_pos_ecef_data_valid_flags(serializer, self->valid_flags); @@ -128,9 +128,9 @@ void insert_mip_gnss_pos_ecef_data(mip_serializer* serializer, const mip_gnss_po void extract_mip_gnss_pos_ecef_data(mip_serializer* serializer, mip_gnss_pos_ecef_data* self) { for(unsigned int i=0; i < 3; i++) - extract_double(serializer, &self->x[i]); - - extract_float(serializer, &self->x_accuracy); + microstrain_extract_double(serializer, &self->x[i]); + + microstrain_extract_float(serializer, &self->x_accuracy); extract_mip_gnss_pos_ecef_data_valid_flags(serializer, &self->valid_flags); @@ -142,34 +142,34 @@ bool extract_mip_gnss_pos_ecef_data_from_field(const mip_field* field, void* ptr struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_pos_ecef_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_pos_ecef_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_pos_ecef_data_valid_flags(struct mip_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_vel_ned_data(mip_serializer* serializer, const mip_gnss_vel_ned_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->v[i]); - - insert_float(serializer, self->speed); - - insert_float(serializer, self->ground_speed); - - insert_float(serializer, self->heading); - - insert_float(serializer, self->speed_accuracy); - - insert_float(serializer, self->heading_accuracy); + microstrain_insert_float(serializer, self->v[i]); + + microstrain_insert_float(serializer, self->speed); + + microstrain_insert_float(serializer, self->ground_speed); + + microstrain_insert_float(serializer, self->heading); + + microstrain_insert_float(serializer, self->speed_accuracy); + + microstrain_insert_float(serializer, self->heading_accuracy); insert_mip_gnss_vel_ned_data_valid_flags(serializer, self->valid_flags); @@ -177,17 +177,17 @@ void insert_mip_gnss_vel_ned_data(mip_serializer* serializer, const mip_gnss_vel void extract_mip_gnss_vel_ned_data(mip_serializer* serializer, mip_gnss_vel_ned_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->v[i]); - - extract_float(serializer, &self->speed); - - extract_float(serializer, &self->ground_speed); - - extract_float(serializer, &self->heading); - - extract_float(serializer, &self->speed_accuracy); - - extract_float(serializer, &self->heading_accuracy); + microstrain_extract_float(serializer, &self->v[i]); + + microstrain_extract_float(serializer, &self->speed); + + microstrain_extract_float(serializer, &self->ground_speed); + + microstrain_extract_float(serializer, &self->heading); + + microstrain_extract_float(serializer, &self->speed_accuracy); + + microstrain_extract_float(serializer, &self->heading_accuracy); extract_mip_gnss_vel_ned_data_valid_flags(serializer, &self->valid_flags); @@ -199,26 +199,26 @@ bool extract_mip_gnss_vel_ned_data_from_field(const mip_field* field, void* ptr) struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_vel_ned_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_vel_ned_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_vel_ned_data_valid_flags(struct mip_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_vel_ecef_data(mip_serializer* serializer, const mip_gnss_vel_ecef_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->v[i]); - - insert_float(serializer, self->v_accuracy); + microstrain_insert_float(serializer, self->v[i]); + + microstrain_insert_float(serializer, self->v_accuracy); insert_mip_gnss_vel_ecef_data_valid_flags(serializer, self->valid_flags); @@ -226,9 +226,9 @@ void insert_mip_gnss_vel_ecef_data(mip_serializer* serializer, const mip_gnss_ve void extract_mip_gnss_vel_ecef_data(mip_serializer* serializer, mip_gnss_vel_ecef_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->v[i]); - - extract_float(serializer, &self->v_accuracy); + microstrain_extract_float(serializer, &self->v[i]); + + microstrain_extract_float(serializer, &self->v_accuracy); extract_mip_gnss_vel_ecef_data_valid_flags(serializer, &self->valid_flags); @@ -240,54 +240,54 @@ bool extract_mip_gnss_vel_ecef_data_from_field(const mip_field* field, void* ptr struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_vel_ecef_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_vel_ecef_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_vel_ecef_data_valid_flags(struct mip_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_dop_data(mip_serializer* serializer, const mip_gnss_dop_data* self) { - insert_float(serializer, self->gdop); - - insert_float(serializer, self->pdop); - - insert_float(serializer, self->hdop); - - insert_float(serializer, self->vdop); - - insert_float(serializer, self->tdop); - - insert_float(serializer, self->ndop); - - insert_float(serializer, self->edop); + microstrain_insert_float(serializer, self->gdop); + + microstrain_insert_float(serializer, self->pdop); + + microstrain_insert_float(serializer, self->hdop); + + microstrain_insert_float(serializer, self->vdop); + + microstrain_insert_float(serializer, self->tdop); + + microstrain_insert_float(serializer, self->ndop); + + microstrain_insert_float(serializer, self->edop); insert_mip_gnss_dop_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_dop_data(mip_serializer* serializer, mip_gnss_dop_data* self) { - extract_float(serializer, &self->gdop); - - extract_float(serializer, &self->pdop); - - extract_float(serializer, &self->hdop); - - extract_float(serializer, &self->vdop); - - extract_float(serializer, &self->tdop); - - extract_float(serializer, &self->ndop); - - extract_float(serializer, &self->edop); + microstrain_extract_float(serializer, &self->gdop); + + microstrain_extract_float(serializer, &self->pdop); + + microstrain_extract_float(serializer, &self->hdop); + + microstrain_extract_float(serializer, &self->vdop); + + microstrain_extract_float(serializer, &self->tdop); + + microstrain_extract_float(serializer, &self->ndop); + + microstrain_extract_float(serializer, &self->edop); extract_mip_gnss_dop_data_valid_flags(serializer, &self->valid_flags); @@ -299,54 +299,54 @@ bool extract_mip_gnss_dop_data_from_field(const mip_field* field, void* ptr) struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_dop_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_dop_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_dop_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_dop_data_valid_flags(struct mip_serializer* serializer, mip_gnss_dop_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_utc_time_data(mip_serializer* serializer, const mip_gnss_utc_time_data* self) { - insert_u16(serializer, self->year); - - insert_u8(serializer, self->month); - - insert_u8(serializer, self->day); - - insert_u8(serializer, self->hour); - - insert_u8(serializer, self->min); - - insert_u8(serializer, self->sec); - - insert_u32(serializer, self->msec); + microstrain_insert_u16(serializer, self->year); + + microstrain_insert_u8(serializer, self->month); + + microstrain_insert_u8(serializer, self->day); + + microstrain_insert_u8(serializer, self->hour); + + microstrain_insert_u8(serializer, self->min); + + microstrain_insert_u8(serializer, self->sec); + + microstrain_insert_u32(serializer, self->msec); insert_mip_gnss_utc_time_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_utc_time_data(mip_serializer* serializer, mip_gnss_utc_time_data* self) { - extract_u16(serializer, &self->year); - - extract_u8(serializer, &self->month); - - extract_u8(serializer, &self->day); - - extract_u8(serializer, &self->hour); - - extract_u8(serializer, &self->min); - - extract_u8(serializer, &self->sec); - - extract_u32(serializer, &self->msec); + microstrain_extract_u16(serializer, &self->year); + + microstrain_extract_u8(serializer, &self->month); + + microstrain_extract_u8(serializer, &self->day); + + microstrain_extract_u8(serializer, &self->hour); + + microstrain_extract_u8(serializer, &self->min); + + microstrain_extract_u8(serializer, &self->sec); + + microstrain_extract_u32(serializer, &self->msec); extract_mip_gnss_utc_time_data_valid_flags(serializer, &self->valid_flags); @@ -358,34 +358,34 @@ bool extract_mip_gnss_utc_time_data_from_field(const mip_field* field, void* ptr struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_utc_time_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_utc_time_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_utc_time_data_valid_flags(struct mip_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_gps_time_data(mip_serializer* serializer, const mip_gnss_gps_time_data* self) { - insert_double(serializer, self->tow); - - insert_u16(serializer, self->week_number); + microstrain_insert_double(serializer, self->tow); + + microstrain_insert_u16(serializer, self->week_number); insert_mip_gnss_gps_time_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_gps_time_data(mip_serializer* serializer, mip_gnss_gps_time_data* self) { - extract_double(serializer, &self->tow); - - extract_u16(serializer, &self->week_number); + microstrain_extract_double(serializer, &self->tow); + + microstrain_extract_u16(serializer, &self->week_number); extract_mip_gnss_gps_time_data_valid_flags(serializer, &self->valid_flags); @@ -397,38 +397,38 @@ bool extract_mip_gnss_gps_time_data_from_field(const mip_field* field, void* ptr struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_time_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_gps_time_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_gps_time_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_clock_info_data(mip_serializer* serializer, const mip_gnss_clock_info_data* self) { - insert_double(serializer, self->bias); - - insert_double(serializer, self->drift); - - insert_double(serializer, self->accuracy_estimate); + microstrain_insert_double(serializer, self->bias); + + microstrain_insert_double(serializer, self->drift); + + microstrain_insert_double(serializer, self->accuracy_estimate); insert_mip_gnss_clock_info_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_clock_info_data(mip_serializer* serializer, mip_gnss_clock_info_data* self) { - extract_double(serializer, &self->bias); - - extract_double(serializer, &self->drift); - - extract_double(serializer, &self->accuracy_estimate); + microstrain_extract_double(serializer, &self->bias); + + microstrain_extract_double(serializer, &self->drift); + + microstrain_extract_double(serializer, &self->accuracy_estimate); extract_mip_gnss_clock_info_data_valid_flags(serializer, &self->valid_flags); @@ -440,25 +440,25 @@ bool extract_mip_gnss_clock_info_data_from_field(const mip_field* field, void* p struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_clock_info_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_clock_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_clock_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_fix_info_data(mip_serializer* serializer, const mip_gnss_fix_info_data* self) { insert_mip_gnss_fix_info_data_fix_type(serializer, self->fix_type); - - insert_u8(serializer, self->num_sv); + + microstrain_insert_u8(serializer, self->num_sv); insert_mip_gnss_fix_info_data_fix_flags(serializer, self->fix_flags); @@ -468,8 +468,8 @@ void insert_mip_gnss_fix_info_data(mip_serializer* serializer, const mip_gnss_fi void extract_mip_gnss_fix_info_data(mip_serializer* serializer, mip_gnss_fix_info_data* self) { extract_mip_gnss_fix_info_data_fix_type(serializer, &self->fix_type); - - extract_u8(serializer, &self->num_sv); + + microstrain_extract_u8(serializer, &self->num_sv); extract_mip_gnss_fix_info_data_fix_flags(serializer, &self->fix_flags); @@ -483,53 +483,53 @@ bool extract_mip_gnss_fix_info_data_from_field(const mip_field* field, void* ptr struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_fix_info_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_fix_info_data_fix_type(struct mip_serializer* serializer, const mip_gnss_fix_info_data_fix_type self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_fix_info_data_fix_type(struct mip_serializer* serializer, mip_gnss_fix_info_data_fix_type* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_fix_info_data_fix_flags(struct mip_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_fix_info_data_fix_flags(struct mip_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_fix_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_fix_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_sv_info_data(mip_serializer* serializer, const mip_gnss_sv_info_data* self) { - insert_u8(serializer, self->channel); - - insert_u8(serializer, self->sv_id); - - insert_u16(serializer, self->carrier_noise_ratio); - - insert_s16(serializer, self->azimuth); - - insert_s16(serializer, self->elevation); + microstrain_insert_u8(serializer, self->channel); + + microstrain_insert_u8(serializer, self->sv_id); + + microstrain_insert_u16(serializer, self->carrier_noise_ratio); + + microstrain_insert_s16(serializer, self->azimuth); + + microstrain_insert_s16(serializer, self->elevation); insert_mip_gnss_sv_info_data_svflags(serializer, self->sv_flags); @@ -538,15 +538,15 @@ void insert_mip_gnss_sv_info_data(mip_serializer* serializer, const mip_gnss_sv_ } void extract_mip_gnss_sv_info_data(mip_serializer* serializer, mip_gnss_sv_info_data* self) { - extract_u8(serializer, &self->channel); - - extract_u8(serializer, &self->sv_id); - - extract_u16(serializer, &self->carrier_noise_ratio); - - extract_s16(serializer, &self->azimuth); - - extract_s16(serializer, &self->elevation); + microstrain_extract_u8(serializer, &self->channel); + + microstrain_extract_u8(serializer, &self->sv_id); + + microstrain_extract_u16(serializer, &self->carrier_noise_ratio); + + microstrain_extract_s16(serializer, &self->azimuth); + + microstrain_extract_s16(serializer, &self->elevation); extract_mip_gnss_sv_info_data_svflags(serializer, &self->sv_flags); @@ -560,28 +560,28 @@ bool extract_mip_gnss_sv_info_data_from_field(const mip_field* field, void* ptr) struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_sv_info_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_sv_info_data_svflags(struct mip_serializer* serializer, const mip_gnss_sv_info_data_svflags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_sv_info_data_svflags(struct mip_serializer* serializer, mip_gnss_sv_info_data_svflags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_sv_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_sv_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -614,75 +614,75 @@ bool extract_mip_gnss_hw_status_data_from_field(const mip_field* field, void* pt struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_hw_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_hw_status_data_receiver_state(struct mip_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_hw_status_data_receiver_state(struct mip_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_hw_status_data_antenna_state(struct mip_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_hw_status_data_antenna_state(struct mip_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_hw_status_data_antenna_power(struct mip_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_hw_status_data_antenna_power(struct mip_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_hw_status_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_hw_status_data_valid_flags(struct mip_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_dgps_info_data(mip_serializer* serializer, const mip_gnss_dgps_info_data* self) { - insert_u8(serializer, self->sv_id); - - insert_float(serializer, self->age); - - insert_float(serializer, self->range_correction); - - insert_float(serializer, self->range_rate_correction); + microstrain_insert_u8(serializer, self->sv_id); + + microstrain_insert_float(serializer, self->age); + + microstrain_insert_float(serializer, self->range_correction); + + microstrain_insert_float(serializer, self->range_rate_correction); insert_mip_gnss_dgps_info_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_dgps_info_data(mip_serializer* serializer, mip_gnss_dgps_info_data* self) { - extract_u8(serializer, &self->sv_id); - - extract_float(serializer, &self->age); - - extract_float(serializer, &self->range_correction); - - extract_float(serializer, &self->range_rate_correction); + microstrain_extract_u8(serializer, &self->sv_id); + + microstrain_extract_float(serializer, &self->age); + + microstrain_extract_float(serializer, &self->range_correction); + + microstrain_extract_float(serializer, &self->range_rate_correction); extract_mip_gnss_dgps_info_data_valid_flags(serializer, &self->valid_flags); @@ -694,42 +694,42 @@ bool extract_mip_gnss_dgps_info_data_from_field(const mip_field* field, void* pt struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_dgps_info_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_dgps_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_dgps_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_dgps_channel_data(mip_serializer* serializer, const mip_gnss_dgps_channel_data* self) { - insert_u8(serializer, self->sv_id); - - insert_float(serializer, self->age); - - insert_float(serializer, self->range_correction); - - insert_float(serializer, self->range_rate_correction); + microstrain_insert_u8(serializer, self->sv_id); + + microstrain_insert_float(serializer, self->age); + + microstrain_insert_float(serializer, self->range_correction); + + microstrain_insert_float(serializer, self->range_rate_correction); insert_mip_gnss_dgps_channel_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_dgps_channel_data(mip_serializer* serializer, mip_gnss_dgps_channel_data* self) { - extract_u8(serializer, &self->sv_id); - - extract_float(serializer, &self->age); - - extract_float(serializer, &self->range_correction); - - extract_float(serializer, &self->range_rate_correction); + microstrain_extract_u8(serializer, &self->sv_id); + + microstrain_extract_float(serializer, &self->age); + + microstrain_extract_float(serializer, &self->range_correction); + + microstrain_extract_float(serializer, &self->range_rate_correction); extract_mip_gnss_dgps_channel_data_valid_flags(serializer, &self->valid_flags); @@ -741,42 +741,42 @@ bool extract_mip_gnss_dgps_channel_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_dgps_channel_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_dgps_channel_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_dgps_channel_data_valid_flags(struct mip_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_clock_info_2_data(mip_serializer* serializer, const mip_gnss_clock_info_2_data* self) { - insert_double(serializer, self->bias); - - insert_double(serializer, self->drift); - - insert_double(serializer, self->bias_accuracy_estimate); - - insert_double(serializer, self->drift_accuracy_estimate); + microstrain_insert_double(serializer, self->bias); + + microstrain_insert_double(serializer, self->drift); + + microstrain_insert_double(serializer, self->bias_accuracy_estimate); + + microstrain_insert_double(serializer, self->drift_accuracy_estimate); insert_mip_gnss_clock_info_2_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_clock_info_2_data(mip_serializer* serializer, mip_gnss_clock_info_2_data* self) { - extract_double(serializer, &self->bias); - - extract_double(serializer, &self->drift); - - extract_double(serializer, &self->bias_accuracy_estimate); - - extract_double(serializer, &self->drift_accuracy_estimate); + microstrain_extract_double(serializer, &self->bias); + + microstrain_extract_double(serializer, &self->drift); + + microstrain_extract_double(serializer, &self->bias_accuracy_estimate); + + microstrain_extract_double(serializer, &self->drift_accuracy_estimate); extract_mip_gnss_clock_info_2_data_valid_flags(serializer, &self->valid_flags); @@ -788,30 +788,30 @@ bool extract_mip_gnss_clock_info_2_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_clock_info_2_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_clock_info_2_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_clock_info_2_data_valid_flags(struct mip_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_gps_leap_seconds_data(mip_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self) { - insert_u8(serializer, self->leap_seconds); + microstrain_insert_u8(serializer, self->leap_seconds); insert_mip_gnss_gps_leap_seconds_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_gps_leap_seconds_data(mip_serializer* serializer, mip_gnss_gps_leap_seconds_data* self) { - extract_u8(serializer, &self->leap_seconds); + microstrain_extract_u8(serializer, &self->leap_seconds); extract_mip_gnss_gps_leap_seconds_data_valid_flags(serializer, &self->valid_flags); @@ -823,31 +823,31 @@ bool extract_mip_gnss_gps_leap_seconds_data_from_field(const mip_field* field, v struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_leap_seconds_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_gps_leap_seconds_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_gps_leap_seconds_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_sbas_info_data(mip_serializer* serializer, const mip_gnss_sbas_info_data* self) { - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); insert_mip_sbas_system(serializer, self->sbas_system); - - insert_u8(serializer, self->sbas_id); - - insert_u8(serializer, self->count); + + microstrain_insert_u8(serializer, self->sbas_id); + + microstrain_insert_u8(serializer, self->count); insert_mip_gnss_sbas_info_data_sbas_status(serializer, self->sbas_status); @@ -856,15 +856,15 @@ void insert_mip_gnss_sbas_info_data(mip_serializer* serializer, const mip_gnss_s } void extract_mip_gnss_sbas_info_data(mip_serializer* serializer, mip_gnss_sbas_info_data* self) { - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); extract_mip_sbas_system(serializer, &self->sbas_system); - - extract_u8(serializer, &self->sbas_id); - - extract_u8(serializer, &self->count); + + microstrain_extract_u8(serializer, &self->sbas_id); + + microstrain_extract_u8(serializer, &self->count); extract_mip_gnss_sbas_info_data_sbas_status(serializer, &self->sbas_status); @@ -878,73 +878,73 @@ bool extract_mip_gnss_sbas_info_data_from_field(const mip_field* field, void* pt struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_sbas_info_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_sbas_info_data_sbas_status(struct mip_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_sbas_info_data_sbas_status(struct mip_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_sbas_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_sbas_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_sbas_correction_data(mip_serializer* serializer, const mip_gnss_sbas_correction_data* self) { - insert_u8(serializer, self->index); - - insert_u8(serializer, self->count); - - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); + microstrain_insert_u8(serializer, self->index); + + microstrain_insert_u8(serializer, self->count); + + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); insert_mip_gnss_constellation_id(serializer, self->gnss_id); - - insert_u8(serializer, self->sv_id); - - insert_u8(serializer, self->udrei); - - insert_float(serializer, self->pseudorange_correction); - - insert_float(serializer, self->iono_correction); + + microstrain_insert_u8(serializer, self->sv_id); + + microstrain_insert_u8(serializer, self->udrei); + + microstrain_insert_float(serializer, self->pseudorange_correction); + + microstrain_insert_float(serializer, self->iono_correction); insert_mip_gnss_sbas_correction_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_sbas_correction_data(mip_serializer* serializer, mip_gnss_sbas_correction_data* self) { - extract_u8(serializer, &self->index); - - extract_u8(serializer, &self->count); - - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); + microstrain_extract_u8(serializer, &self->index); + + microstrain_extract_u8(serializer, &self->count); + + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); extract_mip_gnss_constellation_id(serializer, &self->gnss_id); - - extract_u8(serializer, &self->sv_id); - - extract_u8(serializer, &self->udrei); - - extract_float(serializer, &self->pseudorange_correction); - - extract_float(serializer, &self->iono_correction); + + microstrain_extract_u8(serializer, &self->sv_id); + + microstrain_extract_u8(serializer, &self->udrei); + + microstrain_extract_float(serializer, &self->pseudorange_correction); + + microstrain_extract_float(serializer, &self->iono_correction); extract_mip_gnss_sbas_correction_data_valid_flags(serializer, &self->valid_flags); @@ -956,17 +956,17 @@ bool extract_mip_gnss_sbas_correction_data_from_field(const mip_field* field, vo struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_sbas_correction_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_sbas_correction_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_sbas_correction_data_valid_flags(struct mip_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } @@ -979,7 +979,7 @@ void insert_mip_gnss_rf_error_detection_data(mip_serializer* serializer, const m insert_mip_gnss_rf_error_detection_data_spoofing_state(serializer, self->spoofing_state); for(unsigned int i=0; i < 4; i++) - insert_u8(serializer, self->reserved[i]); + microstrain_insert_u8(serializer, self->reserved[i]); insert_mip_gnss_rf_error_detection_data_valid_flags(serializer, self->valid_flags); @@ -993,7 +993,7 @@ void extract_mip_gnss_rf_error_detection_data(mip_serializer* serializer, mip_gn extract_mip_gnss_rf_error_detection_data_spoofing_state(serializer, &self->spoofing_state); for(unsigned int i=0; i < 4; i++) - extract_u8(serializer, &self->reserved[i]); + microstrain_extract_u8(serializer, &self->reserved[i]); extract_mip_gnss_rf_error_detection_data_valid_flags(serializer, &self->valid_flags); @@ -1005,65 +1005,65 @@ bool extract_mip_gnss_rf_error_detection_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_rf_error_detection_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_rf_error_detection_data_rfband(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_rf_error_detection_data_rfband(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_rf_error_detection_data_jamming_state(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_rf_error_detection_data_jamming_state(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_rf_error_detection_data_spoofing_state(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_rf_error_detection_data_spoofing_state(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_rf_error_detection_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_rf_error_detection_data_valid_flags(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_base_station_info_data(mip_serializer* serializer, const mip_gnss_base_station_info_data* self) { - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); for(unsigned int i=0; i < 3; i++) - insert_double(serializer, self->ecef_pos[i]); - - insert_float(serializer, self->height); - - insert_u16(serializer, self->station_id); + microstrain_insert_double(serializer, self->ecef_pos[i]); + + microstrain_insert_float(serializer, self->height); + + microstrain_insert_u16(serializer, self->station_id); insert_mip_gnss_base_station_info_data_indicator_flags(serializer, self->indicators); @@ -1072,16 +1072,16 @@ void insert_mip_gnss_base_station_info_data(mip_serializer* serializer, const mi } void extract_mip_gnss_base_station_info_data(mip_serializer* serializer, mip_gnss_base_station_info_data* self) { - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); for(unsigned int i=0; i < 3; i++) - extract_double(serializer, &self->ecef_pos[i]); - - extract_float(serializer, &self->height); - - extract_u16(serializer, &self->station_id); + microstrain_extract_double(serializer, &self->ecef_pos[i]); + + microstrain_extract_float(serializer, &self->height); + + microstrain_extract_u16(serializer, &self->station_id); extract_mip_gnss_base_station_info_data_indicator_flags(serializer, &self->indicators); @@ -1095,75 +1095,75 @@ bool extract_mip_gnss_base_station_info_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_base_station_info_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_base_station_info_data_indicator_flags(struct mip_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_base_station_info_data_indicator_flags(struct mip_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_base_station_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_base_station_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_rtk_corrections_status_data(mip_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self) { - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); insert_mip_gnss_rtk_corrections_status_data_epoch_status(serializer, self->epoch_status); - - insert_u32(serializer, self->dongle_status); - - insert_float(serializer, self->gps_correction_latency); - - insert_float(serializer, self->glonass_correction_latency); - - insert_float(serializer, self->galileo_correction_latency); - - insert_float(serializer, self->beidou_correction_latency); + + microstrain_insert_u32(serializer, self->dongle_status); + + microstrain_insert_float(serializer, self->gps_correction_latency); + + microstrain_insert_float(serializer, self->glonass_correction_latency); + + microstrain_insert_float(serializer, self->galileo_correction_latency); + + microstrain_insert_float(serializer, self->beidou_correction_latency); for(unsigned int i=0; i < 4; i++) - insert_u32(serializer, self->reserved[i]); + microstrain_insert_u32(serializer, self->reserved[i]); insert_mip_gnss_rtk_corrections_status_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_rtk_corrections_status_data(mip_serializer* serializer, mip_gnss_rtk_corrections_status_data* self) { - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); extract_mip_gnss_rtk_corrections_status_data_epoch_status(serializer, &self->epoch_status); - - extract_u32(serializer, &self->dongle_status); - - extract_float(serializer, &self->gps_correction_latency); - - extract_float(serializer, &self->glonass_correction_latency); - - extract_float(serializer, &self->galileo_correction_latency); - - extract_float(serializer, &self->beidou_correction_latency); + + microstrain_extract_u32(serializer, &self->dongle_status); + + microstrain_extract_float(serializer, &self->gps_correction_latency); + + microstrain_extract_float(serializer, &self->glonass_correction_latency); + + microstrain_extract_float(serializer, &self->galileo_correction_latency); + + microstrain_extract_float(serializer, &self->beidou_correction_latency); for(unsigned int i=0; i < 4; i++) - extract_u32(serializer, &self->reserved[i]); + microstrain_extract_u32(serializer, &self->reserved[i]); extract_mip_gnss_rtk_corrections_status_data_valid_flags(serializer, &self->valid_flags); @@ -1175,73 +1175,73 @@ bool extract_mip_gnss_rtk_corrections_status_data_from_field(const mip_field* fi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_rtk_corrections_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_rtk_corrections_status_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_rtk_corrections_status_data_valid_flags(struct mip_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_rtk_corrections_status_data_epoch_status(struct mip_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_rtk_corrections_status_data_epoch_status(struct mip_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_satellite_status_data(mip_serializer* serializer, const mip_gnss_satellite_status_data* self) { - insert_u8(serializer, self->index); - - insert_u8(serializer, self->count); - - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); + microstrain_insert_u8(serializer, self->index); + + microstrain_insert_u8(serializer, self->count); + + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); insert_mip_gnss_constellation_id(serializer, self->gnss_id); - - insert_u8(serializer, self->satellite_id); - - insert_float(serializer, self->elevation); - - insert_float(serializer, self->azimuth); - - insert_bool(serializer, self->health); + + microstrain_insert_u8(serializer, self->satellite_id); + + microstrain_insert_float(serializer, self->elevation); + + microstrain_insert_float(serializer, self->azimuth); + + microstrain_insert_bool(serializer, self->health); insert_mip_gnss_satellite_status_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_satellite_status_data(mip_serializer* serializer, mip_gnss_satellite_status_data* self) { - extract_u8(serializer, &self->index); - - extract_u8(serializer, &self->count); - - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); + microstrain_extract_u8(serializer, &self->index); + + microstrain_extract_u8(serializer, &self->count); + + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); extract_mip_gnss_constellation_id(serializer, &self->gnss_id); - - extract_u8(serializer, &self->satellite_id); - - extract_float(serializer, &self->elevation); - - extract_float(serializer, &self->azimuth); - - extract_bool(serializer, &self->health); + + microstrain_extract_u8(serializer, &self->satellite_id); + + microstrain_extract_float(serializer, &self->elevation); + + microstrain_extract_float(serializer, &self->azimuth); + + microstrain_extract_bool(serializer, &self->health); extract_mip_gnss_satellite_status_data_valid_flags(serializer, &self->valid_flags); @@ -1253,98 +1253,98 @@ bool extract_mip_gnss_satellite_status_data_from_field(const mip_field* field, v struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_satellite_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_satellite_status_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_satellite_status_data_valid_flags(struct mip_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_raw_data(mip_serializer* serializer, const mip_gnss_raw_data* self) { - insert_u8(serializer, self->index); - - insert_u8(serializer, self->count); - - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); - - insert_u16(serializer, self->receiver_id); - - insert_u8(serializer, self->tracking_channel); + microstrain_insert_u8(serializer, self->index); + + microstrain_insert_u8(serializer, self->count); + + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); + + microstrain_insert_u16(serializer, self->receiver_id); + + microstrain_insert_u8(serializer, self->tracking_channel); insert_mip_gnss_constellation_id(serializer, self->gnss_id); - - insert_u8(serializer, self->satellite_id); + + microstrain_insert_u8(serializer, self->satellite_id); insert_mip_gnss_signal_id(serializer, self->signal_id); - - insert_float(serializer, self->signal_strength); + + microstrain_insert_float(serializer, self->signal_strength); insert_mip_gnss_raw_data_gnss_signal_quality(serializer, self->quality); - - insert_double(serializer, self->pseudorange); - - insert_double(serializer, self->carrier_phase); - - insert_float(serializer, self->doppler); - - insert_float(serializer, self->range_uncert); - - insert_float(serializer, self->phase_uncert); - - insert_float(serializer, self->doppler_uncert); - - insert_float(serializer, self->lock_time); + + microstrain_insert_double(serializer, self->pseudorange); + + microstrain_insert_double(serializer, self->carrier_phase); + + microstrain_insert_float(serializer, self->doppler); + + microstrain_insert_float(serializer, self->range_uncert); + + microstrain_insert_float(serializer, self->phase_uncert); + + microstrain_insert_float(serializer, self->doppler_uncert); + + microstrain_insert_float(serializer, self->lock_time); insert_mip_gnss_raw_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_raw_data(mip_serializer* serializer, mip_gnss_raw_data* self) { - extract_u8(serializer, &self->index); - - extract_u8(serializer, &self->count); - - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); - - extract_u16(serializer, &self->receiver_id); - - extract_u8(serializer, &self->tracking_channel); + microstrain_extract_u8(serializer, &self->index); + + microstrain_extract_u8(serializer, &self->count); + + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); + + microstrain_extract_u16(serializer, &self->receiver_id); + + microstrain_extract_u8(serializer, &self->tracking_channel); extract_mip_gnss_constellation_id(serializer, &self->gnss_id); - - extract_u8(serializer, &self->satellite_id); + + microstrain_extract_u8(serializer, &self->satellite_id); extract_mip_gnss_signal_id(serializer, &self->signal_id); - - extract_float(serializer, &self->signal_strength); + + microstrain_extract_float(serializer, &self->signal_strength); extract_mip_gnss_raw_data_gnss_signal_quality(serializer, &self->quality); - - extract_double(serializer, &self->pseudorange); - - extract_double(serializer, &self->carrier_phase); - - extract_float(serializer, &self->doppler); - - extract_float(serializer, &self->range_uncert); - - extract_float(serializer, &self->phase_uncert); - - extract_float(serializer, &self->doppler_uncert); - - extract_float(serializer, &self->lock_time); + + microstrain_extract_double(serializer, &self->pseudorange); + + microstrain_extract_double(serializer, &self->carrier_phase); + + microstrain_extract_float(serializer, &self->doppler); + + microstrain_extract_float(serializer, &self->range_uncert); + + microstrain_extract_float(serializer, &self->phase_uncert); + + microstrain_extract_float(serializer, &self->doppler_uncert); + + microstrain_extract_float(serializer, &self->lock_time); extract_mip_gnss_raw_data_valid_flags(serializer, &self->valid_flags); @@ -1356,169 +1356,169 @@ bool extract_mip_gnss_raw_data_from_field(const mip_field* field, void* ptr) struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_raw_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_raw_data_gnss_signal_quality(struct mip_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self) { - insert_u8(serializer, (uint8_t)(self)); + microstrain_insert_u8(serializer, (uint8_t) (self)); } void extract_mip_gnss_raw_data_gnss_signal_quality(struct mip_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self) { uint8_t tmp = 0; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = tmp; } void insert_mip_gnss_raw_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_raw_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_raw_data_valid_flags(struct mip_serializer* serializer, mip_gnss_raw_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_gps_ephemeris_data(mip_serializer* serializer, const mip_gnss_gps_ephemeris_data* self) { - insert_u8(serializer, self->index); - - insert_u8(serializer, self->count); - - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); - - insert_u8(serializer, self->satellite_id); - - insert_u8(serializer, self->health); - - insert_u8(serializer, self->iodc); - - insert_u8(serializer, self->iode); - - insert_double(serializer, self->t_oc); - - insert_double(serializer, self->af0); - - insert_double(serializer, self->af1); - - insert_double(serializer, self->af2); - - insert_double(serializer, self->t_gd); - - insert_double(serializer, self->ISC_L1CA); - - insert_double(serializer, self->ISC_L2C); - - insert_double(serializer, self->t_oe); - - insert_double(serializer, self->a); - - insert_double(serializer, self->a_dot); - - insert_double(serializer, self->mean_anomaly); - - insert_double(serializer, self->delta_mean_motion); - - insert_double(serializer, self->delta_mean_motion_dot); - - insert_double(serializer, self->eccentricity); - - insert_double(serializer, self->argument_of_perigee); - - insert_double(serializer, self->omega); - - insert_double(serializer, self->omega_dot); - - insert_double(serializer, self->inclination); - - insert_double(serializer, self->inclination_dot); - - insert_double(serializer, self->c_ic); - - insert_double(serializer, self->c_is); - - insert_double(serializer, self->c_uc); - - insert_double(serializer, self->c_us); - - insert_double(serializer, self->c_rc); - - insert_double(serializer, self->c_rs); + microstrain_insert_u8(serializer, self->index); + + microstrain_insert_u8(serializer, self->count); + + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); + + microstrain_insert_u8(serializer, self->satellite_id); + + microstrain_insert_u8(serializer, self->health); + + microstrain_insert_u8(serializer, self->iodc); + + microstrain_insert_u8(serializer, self->iode); + + microstrain_insert_double(serializer, self->t_oc); + + microstrain_insert_double(serializer, self->af0); + + microstrain_insert_double(serializer, self->af1); + + microstrain_insert_double(serializer, self->af2); + + microstrain_insert_double(serializer, self->t_gd); + + microstrain_insert_double(serializer, self->ISC_L1CA); + + microstrain_insert_double(serializer, self->ISC_L2C); + + microstrain_insert_double(serializer, self->t_oe); + + microstrain_insert_double(serializer, self->a); + + microstrain_insert_double(serializer, self->a_dot); + + microstrain_insert_double(serializer, self->mean_anomaly); + + microstrain_insert_double(serializer, self->delta_mean_motion); + + microstrain_insert_double(serializer, self->delta_mean_motion_dot); + + microstrain_insert_double(serializer, self->eccentricity); + + microstrain_insert_double(serializer, self->argument_of_perigee); + + microstrain_insert_double(serializer, self->omega); + + microstrain_insert_double(serializer, self->omega_dot); + + microstrain_insert_double(serializer, self->inclination); + + microstrain_insert_double(serializer, self->inclination_dot); + + microstrain_insert_double(serializer, self->c_ic); + + microstrain_insert_double(serializer, self->c_is); + + microstrain_insert_double(serializer, self->c_uc); + + microstrain_insert_double(serializer, self->c_us); + + microstrain_insert_double(serializer, self->c_rc); + + microstrain_insert_double(serializer, self->c_rs); insert_mip_gnss_gps_ephemeris_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_gps_ephemeris_data(mip_serializer* serializer, mip_gnss_gps_ephemeris_data* self) { - extract_u8(serializer, &self->index); - - extract_u8(serializer, &self->count); - - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); - - extract_u8(serializer, &self->satellite_id); - - extract_u8(serializer, &self->health); - - extract_u8(serializer, &self->iodc); - - extract_u8(serializer, &self->iode); - - extract_double(serializer, &self->t_oc); - - extract_double(serializer, &self->af0); - - extract_double(serializer, &self->af1); - - extract_double(serializer, &self->af2); - - extract_double(serializer, &self->t_gd); - - extract_double(serializer, &self->ISC_L1CA); - - extract_double(serializer, &self->ISC_L2C); - - extract_double(serializer, &self->t_oe); - - extract_double(serializer, &self->a); - - extract_double(serializer, &self->a_dot); - - extract_double(serializer, &self->mean_anomaly); - - extract_double(serializer, &self->delta_mean_motion); - - extract_double(serializer, &self->delta_mean_motion_dot); - - extract_double(serializer, &self->eccentricity); - - extract_double(serializer, &self->argument_of_perigee); - - extract_double(serializer, &self->omega); - - extract_double(serializer, &self->omega_dot); - - extract_double(serializer, &self->inclination); - - extract_double(serializer, &self->inclination_dot); - - extract_double(serializer, &self->c_ic); - - extract_double(serializer, &self->c_is); - - extract_double(serializer, &self->c_uc); - - extract_double(serializer, &self->c_us); - - extract_double(serializer, &self->c_rc); - - extract_double(serializer, &self->c_rs); + microstrain_extract_u8(serializer, &self->index); + + microstrain_extract_u8(serializer, &self->count); + + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); + + microstrain_extract_u8(serializer, &self->satellite_id); + + microstrain_extract_u8(serializer, &self->health); + + microstrain_extract_u8(serializer, &self->iodc); + + microstrain_extract_u8(serializer, &self->iode); + + microstrain_extract_double(serializer, &self->t_oc); + + microstrain_extract_double(serializer, &self->af0); + + microstrain_extract_double(serializer, &self->af1); + + microstrain_extract_double(serializer, &self->af2); + + microstrain_extract_double(serializer, &self->t_gd); + + microstrain_extract_double(serializer, &self->ISC_L1CA); + + microstrain_extract_double(serializer, &self->ISC_L2C); + + microstrain_extract_double(serializer, &self->t_oe); + + microstrain_extract_double(serializer, &self->a); + + microstrain_extract_double(serializer, &self->a_dot); + + microstrain_extract_double(serializer, &self->mean_anomaly); + + microstrain_extract_double(serializer, &self->delta_mean_motion); + + microstrain_extract_double(serializer, &self->delta_mean_motion_dot); + + microstrain_extract_double(serializer, &self->eccentricity); + + microstrain_extract_double(serializer, &self->argument_of_perigee); + + microstrain_extract_double(serializer, &self->omega); + + microstrain_extract_double(serializer, &self->omega_dot); + + microstrain_extract_double(serializer, &self->inclination); + + microstrain_extract_double(serializer, &self->inclination_dot); + + microstrain_extract_double(serializer, &self->c_ic); + + microstrain_extract_double(serializer, &self->c_is); + + microstrain_extract_double(serializer, &self->c_uc); + + microstrain_extract_double(serializer, &self->c_us); + + microstrain_extract_double(serializer, &self->c_rc); + + microstrain_extract_double(serializer, &self->c_rs); extract_mip_gnss_gps_ephemeris_data_valid_flags(serializer, &self->valid_flags); @@ -1530,158 +1530,158 @@ bool extract_mip_gnss_gps_ephemeris_data_from_field(const mip_field* field, void struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_ephemeris_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_gps_ephemeris_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_gps_ephemeris_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_galileo_ephemeris_data(mip_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self) { - insert_u8(serializer, self->index); - - insert_u8(serializer, self->count); - - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); - - insert_u8(serializer, self->satellite_id); - - insert_u8(serializer, self->health); - - insert_u8(serializer, self->iodc); - - insert_u8(serializer, self->iode); - - insert_double(serializer, self->t_oc); - - insert_double(serializer, self->af0); - - insert_double(serializer, self->af1); - - insert_double(serializer, self->af2); - - insert_double(serializer, self->t_gd); - - insert_double(serializer, self->ISC_L1CA); - - insert_double(serializer, self->ISC_L2C); - - insert_double(serializer, self->t_oe); - - insert_double(serializer, self->a); - - insert_double(serializer, self->a_dot); - - insert_double(serializer, self->mean_anomaly); - - insert_double(serializer, self->delta_mean_motion); - - insert_double(serializer, self->delta_mean_motion_dot); - - insert_double(serializer, self->eccentricity); - - insert_double(serializer, self->argument_of_perigee); - - insert_double(serializer, self->omega); - - insert_double(serializer, self->omega_dot); - - insert_double(serializer, self->inclination); - - insert_double(serializer, self->inclination_dot); - - insert_double(serializer, self->c_ic); - - insert_double(serializer, self->c_is); - - insert_double(serializer, self->c_uc); - - insert_double(serializer, self->c_us); - - insert_double(serializer, self->c_rc); - - insert_double(serializer, self->c_rs); + microstrain_insert_u8(serializer, self->index); + + microstrain_insert_u8(serializer, self->count); + + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); + + microstrain_insert_u8(serializer, self->satellite_id); + + microstrain_insert_u8(serializer, self->health); + + microstrain_insert_u8(serializer, self->iodc); + + microstrain_insert_u8(serializer, self->iode); + + microstrain_insert_double(serializer, self->t_oc); + + microstrain_insert_double(serializer, self->af0); + + microstrain_insert_double(serializer, self->af1); + + microstrain_insert_double(serializer, self->af2); + + microstrain_insert_double(serializer, self->t_gd); + + microstrain_insert_double(serializer, self->ISC_L1CA); + + microstrain_insert_double(serializer, self->ISC_L2C); + + microstrain_insert_double(serializer, self->t_oe); + + microstrain_insert_double(serializer, self->a); + + microstrain_insert_double(serializer, self->a_dot); + + microstrain_insert_double(serializer, self->mean_anomaly); + + microstrain_insert_double(serializer, self->delta_mean_motion); + + microstrain_insert_double(serializer, self->delta_mean_motion_dot); + + microstrain_insert_double(serializer, self->eccentricity); + + microstrain_insert_double(serializer, self->argument_of_perigee); + + microstrain_insert_double(serializer, self->omega); + + microstrain_insert_double(serializer, self->omega_dot); + + microstrain_insert_double(serializer, self->inclination); + + microstrain_insert_double(serializer, self->inclination_dot); + + microstrain_insert_double(serializer, self->c_ic); + + microstrain_insert_double(serializer, self->c_is); + + microstrain_insert_double(serializer, self->c_uc); + + microstrain_insert_double(serializer, self->c_us); + + microstrain_insert_double(serializer, self->c_rc); + + microstrain_insert_double(serializer, self->c_rs); insert_mip_gnss_galileo_ephemeris_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_galileo_ephemeris_data(mip_serializer* serializer, mip_gnss_galileo_ephemeris_data* self) { - extract_u8(serializer, &self->index); - - extract_u8(serializer, &self->count); - - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); - - extract_u8(serializer, &self->satellite_id); - - extract_u8(serializer, &self->health); - - extract_u8(serializer, &self->iodc); - - extract_u8(serializer, &self->iode); - - extract_double(serializer, &self->t_oc); - - extract_double(serializer, &self->af0); - - extract_double(serializer, &self->af1); - - extract_double(serializer, &self->af2); - - extract_double(serializer, &self->t_gd); - - extract_double(serializer, &self->ISC_L1CA); - - extract_double(serializer, &self->ISC_L2C); - - extract_double(serializer, &self->t_oe); - - extract_double(serializer, &self->a); - - extract_double(serializer, &self->a_dot); - - extract_double(serializer, &self->mean_anomaly); - - extract_double(serializer, &self->delta_mean_motion); - - extract_double(serializer, &self->delta_mean_motion_dot); - - extract_double(serializer, &self->eccentricity); - - extract_double(serializer, &self->argument_of_perigee); - - extract_double(serializer, &self->omega); - - extract_double(serializer, &self->omega_dot); - - extract_double(serializer, &self->inclination); - - extract_double(serializer, &self->inclination_dot); - - extract_double(serializer, &self->c_ic); - - extract_double(serializer, &self->c_is); - - extract_double(serializer, &self->c_uc); - - extract_double(serializer, &self->c_us); - - extract_double(serializer, &self->c_rc); - - extract_double(serializer, &self->c_rs); + microstrain_extract_u8(serializer, &self->index); + + microstrain_extract_u8(serializer, &self->count); + + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); + + microstrain_extract_u8(serializer, &self->satellite_id); + + microstrain_extract_u8(serializer, &self->health); + + microstrain_extract_u8(serializer, &self->iodc); + + microstrain_extract_u8(serializer, &self->iode); + + microstrain_extract_double(serializer, &self->t_oc); + + microstrain_extract_double(serializer, &self->af0); + + microstrain_extract_double(serializer, &self->af1); + + microstrain_extract_double(serializer, &self->af2); + + microstrain_extract_double(serializer, &self->t_gd); + + microstrain_extract_double(serializer, &self->ISC_L1CA); + + microstrain_extract_double(serializer, &self->ISC_L2C); + + microstrain_extract_double(serializer, &self->t_oe); + + microstrain_extract_double(serializer, &self->a); + + microstrain_extract_double(serializer, &self->a_dot); + + microstrain_extract_double(serializer, &self->mean_anomaly); + + microstrain_extract_double(serializer, &self->delta_mean_motion); + + microstrain_extract_double(serializer, &self->delta_mean_motion_dot); + + microstrain_extract_double(serializer, &self->eccentricity); + + microstrain_extract_double(serializer, &self->argument_of_perigee); + + microstrain_extract_double(serializer, &self->omega); + + microstrain_extract_double(serializer, &self->omega_dot); + + microstrain_extract_double(serializer, &self->inclination); + + microstrain_extract_double(serializer, &self->inclination_dot); + + microstrain_extract_double(serializer, &self->c_ic); + + microstrain_extract_double(serializer, &self->c_is); + + microstrain_extract_double(serializer, &self->c_uc); + + microstrain_extract_double(serializer, &self->c_us); + + microstrain_extract_double(serializer, &self->c_rc); + + microstrain_extract_double(serializer, &self->c_rs); extract_mip_gnss_galileo_ephemeris_data_valid_flags(serializer, &self->valid_flags); @@ -1693,128 +1693,128 @@ bool extract_mip_gnss_galileo_ephemeris_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_galileo_ephemeris_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_galileo_ephemeris_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_galileo_ephemeris_data_valid_flags(struct mip_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_glo_ephemeris_data(mip_serializer* serializer, const mip_gnss_glo_ephemeris_data* self) { - insert_u8(serializer, self->index); - - insert_u8(serializer, self->count); - - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); - - insert_u8(serializer, self->satellite_id); - - insert_s8(serializer, self->freq_number); - - insert_u32(serializer, self->tk); - - insert_u32(serializer, self->tb); - - insert_u8(serializer, self->sat_type); - - insert_double(serializer, self->gamma); - - insert_double(serializer, self->tau_n); + microstrain_insert_u8(serializer, self->index); + + microstrain_insert_u8(serializer, self->count); + + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); + + microstrain_insert_u8(serializer, self->satellite_id); + + microstrain_insert_s8(serializer, self->freq_number); + + microstrain_insert_u32(serializer, self->tk); + + microstrain_insert_u32(serializer, self->tb); + + microstrain_insert_u8(serializer, self->sat_type); + + microstrain_insert_double(serializer, self->gamma); + + microstrain_insert_double(serializer, self->tau_n); for(unsigned int i=0; i < 3; i++) - insert_double(serializer, self->x[i]); + microstrain_insert_double(serializer, self->x[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->v[i]); + microstrain_insert_float(serializer, self->v[i]); for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->a[i]); - - insert_u8(serializer, self->health); - - insert_u8(serializer, self->P); - - insert_u8(serializer, self->NT); - - insert_float(serializer, self->delta_tau_n); - - insert_u8(serializer, self->Ft); - - insert_u8(serializer, self->En); - - insert_u8(serializer, self->P1); - - insert_u8(serializer, self->P2); - - insert_u8(serializer, self->P3); - - insert_u8(serializer, self->P4); + microstrain_insert_float(serializer, self->a[i]); + + microstrain_insert_u8(serializer, self->health); + + microstrain_insert_u8(serializer, self->P); + + microstrain_insert_u8(serializer, self->NT); + + microstrain_insert_float(serializer, self->delta_tau_n); + + microstrain_insert_u8(serializer, self->Ft); + + microstrain_insert_u8(serializer, self->En); + + microstrain_insert_u8(serializer, self->P1); + + microstrain_insert_u8(serializer, self->P2); + + microstrain_insert_u8(serializer, self->P3); + + microstrain_insert_u8(serializer, self->P4); insert_mip_gnss_glo_ephemeris_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_glo_ephemeris_data(mip_serializer* serializer, mip_gnss_glo_ephemeris_data* self) { - extract_u8(serializer, &self->index); - - extract_u8(serializer, &self->count); - - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); - - extract_u8(serializer, &self->satellite_id); - - extract_s8(serializer, &self->freq_number); - - extract_u32(serializer, &self->tk); - - extract_u32(serializer, &self->tb); - - extract_u8(serializer, &self->sat_type); - - extract_double(serializer, &self->gamma); - - extract_double(serializer, &self->tau_n); + microstrain_extract_u8(serializer, &self->index); + + microstrain_extract_u8(serializer, &self->count); + + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); + + microstrain_extract_u8(serializer, &self->satellite_id); + + microstrain_extract_s8(serializer, &self->freq_number); + + microstrain_extract_u32(serializer, &self->tk); + + microstrain_extract_u32(serializer, &self->tb); + + microstrain_extract_u8(serializer, &self->sat_type); + + microstrain_extract_double(serializer, &self->gamma); + + microstrain_extract_double(serializer, &self->tau_n); for(unsigned int i=0; i < 3; i++) - extract_double(serializer, &self->x[i]); + microstrain_extract_double(serializer, &self->x[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->v[i]); + microstrain_extract_float(serializer, &self->v[i]); for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->a[i]); - - extract_u8(serializer, &self->health); - - extract_u8(serializer, &self->P); - - extract_u8(serializer, &self->NT); - - extract_float(serializer, &self->delta_tau_n); - - extract_u8(serializer, &self->Ft); - - extract_u8(serializer, &self->En); - - extract_u8(serializer, &self->P1); - - extract_u8(serializer, &self->P2); - - extract_u8(serializer, &self->P3); - - extract_u8(serializer, &self->P4); + microstrain_extract_float(serializer, &self->a[i]); + + microstrain_extract_u8(serializer, &self->health); + + microstrain_extract_u8(serializer, &self->P); + + microstrain_extract_u8(serializer, &self->NT); + + microstrain_extract_float(serializer, &self->delta_tau_n); + + microstrain_extract_u8(serializer, &self->Ft); + + microstrain_extract_u8(serializer, &self->En); + + microstrain_extract_u8(serializer, &self->P1); + + microstrain_extract_u8(serializer, &self->P2); + + microstrain_extract_u8(serializer, &self->P3); + + microstrain_extract_u8(serializer, &self->P4); extract_mip_gnss_glo_ephemeris_data_valid_flags(serializer, &self->valid_flags); @@ -1826,46 +1826,46 @@ bool extract_mip_gnss_glo_ephemeris_data_from_field(const mip_field* field, void struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_glo_ephemeris_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_glo_ephemeris_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_glo_ephemeris_data_valid_flags(struct mip_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_gps_iono_corr_data(mip_serializer* serializer, const mip_gnss_gps_iono_corr_data* self) { - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); for(unsigned int i=0; i < 4; i++) - insert_double(serializer, self->alpha[i]); + microstrain_insert_double(serializer, self->alpha[i]); for(unsigned int i=0; i < 4; i++) - insert_double(serializer, self->beta[i]); + microstrain_insert_double(serializer, self->beta[i]); insert_mip_gnss_gps_iono_corr_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_gps_iono_corr_data(mip_serializer* serializer, mip_gnss_gps_iono_corr_data* self) { - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); for(unsigned int i=0; i < 4; i++) - extract_double(serializer, &self->alpha[i]); + microstrain_extract_double(serializer, &self->alpha[i]); for(unsigned int i=0; i < 4; i++) - extract_double(serializer, &self->beta[i]); + microstrain_extract_double(serializer, &self->beta[i]); extract_mip_gnss_gps_iono_corr_data_valid_flags(serializer, &self->valid_flags); @@ -1877,44 +1877,44 @@ bool extract_mip_gnss_gps_iono_corr_data_from_field(const mip_field* field, void struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_iono_corr_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_gps_iono_corr_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_gps_iono_corr_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_gnss_galileo_iono_corr_data(mip_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self) { - insert_double(serializer, self->time_of_week); - - insert_u16(serializer, self->week_number); + microstrain_insert_double(serializer, self->time_of_week); + + microstrain_insert_u16(serializer, self->week_number); for(unsigned int i=0; i < 3; i++) - insert_double(serializer, self->alpha[i]); - - insert_u8(serializer, self->disturbance_flags); + microstrain_insert_double(serializer, self->alpha[i]); + + microstrain_insert_u8(serializer, self->disturbance_flags); insert_mip_gnss_galileo_iono_corr_data_valid_flags(serializer, self->valid_flags); } void extract_mip_gnss_galileo_iono_corr_data(mip_serializer* serializer, mip_gnss_galileo_iono_corr_data* self) { - extract_double(serializer, &self->time_of_week); - - extract_u16(serializer, &self->week_number); + microstrain_extract_double(serializer, &self->time_of_week); + + microstrain_extract_u16(serializer, &self->week_number); for(unsigned int i=0; i < 3; i++) - extract_double(serializer, &self->alpha[i]); - - extract_u8(serializer, &self->disturbance_flags); + microstrain_extract_double(serializer, &self->alpha[i]); + + microstrain_extract_u8(serializer, &self->disturbance_flags); extract_mip_gnss_galileo_iono_corr_data_valid_flags(serializer, &self->valid_flags); @@ -1926,17 +1926,17 @@ bool extract_mip_gnss_galileo_iono_corr_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_gnss_galileo_iono_corr_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_gnss_galileo_iono_corr_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_gnss_galileo_iono_corr_data_valid_flags(struct mip_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } diff --git a/src/mip/definitions/data_gnss.cpp b/src/mip/definitions/data_gnss.cpp index 2511644c5..6a82cbc77 100644 --- a/src/mip/definitions/data_gnss.cpp +++ b/src/mip/definitions/data_gnss.cpp @@ -1,7 +1,7 @@ #include "data_gnss.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/data_sensor.c b/src/mip/definitions/data_sensor.c index 03c7de2c8..d788d8fcb 100644 --- a/src/mip/definitions/data_sensor.c +++ b/src/mip/definitions/data_sensor.c @@ -1,7 +1,7 @@ #include "data_sensor.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -30,13 +30,13 @@ struct mip_field; void insert_mip_sensor_raw_accel_data(mip_serializer* serializer, const mip_sensor_raw_accel_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->raw_accel[i]); + microstrain_insert_float(serializer, self->raw_accel[i]); } void extract_mip_sensor_raw_accel_data(mip_serializer* serializer, mip_sensor_raw_accel_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->raw_accel[i]); + microstrain_extract_float(serializer, &self->raw_accel[i]); } bool extract_mip_sensor_raw_accel_data_from_field(const mip_field* field, void* ptr) @@ -46,19 +46,19 @@ bool extract_mip_sensor_raw_accel_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_accel_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_raw_gyro_data(mip_serializer* serializer, const mip_sensor_raw_gyro_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->raw_gyro[i]); + microstrain_insert_float(serializer, self->raw_gyro[i]); } void extract_mip_sensor_raw_gyro_data(mip_serializer* serializer, mip_sensor_raw_gyro_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->raw_gyro[i]); + microstrain_extract_float(serializer, &self->raw_gyro[i]); } bool extract_mip_sensor_raw_gyro_data_from_field(const mip_field* field, void* ptr) @@ -68,19 +68,19 @@ bool extract_mip_sensor_raw_gyro_data_from_field(const mip_field* field, void* p struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_gyro_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_raw_mag_data(mip_serializer* serializer, const mip_sensor_raw_mag_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->raw_mag[i]); + microstrain_insert_float(serializer, self->raw_mag[i]); } void extract_mip_sensor_raw_mag_data(mip_serializer* serializer, mip_sensor_raw_mag_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->raw_mag[i]); + microstrain_extract_float(serializer, &self->raw_mag[i]); } bool extract_mip_sensor_raw_mag_data_from_field(const mip_field* field, void* ptr) @@ -90,17 +90,17 @@ bool extract_mip_sensor_raw_mag_data_from_field(const mip_field* field, void* pt struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_mag_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_raw_pressure_data(mip_serializer* serializer, const mip_sensor_raw_pressure_data* self) { - insert_float(serializer, self->raw_pressure); + microstrain_insert_float(serializer, self->raw_pressure); } void extract_mip_sensor_raw_pressure_data(mip_serializer* serializer, mip_sensor_raw_pressure_data* self) { - extract_float(serializer, &self->raw_pressure); + microstrain_extract_float(serializer, &self->raw_pressure); } bool extract_mip_sensor_raw_pressure_data_from_field(const mip_field* field, void* ptr) @@ -110,19 +110,19 @@ bool extract_mip_sensor_raw_pressure_data_from_field(const mip_field* field, voi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_pressure_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_scaled_accel_data(mip_serializer* serializer, const mip_sensor_scaled_accel_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->scaled_accel[i]); + microstrain_insert_float(serializer, self->scaled_accel[i]); } void extract_mip_sensor_scaled_accel_data(mip_serializer* serializer, mip_sensor_scaled_accel_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->scaled_accel[i]); + microstrain_extract_float(serializer, &self->scaled_accel[i]); } bool extract_mip_sensor_scaled_accel_data_from_field(const mip_field* field, void* ptr) @@ -132,19 +132,19 @@ bool extract_mip_sensor_scaled_accel_data_from_field(const mip_field* field, voi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_accel_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_scaled_gyro_data(mip_serializer* serializer, const mip_sensor_scaled_gyro_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->scaled_gyro[i]); + microstrain_insert_float(serializer, self->scaled_gyro[i]); } void extract_mip_sensor_scaled_gyro_data(mip_serializer* serializer, mip_sensor_scaled_gyro_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->scaled_gyro[i]); + microstrain_extract_float(serializer, &self->scaled_gyro[i]); } bool extract_mip_sensor_scaled_gyro_data_from_field(const mip_field* field, void* ptr) @@ -154,19 +154,19 @@ bool extract_mip_sensor_scaled_gyro_data_from_field(const mip_field* field, void struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_gyro_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_scaled_mag_data(mip_serializer* serializer, const mip_sensor_scaled_mag_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->scaled_mag[i]); + microstrain_insert_float(serializer, self->scaled_mag[i]); } void extract_mip_sensor_scaled_mag_data(mip_serializer* serializer, mip_sensor_scaled_mag_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->scaled_mag[i]); + microstrain_extract_float(serializer, &self->scaled_mag[i]); } bool extract_mip_sensor_scaled_mag_data_from_field(const mip_field* field, void* ptr) @@ -176,17 +176,17 @@ bool extract_mip_sensor_scaled_mag_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_mag_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_scaled_pressure_data(mip_serializer* serializer, const mip_sensor_scaled_pressure_data* self) { - insert_float(serializer, self->scaled_pressure); + microstrain_insert_float(serializer, self->scaled_pressure); } void extract_mip_sensor_scaled_pressure_data(mip_serializer* serializer, mip_sensor_scaled_pressure_data* self) { - extract_float(serializer, &self->scaled_pressure); + microstrain_extract_float(serializer, &self->scaled_pressure); } bool extract_mip_sensor_scaled_pressure_data_from_field(const mip_field* field, void* ptr) @@ -196,19 +196,19 @@ bool extract_mip_sensor_scaled_pressure_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_pressure_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_delta_theta_data(mip_serializer* serializer, const mip_sensor_delta_theta_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->delta_theta[i]); + microstrain_insert_float(serializer, self->delta_theta[i]); } void extract_mip_sensor_delta_theta_data(mip_serializer* serializer, mip_sensor_delta_theta_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->delta_theta[i]); + microstrain_extract_float(serializer, &self->delta_theta[i]); } bool extract_mip_sensor_delta_theta_data_from_field(const mip_field* field, void* ptr) @@ -218,19 +218,19 @@ bool extract_mip_sensor_delta_theta_data_from_field(const mip_field* field, void struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_delta_theta_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_delta_velocity_data(mip_serializer* serializer, const mip_sensor_delta_velocity_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->delta_velocity[i]); + microstrain_insert_float(serializer, self->delta_velocity[i]); } void extract_mip_sensor_delta_velocity_data(mip_serializer* serializer, mip_sensor_delta_velocity_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->delta_velocity[i]); + microstrain_extract_float(serializer, &self->delta_velocity[i]); } bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field* field, void* ptr) @@ -240,19 +240,19 @@ bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field* field, v struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_delta_velocity_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_comp_orientation_matrix_data(mip_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->m[i]); + microstrain_insert_float(serializer, self->m[i]); } void extract_mip_sensor_comp_orientation_matrix_data(mip_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->m[i]); + microstrain_extract_float(serializer, &self->m[i]); } bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const mip_field* field, void* ptr) @@ -262,19 +262,19 @@ bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const mip_field* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_orientation_matrix_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_comp_quaternion_data(mip_serializer* serializer, const mip_sensor_comp_quaternion_data* self) { for(unsigned int i=0; i < 4; i++) - insert_float(serializer, self->q[i]); + microstrain_insert_float(serializer, self->q[i]); } void extract_mip_sensor_comp_quaternion_data(mip_serializer* serializer, mip_sensor_comp_quaternion_data* self) { for(unsigned int i=0; i < 4; i++) - extract_float(serializer, &self->q[i]); + microstrain_extract_float(serializer, &self->q[i]); } bool extract_mip_sensor_comp_quaternion_data_from_field(const mip_field* field, void* ptr) @@ -284,25 +284,25 @@ bool extract_mip_sensor_comp_quaternion_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_quaternion_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_comp_euler_angles_data(mip_serializer* serializer, const mip_sensor_comp_euler_angles_data* self) { - insert_float(serializer, self->roll); - - insert_float(serializer, self->pitch); - - insert_float(serializer, self->yaw); + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->yaw); } void extract_mip_sensor_comp_euler_angles_data(mip_serializer* serializer, mip_sensor_comp_euler_angles_data* self) { - extract_float(serializer, &self->roll); - - extract_float(serializer, &self->pitch); - - extract_float(serializer, &self->yaw); + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->yaw); } bool extract_mip_sensor_comp_euler_angles_data_from_field(const mip_field* field, void* ptr) @@ -312,19 +312,19 @@ bool extract_mip_sensor_comp_euler_angles_data_from_field(const mip_field* field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_euler_angles_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_comp_orientation_update_matrix_data(mip_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self) { for(unsigned int i=0; i < 9; i++) - insert_float(serializer, self->m[i]); + microstrain_insert_float(serializer, self->m[i]); } void extract_mip_sensor_comp_orientation_update_matrix_data(mip_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self) { for(unsigned int i=0; i < 9; i++) - extract_float(serializer, &self->m[i]); + microstrain_extract_float(serializer, &self->m[i]); } bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const mip_field* field, void* ptr) @@ -334,19 +334,19 @@ bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const mip struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_orientation_update_matrix_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_orientation_raw_temp_data(mip_serializer* serializer, const mip_sensor_orientation_raw_temp_data* self) { for(unsigned int i=0; i < 4; i++) - insert_u16(serializer, self->raw_temp[i]); + microstrain_insert_u16(serializer, self->raw_temp[i]); } void extract_mip_sensor_orientation_raw_temp_data(mip_serializer* serializer, mip_sensor_orientation_raw_temp_data* self) { for(unsigned int i=0; i < 4; i++) - extract_u16(serializer, &self->raw_temp[i]); + microstrain_extract_u16(serializer, &self->raw_temp[i]); } bool extract_mip_sensor_orientation_raw_temp_data_from_field(const mip_field* field, void* ptr) @@ -356,17 +356,17 @@ bool extract_mip_sensor_orientation_raw_temp_data_from_field(const mip_field* fi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_orientation_raw_temp_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_internal_timestamp_data(mip_serializer* serializer, const mip_sensor_internal_timestamp_data* self) { - insert_u32(serializer, self->counts); + microstrain_insert_u32(serializer, self->counts); } void extract_mip_sensor_internal_timestamp_data(mip_serializer* serializer, mip_sensor_internal_timestamp_data* self) { - extract_u32(serializer, &self->counts); + microstrain_extract_u32(serializer, &self->counts); } bool extract_mip_sensor_internal_timestamp_data_from_field(const mip_field* field, void* ptr) @@ -376,21 +376,21 @@ bool extract_mip_sensor_internal_timestamp_data_from_field(const mip_field* fiel struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_internal_timestamp_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_pps_timestamp_data(mip_serializer* serializer, const mip_sensor_pps_timestamp_data* self) { - insert_u32(serializer, self->seconds); - - insert_u32(serializer, self->useconds); + microstrain_insert_u32(serializer, self->seconds); + + microstrain_insert_u32(serializer, self->useconds); } void extract_mip_sensor_pps_timestamp_data(mip_serializer* serializer, mip_sensor_pps_timestamp_data* self) { - extract_u32(serializer, &self->seconds); - - extract_u32(serializer, &self->useconds); + microstrain_extract_u32(serializer, &self->seconds); + + microstrain_extract_u32(serializer, &self->useconds); } bool extract_mip_sensor_pps_timestamp_data_from_field(const mip_field* field, void* ptr) @@ -400,23 +400,23 @@ bool extract_mip_sensor_pps_timestamp_data_from_field(const mip_field* field, vo struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_pps_timestamp_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_gps_timestamp_data(mip_serializer* serializer, const mip_sensor_gps_timestamp_data* self) { - insert_double(serializer, self->tow); - - insert_u16(serializer, self->week_number); + microstrain_insert_double(serializer, self->tow); + + microstrain_insert_u16(serializer, self->week_number); insert_mip_sensor_gps_timestamp_data_valid_flags(serializer, self->valid_flags); } void extract_mip_sensor_gps_timestamp_data(mip_serializer* serializer, mip_sensor_gps_timestamp_data* self) { - extract_double(serializer, &self->tow); - - extract_u16(serializer, &self->week_number); + microstrain_extract_double(serializer, &self->tow); + + microstrain_extract_u16(serializer, &self->week_number); extract_mip_sensor_gps_timestamp_data_valid_flags(serializer, &self->valid_flags); @@ -428,36 +428,36 @@ bool extract_mip_sensor_gps_timestamp_data_from_field(const mip_field* field, vo struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_gps_timestamp_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_sensor_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_sensor_temperature_abs_data(mip_serializer* serializer, const mip_sensor_temperature_abs_data* self) { - insert_float(serializer, self->min_temp); - - insert_float(serializer, self->max_temp); - - insert_float(serializer, self->mean_temp); + microstrain_insert_float(serializer, self->min_temp); + + microstrain_insert_float(serializer, self->max_temp); + + microstrain_insert_float(serializer, self->mean_temp); } void extract_mip_sensor_temperature_abs_data(mip_serializer* serializer, mip_sensor_temperature_abs_data* self) { - extract_float(serializer, &self->min_temp); - - extract_float(serializer, &self->max_temp); - - extract_float(serializer, &self->mean_temp); + microstrain_extract_float(serializer, &self->min_temp); + + microstrain_extract_float(serializer, &self->max_temp); + + microstrain_extract_float(serializer, &self->mean_temp); } bool extract_mip_sensor_temperature_abs_data_from_field(const mip_field* field, void* ptr) @@ -467,19 +467,19 @@ bool extract_mip_sensor_temperature_abs_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_temperature_abs_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_up_vector_data(mip_serializer* serializer, const mip_sensor_up_vector_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->up[i]); + microstrain_insert_float(serializer, self->up[i]); } void extract_mip_sensor_up_vector_data(mip_serializer* serializer, mip_sensor_up_vector_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->up[i]); + microstrain_extract_float(serializer, &self->up[i]); } bool extract_mip_sensor_up_vector_data_from_field(const mip_field* field, void* ptr) @@ -489,19 +489,19 @@ bool extract_mip_sensor_up_vector_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_up_vector_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_north_vector_data(mip_serializer* serializer, const mip_sensor_north_vector_data* self) { for(unsigned int i=0; i < 3; i++) - insert_float(serializer, self->north[i]); + microstrain_insert_float(serializer, self->north[i]); } void extract_mip_sensor_north_vector_data(mip_serializer* serializer, mip_sensor_north_vector_data* self) { for(unsigned int i=0; i < 3; i++) - extract_float(serializer, &self->north[i]); + microstrain_extract_float(serializer, &self->north[i]); } bool extract_mip_sensor_north_vector_data_from_field(const mip_field* field, void* ptr) @@ -511,7 +511,7 @@ bool extract_mip_sensor_north_vector_data_from_field(const mip_field* field, voi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_north_vector_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_overrange_status_data(mip_serializer* serializer, const mip_sensor_overrange_status_data* self) @@ -531,36 +531,36 @@ bool extract_mip_sensor_overrange_status_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_overrange_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_sensor_overrange_status_data_status(struct mip_serializer* serializer, const mip_sensor_overrange_status_data_status self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_sensor_overrange_status_data_status(struct mip_serializer* serializer, mip_sensor_overrange_status_data_status* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_sensor_odometer_data_data(mip_serializer* serializer, const mip_sensor_odometer_data_data* self) { - insert_float(serializer, self->speed); - - insert_float(serializer, self->uncertainty); - - insert_u16(serializer, self->valid_flags); + microstrain_insert_float(serializer, self->speed); + + microstrain_insert_float(serializer, self->uncertainty); + + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_sensor_odometer_data_data(mip_serializer* serializer, mip_sensor_odometer_data_data* self) { - extract_float(serializer, &self->speed); - - extract_float(serializer, &self->uncertainty); - - extract_u16(serializer, &self->valid_flags); + microstrain_extract_float(serializer, &self->speed); + + microstrain_extract_float(serializer, &self->uncertainty); + + microstrain_extract_u16(serializer, &self->valid_flags); } bool extract_mip_sensor_odometer_data_data_from_field(const mip_field* field, void* ptr) @@ -570,7 +570,7 @@ bool extract_mip_sensor_odometer_data_data_from_field(const mip_field* field, vo struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_sensor_odometer_data_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } diff --git a/src/mip/definitions/data_sensor.cpp b/src/mip/definitions/data_sensor.cpp index 78af4a4e1..19338d673 100644 --- a/src/mip/definitions/data_sensor.cpp +++ b/src/mip/definitions/data_sensor.cpp @@ -1,7 +1,7 @@ #include "data_sensor.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/data_shared.c b/src/mip/definitions/data_shared.c index 268c34a78..03b335e94 100644 --- a/src/mip/definitions/data_shared.c +++ b/src/mip/definitions/data_shared.c @@ -1,7 +1,7 @@ #include "data_shared.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -29,12 +29,12 @@ struct mip_field; void insert_mip_shared_event_source_data(mip_serializer* serializer, const mip_shared_event_source_data* self) { - insert_u8(serializer, self->trigger_id); + microstrain_insert_u8(serializer, self->trigger_id); } void extract_mip_shared_event_source_data(mip_serializer* serializer, mip_shared_event_source_data* self) { - extract_u8(serializer, &self->trigger_id); + microstrain_extract_u8(serializer, &self->trigger_id); } bool extract_mip_shared_event_source_data_from_field(const mip_field* field, void* ptr) @@ -44,17 +44,17 @@ bool extract_mip_shared_event_source_data_from_field(const mip_field* field, voi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_shared_event_source_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_shared_ticks_data(mip_serializer* serializer, const mip_shared_ticks_data* self) { - insert_u32(serializer, self->ticks); + microstrain_insert_u32(serializer, self->ticks); } void extract_mip_shared_ticks_data(mip_serializer* serializer, mip_shared_ticks_data* self) { - extract_u32(serializer, &self->ticks); + microstrain_extract_u32(serializer, &self->ticks); } bool extract_mip_shared_ticks_data_from_field(const mip_field* field, void* ptr) @@ -64,17 +64,17 @@ bool extract_mip_shared_ticks_data_from_field(const mip_field* field, void* ptr) struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_shared_ticks_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_shared_delta_ticks_data(mip_serializer* serializer, const mip_shared_delta_ticks_data* self) { - insert_u32(serializer, self->ticks); + microstrain_insert_u32(serializer, self->ticks); } void extract_mip_shared_delta_ticks_data(mip_serializer* serializer, mip_shared_delta_ticks_data* self) { - extract_u32(serializer, &self->ticks); + microstrain_extract_u32(serializer, &self->ticks); } bool extract_mip_shared_delta_ticks_data_from_field(const mip_field* field, void* ptr) @@ -84,23 +84,23 @@ bool extract_mip_shared_delta_ticks_data_from_field(const mip_field* field, void struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_shared_delta_ticks_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_shared_gps_timestamp_data(mip_serializer* serializer, const mip_shared_gps_timestamp_data* self) { - insert_double(serializer, self->tow); - - insert_u16(serializer, self->week_number); + microstrain_insert_double(serializer, self->tow); + + microstrain_insert_u16(serializer, self->week_number); insert_mip_shared_gps_timestamp_data_valid_flags(serializer, self->valid_flags); } void extract_mip_shared_gps_timestamp_data(mip_serializer* serializer, mip_shared_gps_timestamp_data* self) { - extract_double(serializer, &self->tow); - - extract_u16(serializer, &self->week_number); + microstrain_extract_double(serializer, &self->tow); + + microstrain_extract_u16(serializer, &self->week_number); extract_mip_shared_gps_timestamp_data_valid_flags(serializer, &self->valid_flags); @@ -112,28 +112,28 @@ bool extract_mip_shared_gps_timestamp_data_from_field(const mip_field* field, vo struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_shared_gps_timestamp_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_shared_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_shared_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_shared_delta_time_data(mip_serializer* serializer, const mip_shared_delta_time_data* self) { - insert_double(serializer, self->seconds); + microstrain_insert_double(serializer, self->seconds); } void extract_mip_shared_delta_time_data(mip_serializer* serializer, mip_shared_delta_time_data* self) { - extract_double(serializer, &self->seconds); + microstrain_extract_double(serializer, &self->seconds); } bool extract_mip_shared_delta_time_data_from_field(const mip_field* field, void* ptr) @@ -143,17 +143,17 @@ bool extract_mip_shared_delta_time_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_shared_delta_time_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_shared_reference_timestamp_data(mip_serializer* serializer, const mip_shared_reference_timestamp_data* self) { - insert_u64(serializer, self->nanoseconds); + microstrain_insert_u64(serializer, self->nanoseconds); } void extract_mip_shared_reference_timestamp_data(mip_serializer* serializer, mip_shared_reference_timestamp_data* self) { - extract_u64(serializer, &self->nanoseconds); + microstrain_extract_u64(serializer, &self->nanoseconds); } bool extract_mip_shared_reference_timestamp_data_from_field(const mip_field* field, void* ptr) @@ -163,17 +163,17 @@ bool extract_mip_shared_reference_timestamp_data_from_field(const mip_field* fie struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_shared_reference_timestamp_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_shared_reference_time_delta_data(mip_serializer* serializer, const mip_shared_reference_time_delta_data* self) { - insert_u64(serializer, self->dt_nanos); + microstrain_insert_u64(serializer, self->dt_nanos); } void extract_mip_shared_reference_time_delta_data(mip_serializer* serializer, mip_shared_reference_time_delta_data* self) { - extract_u64(serializer, &self->dt_nanos); + microstrain_extract_u64(serializer, &self->dt_nanos); } bool extract_mip_shared_reference_time_delta_data_from_field(const mip_field* field, void* ptr) @@ -183,19 +183,19 @@ bool extract_mip_shared_reference_time_delta_data_from_field(const mip_field* fi struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_shared_reference_time_delta_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_shared_external_timestamp_data(mip_serializer* serializer, const mip_shared_external_timestamp_data* self) { - insert_u64(serializer, self->nanoseconds); + microstrain_insert_u64(serializer, self->nanoseconds); insert_mip_shared_external_timestamp_data_valid_flags(serializer, self->valid_flags); } void extract_mip_shared_external_timestamp_data(mip_serializer* serializer, mip_shared_external_timestamp_data* self) { - extract_u64(serializer, &self->nanoseconds); + microstrain_extract_u64(serializer, &self->nanoseconds); extract_mip_shared_external_timestamp_data_valid_flags(serializer, &self->valid_flags); @@ -207,30 +207,30 @@ bool extract_mip_shared_external_timestamp_data_from_field(const mip_field* fiel struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_shared_external_timestamp_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_shared_external_timestamp_data_valid_flags(struct mip_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_shared_external_timestamp_data_valid_flags(struct mip_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } void insert_mip_shared_external_time_delta_data(mip_serializer* serializer, const mip_shared_external_time_delta_data* self) { - insert_u64(serializer, self->dt_nanos); + microstrain_insert_u64(serializer, self->dt_nanos); insert_mip_shared_external_time_delta_data_valid_flags(serializer, self->valid_flags); } void extract_mip_shared_external_time_delta_data(mip_serializer* serializer, mip_shared_external_time_delta_data* self) { - extract_u64(serializer, &self->dt_nanos); + microstrain_extract_u64(serializer, &self->dt_nanos); extract_mip_shared_external_time_delta_data_valid_flags(serializer, &self->valid_flags); @@ -242,17 +242,17 @@ bool extract_mip_shared_external_time_delta_data_from_field(const mip_field* fie struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_shared_external_time_delta_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_shared_external_time_delta_data_valid_flags(struct mip_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self) { - insert_u16(serializer, (uint16_t)(self)); + microstrain_insert_u16(serializer, (uint16_t) (self)); } void extract_mip_shared_external_time_delta_data_valid_flags(struct mip_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self) { uint16_t tmp = 0; - extract_u16(serializer, &tmp); + microstrain_extract_u16(serializer, &tmp); *self = tmp; } diff --git a/src/mip/definitions/data_shared.cpp b/src/mip/definitions/data_shared.cpp index 248e8f0a5..2f8768339 100644 --- a/src/mip/definitions/data_shared.cpp +++ b/src/mip/definitions/data_shared.cpp @@ -1,7 +1,7 @@ #include "data_shared.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/data_system.c b/src/mip/definitions/data_system.c index d661dfb1c..b0c736bc9 100644 --- a/src/mip/definitions/data_system.c +++ b/src/mip/definitions/data_system.c @@ -1,7 +1,7 @@ #include "data_system.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include @@ -30,13 +30,13 @@ struct mip_field; void insert_mip_system_built_in_test_data(mip_serializer* serializer, const mip_system_built_in_test_data* self) { for(unsigned int i=0; i < 16; i++) - insert_u8(serializer, self->result[i]); + microstrain_insert_u8(serializer, self->result[i]); } void extract_mip_system_built_in_test_data(mip_serializer* serializer, mip_system_built_in_test_data* self) { for(unsigned int i=0; i < 16; i++) - extract_u8(serializer, &self->result[i]); + microstrain_extract_u8(serializer, &self->result[i]); } bool extract_mip_system_built_in_test_data_from_field(const mip_field* field, void* ptr) @@ -46,21 +46,21 @@ bool extract_mip_system_built_in_test_data_from_field(const mip_field* field, vo struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_system_built_in_test_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_system_time_sync_status_data(mip_serializer* serializer, const mip_system_time_sync_status_data* self) { - insert_bool(serializer, self->time_sync); - - insert_u8(serializer, self->last_pps_rcvd); + microstrain_insert_bool(serializer, self->time_sync); + + microstrain_insert_u8(serializer, self->last_pps_rcvd); } void extract_mip_system_time_sync_status_data(mip_serializer* serializer, mip_system_time_sync_status_data* self) { - extract_bool(serializer, &self->time_sync); - - extract_u8(serializer, &self->last_pps_rcvd); + microstrain_extract_bool(serializer, &self->time_sync); + + microstrain_extract_u8(serializer, &self->last_pps_rcvd); } bool extract_mip_system_time_sync_status_data_from_field(const mip_field* field, void* ptr) @@ -70,17 +70,17 @@ bool extract_mip_system_time_sync_status_data_from_field(const mip_field* field, struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_system_time_sync_status_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_system_gpio_state_data(mip_serializer* serializer, const mip_system_gpio_state_data* self) { - insert_u8(serializer, self->states); + microstrain_insert_u8(serializer, self->states); } void extract_mip_system_gpio_state_data(mip_serializer* serializer, mip_system_gpio_state_data* self) { - extract_u8(serializer, &self->states); + microstrain_extract_u8(serializer, &self->states); } bool extract_mip_system_gpio_state_data_from_field(const mip_field* field, void* ptr) @@ -90,21 +90,21 @@ bool extract_mip_system_gpio_state_data_from_field(const mip_field* field, void* struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_system_gpio_state_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } void insert_mip_system_gpio_analog_value_data(mip_serializer* serializer, const mip_system_gpio_analog_value_data* self) { - insert_u8(serializer, self->gpio_id); - - insert_float(serializer, self->value); + microstrain_insert_u8(serializer, self->gpio_id); + + microstrain_insert_float(serializer, self->value); } void extract_mip_system_gpio_analog_value_data(mip_serializer* serializer, mip_system_gpio_analog_value_data* self) { - extract_u8(serializer, &self->gpio_id); - - extract_float(serializer, &self->value); + microstrain_extract_u8(serializer, &self->gpio_id); + + microstrain_extract_float(serializer, &self->value); } bool extract_mip_system_gpio_analog_value_data_from_field(const mip_field* field, void* ptr) @@ -114,7 +114,7 @@ bool extract_mip_system_gpio_analog_value_data_from_field(const mip_field* field struct mip_serializer serializer; mip_serializer_init_from_field(&serializer, field); extract_mip_system_gpio_analog_value_data(&serializer, self); - return mip_serializer_is_complete(&serializer); + return microstrain_serializer_is_complete(&serializer); } diff --git a/src/mip/definitions/data_system.cpp b/src/mip/definitions/data_system.cpp index ee243ac31..7a6446044 100644 --- a/src/mip/definitions/data_system.cpp +++ b/src/mip/definitions/data_system.cpp @@ -1,7 +1,7 @@ #include "data_system.hpp" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_interface.h" #include diff --git a/src/mip/definitions/descriptors.c b/src/mip/definitions/descriptors.c index 685a3b500..83677f4dd 100644 --- a/src/mip/definitions/descriptors.c +++ b/src/mip/definitions/descriptors.c @@ -1,7 +1,7 @@ #include "descriptors.h" -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #ifdef __cplusplus namespace mip { @@ -153,13 +153,13 @@ bool mip_is_shared_data_field_descriptor(uint8_t field_descriptor) void insert_mip_function_selector(mip_serializer* serializer, enum mip_function_selector self) { - insert_u8(serializer, self); + microstrain_insert_u8(serializer, self); } void extract_mip_function_selector(mip_serializer* serializer, enum mip_function_selector* self) { uint8_t tmp; - extract_u8(serializer, &tmp); + microstrain_extract_u8(serializer, &tmp); *self = (enum mip_function_selector)tmp; } diff --git a/src/mip/definitions/descriptors.h b/src/mip/definitions/descriptors.h index d2a01b23d..91d643797 100644 --- a/src/mip/definitions/descriptors.h +++ b/src/mip/definitions/descriptors.h @@ -3,7 +3,7 @@ #include #include #include -#include "../utils/serialization.h" +#include "microstrain/common/serialization.h" #include "../mip_result.h" #ifdef __cplusplus diff --git a/src/mip/mip_all.h b/src/mip/mip_all.h index f07cf6852..84d5b9e5e 100644 --- a/src/mip/mip_all.h +++ b/src/mip/mip_all.h @@ -11,7 +11,7 @@ #include "definitions/descriptors.h" //MIP Utils -#include "utils/serialization.h" +#include "microstrain/common/serialization.h" //MIP Commands #include "definitions/commands_base.h" diff --git a/src/mip/mip_all.hpp b/src/mip/mip_all.hpp index da6d5476b..7284dde9f 100644 --- a/src/mip/mip_all.hpp +++ b/src/mip/mip_all.hpp @@ -11,7 +11,7 @@ #include "definitions/descriptors.h" //MIP Utils -#include "utils/serialization.h" +#include "microstrain/common/serialization.h" //MIP Commands #include "definitions/commands_base.hpp" From 9752d6d529ce1ba496ae7f4ff0d3ae7e0ed95f7a Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 14 May 2024 15:39:24 -0400 Subject: [PATCH 007/147] WIP rename serializer. --- src/microstrain/common/serialization.c | 91 +- src/microstrain/common/serialization.h | 13 +- src/mip/definitions/commands_3dm.c | 1238 +++++++++---------- src/mip/definitions/commands_3dm.cpp | 318 ++--- src/mip/definitions/commands_3dm.h | 457 ++++--- src/mip/definitions/commands_aiding.c | 178 +-- src/mip/definitions/commands_aiding.cpp | 38 +- src/mip/definitions/commands_aiding.h | 94 +- src/mip/definitions/commands_base.c | 78 +- src/mip/definitions/commands_base.cpp | 12 +- src/mip/definitions/commands_base.h | 50 +- src/mip/definitions/commands_filter.c | 1462 +++++++++++------------ src/mip/definitions/commands_filter.cpp | 436 +++---- src/mip/definitions/commands_filter.h | 422 +++---- src/mip/definitions/commands_gnss.c | 74 +- src/mip/definitions/commands_gnss.cpp | 20 +- src/mip/definitions/commands_gnss.h | 26 +- src/mip/definitions/commands_rtk.c | 118 +- src/mip/definitions/commands_rtk.cpp | 16 +- src/mip/definitions/commands_rtk.h | 78 +- src/mip/definitions/commands_system.c | 26 +- src/mip/definitions/commands_system.cpp | 6 +- src/mip/definitions/commands_system.h | 10 +- src/mip/definitions/common.c | 8 +- src/mip/definitions/common.h | 29 +- src/mip/definitions/data_filter.c | 498 ++++---- src/mip/definitions/data_filter.h | 270 ++--- src/mip/definitions/data_gnss.c | 390 +++--- src/mip/definitions/data_gnss.h | 282 ++--- src/mip/definitions/data_sensor.c | 194 +-- src/mip/definitions/data_sensor.h | 102 +- src/mip/definitions/data_shared.c | 86 +- src/mip/definitions/data_shared.h | 50 +- src/mip/definitions/data_system.c | 34 +- src/mip/definitions/data_system.h | 18 +- src/mip/definitions/descriptors.c | 4 +- src/mip/definitions/descriptors.h | 8 +- src/mip/mip.hpp | 4 +- src/mip/mip_field.c | 65 + src/mip/mip_field.h | 2 + src/mip/mip_packet.c | 2 + src/mip/mip_packet.h | 12 +- 42 files changed, 3663 insertions(+), 3656 deletions(-) diff --git a/src/microstrain/common/serialization.c b/src/microstrain/common/serialization.c index 18025a96c..9ab831812 100644 --- a/src/microstrain/common/serialization.c +++ b/src/microstrain/common/serialization.c @@ -1,14 +1,8 @@ #include "serialization.h" -#include "mip/mip_field.h" -#include "mip/mip_packet.h" -#include "mip/mip_offsets.h" - -#include -#include #ifdef __cplusplus -namespace mip { +namespace microstrain { #endif @@ -21,7 +15,7 @@ namespace mip { ///@param buffer_size /// Size of the buffer. Data will not be written beyond this size. /// -void mip_serializer_init_insertion(mip_serializer* serializer, uint8_t* buffer, size_t buffer_size) +void microstrain_serializer_init_insertion(microstrain_serializer* serializer, uint8_t* buffer, size_t buffer_size) { serializer->_buffer = buffer; serializer->_buffer_size = buffer_size; @@ -37,74 +31,13 @@ void mip_serializer_init_insertion(mip_serializer* serializer, uint8_t* buffer, ///@param buffer_size /// Maximum number of bytes to be read from the buffer. /// -void mip_serializer_init_extraction(mip_serializer* serializer, const uint8_t* buffer, size_t buffer_size) +void microstrain_serializer_init_extraction(microstrain_serializer* serializer, const uint8_t* buffer, size_t buffer_size) { serializer->_buffer = (uint8_t*)buffer; serializer->_buffer_size = buffer_size; serializer->_offset = 0; } -//////////////////////////////////////////////////////////////////////////////// -///@brief Initializer a serialization struct for creation of a new field at the -/// end of the packet. -/// -///@note Call mip_serializer_finiish_new_field after the data has been serialized. -/// -///@note Only one new field per packet can be in progress at a time. -/// -///@param serializer -///@param packet -/// Allocate the new field on the end of this packet. -///@param field_descriptor -/// Field descriptor of the new field. -/// -void mip_serializer_init_new_field(mip_serializer* serializer, mip_packet* packet, uint8_t field_descriptor) -{ - assert(packet); - - serializer->_buffer = NULL; - serializer->_buffer_size = 0; - serializer->_offset = 0; - - const int length = mip_packet_alloc_field(packet, field_descriptor, 0, &serializer->_buffer); - - if( length >= 0 ) - serializer->_buffer_size = length; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Call this after a new field allocated by mip_serializer_init_new_field -/// has been written. -/// -/// This will either finish the field, or abort it if the serializer failed. -/// -///@param serializer Must be created from mip_serializer_init_new_field. -///@param packet Must be the original packet. -/// -void mip_serializer_finish_new_field(const mip_serializer* serializer, mip_packet* packet) -{ - assert(packet); - - if(microstrain_serializer_is_ok(serializer) ) - { - assert(serializer->_offset <= MIP_FIELD_LENGTH_MAX); // Payload too long! - mip_packet_realloc_last_field(packet, serializer->_buffer, (uint8_t) serializer->_offset); - } - else if( serializer->_buffer ) - mip_packet_cancel_last_field(packet, serializer->_buffer); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Initialize a serialization struct from a MIP field payload. -/// -///@param serializer -///@param field -/// -void mip_serializer_init_from_field(mip_serializer* serializer, const mip_field* field) -{ - mip_serializer_init_extraction(serializer, mip_field_payload(field), mip_field_payload_length(field)); -} - //////////////////////////////////////////////////////////////////////////////// ///@brief Determines the total length the buffer. /// @@ -112,7 +45,7 @@ void mip_serializer_init_from_field(mip_serializer* serializer, const mip_field* /// ///@returns The buffer size. /// -size_t mip_serializer_capacity(const mip_serializer* serializer) +size_t microstrain_serializer_capacity(const microstrain_serializer* serializer) { return serializer->_buffer_size; } @@ -128,7 +61,7 @@ size_t mip_serializer_capacity(const mip_serializer* serializer) ///@note This may exceed the buffer size. Check microstrain_serializer_is_ok() before using /// the data. /// -size_t mip_serializer_length(const mip_serializer* serializer) +size_t microstrain_serializer_length(const microstrain_serializer* serializer) { return serializer->_offset; } @@ -145,7 +78,7 @@ size_t mip_serializer_length(const mip_serializer* serializer) /// or read more data than contained in the buffer. This is not a bug and /// it can be detected with the microstrain_serializer_is_ok() function. /// -int mip_serializer_remaining(const mip_serializer* serializer) +int microstrain_serializer_remaining(const microstrain_serializer* serializer) { return (int)(microstrain_serializer_capacity(serializer) - microstrain_serializer_length(serializer)); } @@ -162,7 +95,7 @@ int mip_serializer_remaining(const mip_serializer* serializer) /// ///@returns true if microstrain_serializer_remaining() >= 0. /// -bool mip_serializer_is_ok(const mip_serializer* serializer) +bool microstrain_serializer_is_ok(const microstrain_serializer* serializer) { return microstrain_serializer_length(serializer) <= microstrain_serializer_capacity(serializer); } @@ -177,7 +110,7 @@ bool mip_serializer_is_ok(const mip_serializer* serializer) /// ///@returns true if microstrain_serializer_remaining() == 0. /// -bool mip_serializer_is_complete(const mip_serializer* serializer) +bool microstrain_serializer_is_complete(const microstrain_serializer* serializer) { return serializer->_offset == serializer->_buffer_size; } @@ -190,7 +123,7 @@ static void pack(uint8_t* buffer, const void* value, size_t size) } #define INSERT_MACRO(name, type) \ -void insert_##name(mip_serializer* serializer, type value) \ +void insert_##name(microstrain_serializer* serializer, type value) \ { \ const size_t offset = serializer->_offset + sizeof(type); \ if( offset <= serializer->_buffer_size ) \ @@ -221,7 +154,7 @@ static void unpack(const uint8_t* buffer, void* value, size_t size) #define EXTRACT_MACRO(name, type) \ -void extract_##name(mip_serializer* serializer, type* value) \ +void extract_##name(microstrain_serializer* serializer, type* value) \ { \ const size_t offset = serializer->_offset + sizeof(type); \ if( offset <= serializer->_buffer_size ) \ @@ -256,7 +189,7 @@ EXTRACT_MACRO(double, double ) /// The maximum value of the counter. If the count exceeds this, it is /// set to 0 and the serializer is put into an error state. /// -void extract_count(mip_serializer* serializer, uint8_t* count_out, uint8_t max_count) +void extract_count(microstrain_serializer* serializer, uint8_t* count_out, uint8_t max_count) { *count_out = 0; // Default to zero if extraction fails. microstrain_extract_u8(serializer, count_out); @@ -274,5 +207,5 @@ void extract_count(mip_serializer* serializer, uint8_t* count_out, uint8_t max_c } #ifdef __cplusplus -} // namespace mip +} // namespace microstrain #endif diff --git a/src/microstrain/common/serialization.h b/src/microstrain/common/serialization.h index 4c9d4406b..af3ddc315 100644 --- a/src/microstrain/common/serialization.h +++ b/src/microstrain/common/serialization.h @@ -1,12 +1,12 @@ #pragma once -#include -#include - #include "mip/mip_field.h" #include "mip/mip_packet.h" #include "mip/mip_types.h" +#include +#include + //////////////////////////////////////////////////////////////////////////////// ///@defgroup mip_serialization MIP Serialization /// @@ -17,7 +17,7 @@ ///@} #ifdef __cplusplus -#include +#include namespace microstrain { namespace C { @@ -51,9 +51,6 @@ typedef struct microstrain_serializer void microstrain_serializer_init_insertion(microstrain_serializer* serializer, uint8_t* buffer, size_t buffer_size); void microstrain_serializer_init_extraction(microstrain_serializer* serializer, const uint8_t* buffer, size_t buffer_size); -void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor); -void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet* packet); -void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field* field); size_t microstrain_serializer_capacity(const microstrain_serializer* serializer); size_t microstrain_serializer_length(const microstrain_serializer* serializer); @@ -152,7 +149,7 @@ void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* coun class Serializer : public C::microstrain_serializer { public: - Serializer(C::mip_packet& packet, uint8_t newFieldDescriptor) { C::microstrain_serializer_init_new_field(this, &packet, newFieldDescriptor); } + // Serializer(C::mip_packet& packet, uint8_t newFieldDescriptor) { C::microstrain_serializer_init_new_field(this, &packet, newFieldDescriptor); } Serializer(uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_insertion(this, buffer, size); this->_offset = offset; } Serializer(const uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_extraction(this, const_cast(buffer), size); this->_offset = offset; } diff --git a/src/mip/definitions/commands_3dm.c b/src/mip/definitions/commands_3dm.c index 3fbaa81ad..7efbbe808 100644 --- a/src/mip/definitions/commands_3dm.c +++ b/src/mip/definitions/commands_3dm.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -22,7 +22,7 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_nmea_message(mip_serializer* serializer, const mip_nmea_message* self) +void insert_mip_nmea_message(microstrain_serializer* serializer, const mip_nmea_message* self) { insert_mip_nmea_message_message_id(serializer, self->message_id); @@ -33,7 +33,7 @@ void insert_mip_nmea_message(mip_serializer* serializer, const mip_nmea_message* microstrain_insert_u16(serializer, self->decimation); } -void extract_mip_nmea_message(mip_serializer* serializer, mip_nmea_message* self) +void extract_mip_nmea_message(microstrain_serializer* serializer, mip_nmea_message* self) { extract_mip_nmea_message_message_id(serializer, &self->message_id); @@ -45,33 +45,33 @@ void extract_mip_nmea_message(mip_serializer* serializer, mip_nmea_message* self } -void insert_mip_nmea_message_message_id(struct mip_serializer* serializer, const mip_nmea_message_message_id self) +void insert_mip_nmea_message_message_id(struct microstrain_serializer* serializer, const mip_nmea_message_message_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_nmea_message_message_id(struct mip_serializer* serializer, mip_nmea_message_message_id* self) +void extract_mip_nmea_message_message_id(struct microstrain_serializer* serializer, mip_nmea_message_message_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_nmea_message_talker_id(struct mip_serializer* serializer, const mip_nmea_message_talker_id self) +void insert_mip_nmea_message_talker_id(struct microstrain_serializer* serializer, const mip_nmea_message_talker_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_nmea_message_talker_id(struct mip_serializer* serializer, mip_nmea_message_talker_id* self) +void extract_mip_nmea_message_talker_id(struct microstrain_serializer* serializer, mip_nmea_message_talker_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_sensor_range_type(struct mip_serializer* serializer, const mip_sensor_range_type self) +void insert_mip_sensor_range_type(struct microstrain_serializer* serializer, const mip_sensor_range_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_sensor_range_type(struct mip_serializer* serializer, mip_sensor_range_type* self) +void extract_mip_sensor_range_type(struct microstrain_serializer* serializer, mip_sensor_range_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -83,7 +83,7 @@ void extract_mip_sensor_range_type(struct mip_serializer* serializer, mip_sensor // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_3dm_poll_imu_message_command(mip_serializer* serializer, const mip_3dm_poll_imu_message_command* self) +void insert_mip_3dm_poll_imu_message_command(microstrain_serializer* serializer, const mip_3dm_poll_imu_message_command* self) { microstrain_insert_bool(serializer, self->suppress_ack); @@ -94,7 +94,7 @@ void insert_mip_3dm_poll_imu_message_command(mip_serializer* serializer, const m insert_mip_descriptor_rate(serializer, &self->descriptors[i]); } -void extract_mip_3dm_poll_imu_message_command(mip_serializer* serializer, mip_3dm_poll_imu_message_command* self) +void extract_mip_3dm_poll_imu_message_command(microstrain_serializer* serializer, mip_3dm_poll_imu_message_command* self) { microstrain_extract_bool(serializer, &self->suppress_ack); @@ -109,9 +109,9 @@ void extract_mip_3dm_poll_imu_message_command(mip_serializer* serializer, mip_3d mip_cmd_result mip_3dm_poll_imu_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_bool(&serializer, suppress_ack); @@ -126,7 +126,7 @@ mip_cmd_result mip_3dm_poll_imu_message(struct mip_interface* device, bool suppr return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_IMU_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_poll_gnss_message_command(mip_serializer* serializer, const mip_3dm_poll_gnss_message_command* self) +void insert_mip_3dm_poll_gnss_message_command(microstrain_serializer* serializer, const mip_3dm_poll_gnss_message_command* self) { microstrain_insert_bool(serializer, self->suppress_ack); @@ -137,7 +137,7 @@ void insert_mip_3dm_poll_gnss_message_command(mip_serializer* serializer, const insert_mip_descriptor_rate(serializer, &self->descriptors[i]); } -void extract_mip_3dm_poll_gnss_message_command(mip_serializer* serializer, mip_3dm_poll_gnss_message_command* self) +void extract_mip_3dm_poll_gnss_message_command(microstrain_serializer* serializer, mip_3dm_poll_gnss_message_command* self) { microstrain_extract_bool(serializer, &self->suppress_ack); @@ -152,9 +152,9 @@ void extract_mip_3dm_poll_gnss_message_command(mip_serializer* serializer, mip_3 mip_cmd_result mip_3dm_poll_gnss_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_bool(&serializer, suppress_ack); @@ -169,7 +169,7 @@ mip_cmd_result mip_3dm_poll_gnss_message(struct mip_interface* device, bool supp return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_GNSS_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_poll_filter_message_command(mip_serializer* serializer, const mip_3dm_poll_filter_message_command* self) +void insert_mip_3dm_poll_filter_message_command(microstrain_serializer* serializer, const mip_3dm_poll_filter_message_command* self) { microstrain_insert_bool(serializer, self->suppress_ack); @@ -180,7 +180,7 @@ void insert_mip_3dm_poll_filter_message_command(mip_serializer* serializer, cons insert_mip_descriptor_rate(serializer, &self->descriptors[i]); } -void extract_mip_3dm_poll_filter_message_command(mip_serializer* serializer, mip_3dm_poll_filter_message_command* self) +void extract_mip_3dm_poll_filter_message_command(microstrain_serializer* serializer, mip_3dm_poll_filter_message_command* self) { microstrain_extract_bool(serializer, &self->suppress_ack); @@ -195,9 +195,9 @@ void extract_mip_3dm_poll_filter_message_command(mip_serializer* serializer, mip mip_cmd_result mip_3dm_poll_filter_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_bool(&serializer, suppress_ack); @@ -212,7 +212,7 @@ mip_cmd_result mip_3dm_poll_filter_message(struct mip_interface* device, bool su return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_FILTER_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_imu_message_format_command(mip_serializer* serializer, const mip_3dm_imu_message_format_command* self) +void insert_mip_3dm_imu_message_format_command(microstrain_serializer* serializer, const mip_3dm_imu_message_format_command* self) { insert_mip_function_selector(serializer, self->function); @@ -226,7 +226,7 @@ void insert_mip_3dm_imu_message_format_command(mip_serializer* serializer, const } } -void extract_mip_3dm_imu_message_format_command(mip_serializer* serializer, mip_3dm_imu_message_format_command* self) +void extract_mip_3dm_imu_message_format_command(microstrain_serializer* serializer, mip_3dm_imu_message_format_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -242,7 +242,7 @@ void extract_mip_3dm_imu_message_format_command(mip_serializer* serializer, mip_ } } -void insert_mip_3dm_imu_message_format_response(mip_serializer* serializer, const mip_3dm_imu_message_format_response* self) +void insert_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, const mip_3dm_imu_message_format_response* self) { microstrain_insert_u8(serializer, self->num_descriptors); @@ -251,7 +251,7 @@ void insert_mip_3dm_imu_message_format_response(mip_serializer* serializer, cons insert_mip_descriptor_rate(serializer, &self->descriptors[i]); } -void extract_mip_3dm_imu_message_format_response(mip_serializer* serializer, mip_3dm_imu_message_format_response* self) +void extract_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, mip_3dm_imu_message_format_response* self) { assert(self->num_descriptors); microstrain_extract_count(serializer, &self->num_descriptors, @@ -264,9 +264,9 @@ void extract_mip_3dm_imu_message_format_response(mip_serializer* serializer, mip mip_cmd_result mip_3dm_write_imu_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -283,9 +283,9 @@ mip_cmd_result mip_3dm_write_imu_message_format(struct mip_interface* device, ui } mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -297,8 +297,8 @@ mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uin if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(num_descriptors_out); microstrain_extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); @@ -314,9 +314,9 @@ mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uin } mip_cmd_result mip_3dm_save_imu_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -327,9 +327,9 @@ mip_cmd_result mip_3dm_save_imu_message_format(struct mip_interface* device) } mip_cmd_result mip_3dm_load_imu_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -340,9 +340,9 @@ mip_cmd_result mip_3dm_load_imu_message_format(struct mip_interface* device) } mip_cmd_result mip_3dm_default_imu_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -351,7 +351,7 @@ mip_cmd_result mip_3dm_default_imu_message_format(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_gps_message_format_command(mip_serializer* serializer, const mip_3dm_gps_message_format_command* self) +void insert_mip_3dm_gps_message_format_command(microstrain_serializer* serializer, const mip_3dm_gps_message_format_command* self) { insert_mip_function_selector(serializer, self->function); @@ -365,7 +365,7 @@ void insert_mip_3dm_gps_message_format_command(mip_serializer* serializer, const } } -void extract_mip_3dm_gps_message_format_command(mip_serializer* serializer, mip_3dm_gps_message_format_command* self) +void extract_mip_3dm_gps_message_format_command(microstrain_serializer* serializer, mip_3dm_gps_message_format_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -381,7 +381,7 @@ void extract_mip_3dm_gps_message_format_command(mip_serializer* serializer, mip_ } } -void insert_mip_3dm_gps_message_format_response(mip_serializer* serializer, const mip_3dm_gps_message_format_response* self) +void insert_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, const mip_3dm_gps_message_format_response* self) { microstrain_insert_u8(serializer, self->num_descriptors); @@ -390,7 +390,7 @@ void insert_mip_3dm_gps_message_format_response(mip_serializer* serializer, cons insert_mip_descriptor_rate(serializer, &self->descriptors[i]); } -void extract_mip_3dm_gps_message_format_response(mip_serializer* serializer, mip_3dm_gps_message_format_response* self) +void extract_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, mip_3dm_gps_message_format_response* self) { assert(self->num_descriptors); microstrain_extract_count(serializer, &self->num_descriptors, @@ -403,9 +403,9 @@ void extract_mip_3dm_gps_message_format_response(mip_serializer* serializer, mip mip_cmd_result mip_3dm_write_gps_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -422,9 +422,9 @@ mip_cmd_result mip_3dm_write_gps_message_format(struct mip_interface* device, ui } mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -436,8 +436,8 @@ mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uin if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(num_descriptors_out); microstrain_extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); @@ -453,9 +453,9 @@ mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uin } mip_cmd_result mip_3dm_save_gps_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -466,9 +466,9 @@ mip_cmd_result mip_3dm_save_gps_message_format(struct mip_interface* device) } mip_cmd_result mip_3dm_load_gps_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -479,9 +479,9 @@ mip_cmd_result mip_3dm_load_gps_message_format(struct mip_interface* device) } mip_cmd_result mip_3dm_default_gps_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -490,7 +490,7 @@ mip_cmd_result mip_3dm_default_gps_message_format(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_filter_message_format_command(mip_serializer* serializer, const mip_3dm_filter_message_format_command* self) +void insert_mip_3dm_filter_message_format_command(microstrain_serializer* serializer, const mip_3dm_filter_message_format_command* self) { insert_mip_function_selector(serializer, self->function); @@ -504,7 +504,7 @@ void insert_mip_3dm_filter_message_format_command(mip_serializer* serializer, co } } -void extract_mip_3dm_filter_message_format_command(mip_serializer* serializer, mip_3dm_filter_message_format_command* self) +void extract_mip_3dm_filter_message_format_command(microstrain_serializer* serializer, mip_3dm_filter_message_format_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -520,7 +520,7 @@ void extract_mip_3dm_filter_message_format_command(mip_serializer* serializer, m } } -void insert_mip_3dm_filter_message_format_response(mip_serializer* serializer, const mip_3dm_filter_message_format_response* self) +void insert_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, const mip_3dm_filter_message_format_response* self) { microstrain_insert_u8(serializer, self->num_descriptors); @@ -529,7 +529,7 @@ void insert_mip_3dm_filter_message_format_response(mip_serializer* serializer, c insert_mip_descriptor_rate(serializer, &self->descriptors[i]); } -void extract_mip_3dm_filter_message_format_response(mip_serializer* serializer, mip_3dm_filter_message_format_response* self) +void extract_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, mip_3dm_filter_message_format_response* self) { assert(self->num_descriptors); microstrain_extract_count(serializer, &self->num_descriptors, @@ -542,9 +542,9 @@ void extract_mip_3dm_filter_message_format_response(mip_serializer* serializer, mip_cmd_result mip_3dm_write_filter_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -561,9 +561,9 @@ mip_cmd_result mip_3dm_write_filter_message_format(struct mip_interface* device, } mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -575,8 +575,8 @@ mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(num_descriptors_out); microstrain_extract_count(&deserializer, num_descriptors_out, num_descriptors_out_max); @@ -592,9 +592,9 @@ mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, } mip_cmd_result mip_3dm_save_filter_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -605,9 +605,9 @@ mip_cmd_result mip_3dm_save_filter_message_format(struct mip_interface* device) } mip_cmd_result mip_3dm_load_filter_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -618,9 +618,9 @@ mip_cmd_result mip_3dm_load_filter_message_format(struct mip_interface* device) } mip_cmd_result mip_3dm_default_filter_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -638,8 +638,8 @@ mip_cmd_result mip_3dm_imu_get_base_rate(struct mip_interface* device, uint16_t* if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(rate_out); microstrain_extract_u16(&deserializer, rate_out); @@ -658,8 +658,8 @@ mip_cmd_result mip_3dm_gps_get_base_rate(struct mip_interface* device, uint16_t* if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(rate_out); microstrain_extract_u16(&deserializer, rate_out); @@ -678,8 +678,8 @@ mip_cmd_result mip_3dm_filter_get_base_rate(struct mip_interface* device, uint16 if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(rate_out); microstrain_extract_u16(&deserializer, rate_out); @@ -689,7 +689,7 @@ mip_cmd_result mip_3dm_filter_get_base_rate(struct mip_interface* device, uint16 } return result; } -void insert_mip_3dm_poll_data_command(mip_serializer* serializer, const mip_3dm_poll_data_command* self) +void insert_mip_3dm_poll_data_command(microstrain_serializer* serializer, const mip_3dm_poll_data_command* self) { microstrain_insert_u8(serializer, self->desc_set); @@ -702,7 +702,7 @@ void insert_mip_3dm_poll_data_command(mip_serializer* serializer, const mip_3dm_ microstrain_insert_u8(serializer, self->descriptors[i]); } -void extract_mip_3dm_poll_data_command(mip_serializer* serializer, mip_3dm_poll_data_command* self) +void extract_mip_3dm_poll_data_command(microstrain_serializer* serializer, mip_3dm_poll_data_command* self) { microstrain_extract_u8(serializer, &self->desc_set); @@ -719,9 +719,9 @@ void extract_mip_3dm_poll_data_command(mip_serializer* serializer, mip_3dm_poll_ mip_cmd_result mip_3dm_poll_data(struct mip_interface* device, uint8_t desc_set, bool suppress_ack, uint8_t num_descriptors, const uint8_t* descriptors) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_u8(&serializer, desc_set); @@ -738,25 +738,25 @@ mip_cmd_result mip_3dm_poll_data(struct mip_interface* device, uint8_t desc_set, return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_DATA, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_get_base_rate_command(mip_serializer* serializer, const mip_3dm_get_base_rate_command* self) +void insert_mip_3dm_get_base_rate_command(microstrain_serializer* serializer, const mip_3dm_get_base_rate_command* self) { microstrain_insert_u8(serializer, self->desc_set); } -void extract_mip_3dm_get_base_rate_command(mip_serializer* serializer, mip_3dm_get_base_rate_command* self) +void extract_mip_3dm_get_base_rate_command(microstrain_serializer* serializer, mip_3dm_get_base_rate_command* self) { microstrain_extract_u8(serializer, &self->desc_set); } -void insert_mip_3dm_get_base_rate_response(mip_serializer* serializer, const mip_3dm_get_base_rate_response* self) +void insert_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_get_base_rate_response* self) { microstrain_insert_u8(serializer, self->desc_set); microstrain_insert_u16(serializer, self->rate); } -void extract_mip_3dm_get_base_rate_response(mip_serializer* serializer, mip_3dm_get_base_rate_response* self) +void extract_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_get_base_rate_response* self) { microstrain_extract_u8(serializer, &self->desc_set); @@ -766,9 +766,9 @@ void extract_mip_3dm_get_base_rate_response(mip_serializer* serializer, mip_3dm_ mip_cmd_result mip_3dm_get_base_rate(struct mip_interface* device, uint8_t desc_set, uint16_t* rate_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_u8(&serializer, desc_set); @@ -780,8 +780,8 @@ mip_cmd_result mip_3dm_get_base_rate(struct mip_interface* device, uint8_t desc_ if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &desc_set); @@ -793,7 +793,7 @@ mip_cmd_result mip_3dm_get_base_rate(struct mip_interface* device, uint8_t desc_ } return result; } -void insert_mip_3dm_message_format_command(mip_serializer* serializer, const mip_3dm_message_format_command* self) +void insert_mip_3dm_message_format_command(microstrain_serializer* serializer, const mip_3dm_message_format_command* self) { insert_mip_function_selector(serializer, self->function); @@ -809,7 +809,7 @@ void insert_mip_3dm_message_format_command(mip_serializer* serializer, const mip } } -void extract_mip_3dm_message_format_command(mip_serializer* serializer, mip_3dm_message_format_command* self) +void extract_mip_3dm_message_format_command(microstrain_serializer* serializer, mip_3dm_message_format_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -827,7 +827,7 @@ void extract_mip_3dm_message_format_command(mip_serializer* serializer, mip_3dm_ } } -void insert_mip_3dm_message_format_response(mip_serializer* serializer, const mip_3dm_message_format_response* self) +void insert_mip_3dm_message_format_response(microstrain_serializer* serializer, const mip_3dm_message_format_response* self) { microstrain_insert_u8(serializer, self->desc_set); @@ -838,7 +838,7 @@ void insert_mip_3dm_message_format_response(mip_serializer* serializer, const mi insert_mip_descriptor_rate(serializer, &self->descriptors[i]); } -void extract_mip_3dm_message_format_response(mip_serializer* serializer, mip_3dm_message_format_response* self) +void extract_mip_3dm_message_format_response(microstrain_serializer* serializer, mip_3dm_message_format_response* self) { microstrain_extract_u8(serializer, &self->desc_set); @@ -853,9 +853,9 @@ void extract_mip_3dm_message_format_response(mip_serializer* serializer, mip_3dm mip_cmd_result mip_3dm_write_message_format(struct mip_interface* device, uint8_t desc_set, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -874,9 +874,9 @@ mip_cmd_result mip_3dm_write_message_format(struct mip_interface* device, uint8_ } mip_cmd_result mip_3dm_read_message_format(struct mip_interface* device, uint8_t desc_set, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -890,8 +890,8 @@ mip_cmd_result mip_3dm_read_message_format(struct mip_interface* device, uint8_t if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &desc_set); @@ -909,9 +909,9 @@ mip_cmd_result mip_3dm_read_message_format(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_save_message_format(struct mip_interface* device, uint8_t desc_set) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -924,9 +924,9 @@ mip_cmd_result mip_3dm_save_message_format(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_load_message_format(struct mip_interface* device, uint8_t desc_set) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -939,9 +939,9 @@ mip_cmd_result mip_3dm_load_message_format(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_default_message_format(struct mip_interface* device, uint8_t desc_set) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -952,7 +952,7 @@ mip_cmd_result mip_3dm_default_message_format(struct mip_interface* device, uint return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_nmea_poll_data_command(mip_serializer* serializer, const mip_3dm_nmea_poll_data_command* self) +void insert_mip_3dm_nmea_poll_data_command(microstrain_serializer* serializer, const mip_3dm_nmea_poll_data_command* self) { microstrain_insert_bool(serializer, self->suppress_ack); @@ -963,7 +963,7 @@ void insert_mip_3dm_nmea_poll_data_command(mip_serializer* serializer, const mip insert_mip_nmea_message(serializer, &self->format_entries[i]); } -void extract_mip_3dm_nmea_poll_data_command(mip_serializer* serializer, mip_3dm_nmea_poll_data_command* self) +void extract_mip_3dm_nmea_poll_data_command(microstrain_serializer* serializer, mip_3dm_nmea_poll_data_command* self) { microstrain_extract_bool(serializer, &self->suppress_ack); @@ -977,9 +977,9 @@ void extract_mip_3dm_nmea_poll_data_command(mip_serializer* serializer, mip_3dm_ mip_cmd_result mip_3dm_nmea_poll_data(struct mip_interface* device, bool suppress_ack, uint8_t count, const mip_nmea_message* format_entries) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_bool(&serializer, suppress_ack); @@ -994,7 +994,7 @@ mip_cmd_result mip_3dm_nmea_poll_data(struct mip_interface* device, bool suppres return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_NMEA_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_nmea_message_format_command(mip_serializer* serializer, const mip_3dm_nmea_message_format_command* self) +void insert_mip_3dm_nmea_message_format_command(microstrain_serializer* serializer, const mip_3dm_nmea_message_format_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1008,7 +1008,7 @@ void insert_mip_3dm_nmea_message_format_command(mip_serializer* serializer, cons } } -void extract_mip_3dm_nmea_message_format_command(mip_serializer* serializer, mip_3dm_nmea_message_format_command* self) +void extract_mip_3dm_nmea_message_format_command(microstrain_serializer* serializer, mip_3dm_nmea_message_format_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1024,7 +1024,7 @@ void extract_mip_3dm_nmea_message_format_command(mip_serializer* serializer, mip } } -void insert_mip_3dm_nmea_message_format_response(mip_serializer* serializer, const mip_3dm_nmea_message_format_response* self) +void insert_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, const mip_3dm_nmea_message_format_response* self) { microstrain_insert_u8(serializer, self->count); @@ -1033,7 +1033,7 @@ void insert_mip_3dm_nmea_message_format_response(mip_serializer* serializer, con insert_mip_nmea_message(serializer, &self->format_entries[i]); } -void extract_mip_3dm_nmea_message_format_response(mip_serializer* serializer, mip_3dm_nmea_message_format_response* self) +void extract_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, mip_3dm_nmea_message_format_response* self) { assert(self->count); microstrain_extract_count(serializer, &self->count, sizeof(self->format_entries) / sizeof(self->format_entries[0])); @@ -1045,9 +1045,9 @@ void extract_mip_3dm_nmea_message_format_response(mip_serializer* serializer, mi mip_cmd_result mip_3dm_write_nmea_message_format(struct mip_interface* device, uint8_t count, const mip_nmea_message* format_entries) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1064,9 +1064,9 @@ mip_cmd_result mip_3dm_write_nmea_message_format(struct mip_interface* device, u } mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, uint8_t* count_out, uint8_t count_out_max, mip_nmea_message* format_entries_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1078,8 +1078,8 @@ mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, ui if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(count_out); microstrain_extract_count(&deserializer, count_out, count_out_max); @@ -1095,9 +1095,9 @@ mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, ui } mip_cmd_result mip_3dm_save_nmea_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1108,9 +1108,9 @@ mip_cmd_result mip_3dm_save_nmea_message_format(struct mip_interface* device) } mip_cmd_result mip_3dm_load_nmea_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1121,9 +1121,9 @@ mip_cmd_result mip_3dm_load_nmea_message_format(struct mip_interface* device) } mip_cmd_result mip_3dm_default_nmea_message_format(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1132,12 +1132,12 @@ mip_cmd_result mip_3dm_default_nmea_message_format(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_device_settings_command(mip_serializer* serializer, const mip_3dm_device_settings_command* self) +void insert_mip_3dm_device_settings_command(microstrain_serializer* serializer, const mip_3dm_device_settings_command* self) { insert_mip_function_selector(serializer, self->function); } -void extract_mip_3dm_device_settings_command(mip_serializer* serializer, mip_3dm_device_settings_command* self) +void extract_mip_3dm_device_settings_command(microstrain_serializer* serializer, mip_3dm_device_settings_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1145,9 +1145,9 @@ void extract_mip_3dm_device_settings_command(mip_serializer* serializer, mip_3dm mip_cmd_result mip_3dm_save_device_settings(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1158,9 +1158,9 @@ mip_cmd_result mip_3dm_save_device_settings(struct mip_interface* device) } mip_cmd_result mip_3dm_load_device_settings(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1171,9 +1171,9 @@ mip_cmd_result mip_3dm_load_device_settings(struct mip_interface* device) } mip_cmd_result mip_3dm_default_device_settings(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1182,7 +1182,7 @@ mip_cmd_result mip_3dm_default_device_settings(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_uart_baudrate_command(mip_serializer* serializer, const mip_3dm_uart_baudrate_command* self) +void insert_mip_3dm_uart_baudrate_command(microstrain_serializer* serializer, const mip_3dm_uart_baudrate_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1192,7 +1192,7 @@ void insert_mip_3dm_uart_baudrate_command(mip_serializer* serializer, const mip_ } } -void extract_mip_3dm_uart_baudrate_command(mip_serializer* serializer, mip_3dm_uart_baudrate_command* self) +void extract_mip_3dm_uart_baudrate_command(microstrain_serializer* serializer, mip_3dm_uart_baudrate_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1203,12 +1203,12 @@ void extract_mip_3dm_uart_baudrate_command(mip_serializer* serializer, mip_3dm_u } } -void insert_mip_3dm_uart_baudrate_response(mip_serializer* serializer, const mip_3dm_uart_baudrate_response* self) +void insert_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, const mip_3dm_uart_baudrate_response* self) { microstrain_insert_u32(serializer, self->baud); } -void extract_mip_3dm_uart_baudrate_response(mip_serializer* serializer, mip_3dm_uart_baudrate_response* self) +void extract_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, mip_3dm_uart_baudrate_response* self) { microstrain_extract_u32(serializer, &self->baud); @@ -1216,9 +1216,9 @@ void extract_mip_3dm_uart_baudrate_response(mip_serializer* serializer, mip_3dm_ mip_cmd_result mip_3dm_write_uart_baudrate(struct mip_interface* device, uint32_t baud) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1231,9 +1231,9 @@ mip_cmd_result mip_3dm_write_uart_baudrate(struct mip_interface* device, uint32_ } mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t* baud_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1245,8 +1245,8 @@ mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(baud_out); microstrain_extract_u32(&deserializer, baud_out); @@ -1258,9 +1258,9 @@ mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t } mip_cmd_result mip_3dm_save_uart_baudrate(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1271,9 +1271,9 @@ mip_cmd_result mip_3dm_save_uart_baudrate(struct mip_interface* device) } mip_cmd_result mip_3dm_load_uart_baudrate(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1284,9 +1284,9 @@ mip_cmd_result mip_3dm_load_uart_baudrate(struct mip_interface* device) } mip_cmd_result mip_3dm_default_uart_baudrate(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1295,14 +1295,14 @@ mip_cmd_result mip_3dm_default_uart_baudrate(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_factory_streaming_command(mip_serializer* serializer, const mip_3dm_factory_streaming_command* self) +void insert_mip_3dm_factory_streaming_command(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command* self) { insert_mip_3dm_factory_streaming_command_action(serializer, self->action); microstrain_insert_u8(serializer, self->reserved); } -void extract_mip_3dm_factory_streaming_command(mip_serializer* serializer, mip_3dm_factory_streaming_command* self) +void extract_mip_3dm_factory_streaming_command(microstrain_serializer* serializer, mip_3dm_factory_streaming_command* self) { extract_mip_3dm_factory_streaming_command_action(serializer, &self->action); @@ -1310,11 +1310,11 @@ void extract_mip_3dm_factory_streaming_command(mip_serializer* serializer, mip_3 } -void insert_mip_3dm_factory_streaming_command_action(struct mip_serializer* serializer, const mip_3dm_factory_streaming_command_action self) +void insert_mip_3dm_factory_streaming_command_action(struct microstrain_serializer* serializer, const mip_3dm_factory_streaming_command_action self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_factory_streaming_command_action(struct mip_serializer* serializer, mip_3dm_factory_streaming_command_action* self) +void extract_mip_3dm_factory_streaming_command_action(struct microstrain_serializer* serializer, mip_3dm_factory_streaming_command_action* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1323,9 +1323,9 @@ void extract_mip_3dm_factory_streaming_command_action(struct mip_serializer* ser mip_cmd_result mip_3dm_factory_streaming(struct mip_interface* device, mip_3dm_factory_streaming_command_action action, uint8_t reserved) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_3dm_factory_streaming_command_action(&serializer, action); @@ -1336,7 +1336,7 @@ mip_cmd_result mip_3dm_factory_streaming(struct mip_interface* device, mip_3dm_f return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_datastream_control_command(mip_serializer* serializer, const mip_3dm_datastream_control_command* self) +void insert_mip_3dm_datastream_control_command(microstrain_serializer* serializer, const mip_3dm_datastream_control_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1348,7 +1348,7 @@ void insert_mip_3dm_datastream_control_command(mip_serializer* serializer, const } } -void extract_mip_3dm_datastream_control_command(mip_serializer* serializer, mip_3dm_datastream_control_command* self) +void extract_mip_3dm_datastream_control_command(microstrain_serializer* serializer, mip_3dm_datastream_control_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1361,14 +1361,14 @@ void extract_mip_3dm_datastream_control_command(mip_serializer* serializer, mip_ } } -void insert_mip_3dm_datastream_control_response(mip_serializer* serializer, const mip_3dm_datastream_control_response* self) +void insert_mip_3dm_datastream_control_response(microstrain_serializer* serializer, const mip_3dm_datastream_control_response* self) { microstrain_insert_u8(serializer, self->desc_set); microstrain_insert_bool(serializer, self->enabled); } -void extract_mip_3dm_datastream_control_response(mip_serializer* serializer, mip_3dm_datastream_control_response* self) +void extract_mip_3dm_datastream_control_response(microstrain_serializer* serializer, mip_3dm_datastream_control_response* self) { microstrain_extract_u8(serializer, &self->desc_set); @@ -1378,9 +1378,9 @@ void extract_mip_3dm_datastream_control_response(mip_serializer* serializer, mip mip_cmd_result mip_3dm_write_datastream_control(struct mip_interface* device, uint8_t desc_set, bool enable) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1395,9 +1395,9 @@ mip_cmd_result mip_3dm_write_datastream_control(struct mip_interface* device, ui } mip_cmd_result mip_3dm_read_datastream_control(struct mip_interface* device, uint8_t desc_set, bool* enabled_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1411,8 +1411,8 @@ mip_cmd_result mip_3dm_read_datastream_control(struct mip_interface* device, uin if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &desc_set); @@ -1426,9 +1426,9 @@ mip_cmd_result mip_3dm_read_datastream_control(struct mip_interface* device, uin } mip_cmd_result mip_3dm_save_datastream_control(struct mip_interface* device, uint8_t desc_set) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1441,9 +1441,9 @@ mip_cmd_result mip_3dm_save_datastream_control(struct mip_interface* device, uin } mip_cmd_result mip_3dm_load_datastream_control(struct mip_interface* device, uint8_t desc_set) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1456,9 +1456,9 @@ mip_cmd_result mip_3dm_load_datastream_control(struct mip_interface* device, uin } mip_cmd_result mip_3dm_default_datastream_control(struct mip_interface* device, uint8_t desc_set) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1469,7 +1469,7 @@ mip_cmd_result mip_3dm_default_datastream_control(struct mip_interface* device, return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_constellation_settings_command(mip_serializer* serializer, const mip_3dm_constellation_settings_command* self) +void insert_mip_3dm_constellation_settings_command(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1485,7 +1485,7 @@ void insert_mip_3dm_constellation_settings_command(mip_serializer* serializer, c } } -void extract_mip_3dm_constellation_settings_command(mip_serializer* serializer, mip_3dm_constellation_settings_command* self) +void extract_mip_3dm_constellation_settings_command(microstrain_serializer* serializer, mip_3dm_constellation_settings_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1502,7 +1502,7 @@ void extract_mip_3dm_constellation_settings_command(mip_serializer* serializer, } } -void insert_mip_3dm_constellation_settings_response(mip_serializer* serializer, const mip_3dm_constellation_settings_response* self) +void insert_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, const mip_3dm_constellation_settings_response* self) { microstrain_insert_u16(serializer, self->max_channels_available); @@ -1515,7 +1515,7 @@ void insert_mip_3dm_constellation_settings_response(mip_serializer* serializer, insert_mip_3dm_constellation_settings_command_settings(serializer, &self->settings[i]); } -void extract_mip_3dm_constellation_settings_response(mip_serializer* serializer, mip_3dm_constellation_settings_response* self) +void extract_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, mip_3dm_constellation_settings_response* self) { microstrain_extract_u16(serializer, &self->max_channels_available); @@ -1529,29 +1529,29 @@ void extract_mip_3dm_constellation_settings_response(mip_serializer* serializer, } -void insert_mip_3dm_constellation_settings_command_constellation_id(struct mip_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self) +void insert_mip_3dm_constellation_settings_command_constellation_id(struct microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_constellation_settings_command_constellation_id(struct mip_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self) +void extract_mip_3dm_constellation_settings_command_constellation_id(struct microstrain_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_constellation_settings_command_option_flags(struct mip_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self) +void insert_mip_3dm_constellation_settings_command_option_flags(struct microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_3dm_constellation_settings_command_option_flags(struct mip_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self) +void extract_mip_3dm_constellation_settings_command_option_flags(struct microstrain_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_constellation_settings_command_settings(mip_serializer* serializer, const mip_3dm_constellation_settings_command_settings* self) +void insert_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_settings* self) { insert_mip_3dm_constellation_settings_command_constellation_id(serializer, self->constellation_id); @@ -1564,7 +1564,7 @@ void insert_mip_3dm_constellation_settings_command_settings(mip_serializer* seri insert_mip_3dm_constellation_settings_command_option_flags(serializer, self->option_flags); } -void extract_mip_3dm_constellation_settings_command_settings(mip_serializer* serializer, mip_3dm_constellation_settings_command_settings* self) +void extract_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_settings* self) { extract_mip_3dm_constellation_settings_command_constellation_id(serializer, &self->constellation_id); @@ -1580,9 +1580,9 @@ void extract_mip_3dm_constellation_settings_command_settings(mip_serializer* ser mip_cmd_result mip_3dm_write_constellation_settings(struct mip_interface* device, uint16_t max_channels, uint8_t config_count, const mip_3dm_constellation_settings_command_settings* settings) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1601,9 +1601,9 @@ mip_cmd_result mip_3dm_write_constellation_settings(struct mip_interface* device } mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, uint16_t* max_channels_available_out, uint16_t* max_channels_use_out, uint8_t* config_count_out, uint8_t config_count_out_max, mip_3dm_constellation_settings_command_settings* settings_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1615,8 +1615,8 @@ mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(max_channels_available_out); microstrain_extract_u16(&deserializer, max_channels_available_out); @@ -1638,9 +1638,9 @@ mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, } mip_cmd_result mip_3dm_save_constellation_settings(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1651,9 +1651,9 @@ mip_cmd_result mip_3dm_save_constellation_settings(struct mip_interface* device) } mip_cmd_result mip_3dm_load_constellation_settings(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1664,9 +1664,9 @@ mip_cmd_result mip_3dm_load_constellation_settings(struct mip_interface* device) } mip_cmd_result mip_3dm_default_constellation_settings(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1675,7 +1675,7 @@ mip_cmd_result mip_3dm_default_constellation_settings(struct mip_interface* devi return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_gnss_sbas_settings_command(mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_command* self) +void insert_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1693,7 +1693,7 @@ void insert_mip_3dm_gnss_sbas_settings_command(mip_serializer* serializer, const } } -void extract_mip_3dm_gnss_sbas_settings_command(mip_serializer* serializer, mip_3dm_gnss_sbas_settings_command* self) +void extract_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1713,7 +1713,7 @@ void extract_mip_3dm_gnss_sbas_settings_command(mip_serializer* serializer, mip_ } } -void insert_mip_3dm_gnss_sbas_settings_response(mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_response* self) +void insert_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_response* self) { microstrain_insert_u8(serializer, self->enable_sbas); @@ -1726,7 +1726,7 @@ void insert_mip_3dm_gnss_sbas_settings_response(mip_serializer* serializer, cons microstrain_insert_u16(serializer, self->included_prns[i]); } -void extract_mip_3dm_gnss_sbas_settings_response(mip_serializer* serializer, mip_3dm_gnss_sbas_settings_response* self) +void extract_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_response* self) { microstrain_extract_u8(serializer, &self->enable_sbas); @@ -1741,11 +1741,11 @@ void extract_mip_3dm_gnss_sbas_settings_response(mip_serializer* serializer, mip } -void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self) +void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct mip_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self) +void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1754,9 +1754,9 @@ void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct mip_serialize mip_cmd_result mip_3dm_write_gnss_sbas_settings(struct mip_interface* device, uint8_t enable_sbas, mip_3dm_gnss_sbas_settings_command_sbasoptions sbas_options, uint8_t num_included_prns, const uint16_t* included_prns) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1777,9 +1777,9 @@ mip_cmd_result mip_3dm_write_gnss_sbas_settings(struct mip_interface* device, ui } mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uint8_t* enable_sbas_out, mip_3dm_gnss_sbas_settings_command_sbasoptions* sbas_options_out, uint8_t* num_included_prns_out, uint8_t num_included_prns_out_max, uint16_t* included_prns_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1791,8 +1791,8 @@ mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uin if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_sbas_out); microstrain_extract_u8(&deserializer, enable_sbas_out); @@ -1814,9 +1814,9 @@ mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uin } mip_cmd_result mip_3dm_save_gnss_sbas_settings(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1827,9 +1827,9 @@ mip_cmd_result mip_3dm_save_gnss_sbas_settings(struct mip_interface* device) } mip_cmd_result mip_3dm_load_gnss_sbas_settings(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1840,9 +1840,9 @@ mip_cmd_result mip_3dm_load_gnss_sbas_settings(struct mip_interface* device) } mip_cmd_result mip_3dm_default_gnss_sbas_settings(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1851,7 +1851,7 @@ mip_cmd_result mip_3dm_default_gnss_sbas_settings(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_command* self) +void insert_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1863,7 +1863,7 @@ void insert_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, const } } -void extract_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, mip_3dm_gnss_assisted_fix_command* self) +void extract_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1876,14 +1876,14 @@ void extract_mip_3dm_gnss_assisted_fix_command(mip_serializer* serializer, mip_3 } } -void insert_mip_3dm_gnss_assisted_fix_response(mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_response* self) +void insert_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_response* self) { insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, self->option); microstrain_insert_u8(serializer, self->flags); } -void extract_mip_3dm_gnss_assisted_fix_response(mip_serializer* serializer, mip_3dm_gnss_assisted_fix_response* self) +void extract_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_response* self) { extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, &self->option); @@ -1891,11 +1891,11 @@ void extract_mip_3dm_gnss_assisted_fix_response(mip_serializer* serializer, mip_ } -void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self) +void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct mip_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self) +void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1904,9 +1904,9 @@ void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct mip_se mip_cmd_result mip_3dm_write_gnss_assisted_fix(struct mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option option, uint8_t flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1921,9 +1921,9 @@ mip_cmd_result mip_3dm_write_gnss_assisted_fix(struct mip_interface* device, mip } mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* option_out, uint8_t* flags_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1935,8 +1935,8 @@ mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_ if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(option_out); extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(&deserializer, option_out); @@ -1951,9 +1951,9 @@ mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_ } mip_cmd_result mip_3dm_save_gnss_assisted_fix(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1964,9 +1964,9 @@ mip_cmd_result mip_3dm_save_gnss_assisted_fix(struct mip_interface* device) } mip_cmd_result mip_3dm_load_gnss_assisted_fix(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1977,9 +1977,9 @@ mip_cmd_result mip_3dm_load_gnss_assisted_fix(struct mip_interface* device) } mip_cmd_result mip_3dm_default_gnss_assisted_fix(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1988,7 +1988,7 @@ mip_cmd_result mip_3dm_default_gnss_assisted_fix(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_gnss_time_assistance_command(mip_serializer* serializer, const mip_3dm_gnss_time_assistance_command* self) +void insert_mip_3dm_gnss_time_assistance_command(microstrain_serializer* serializer, const mip_3dm_gnss_time_assistance_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2002,7 +2002,7 @@ void insert_mip_3dm_gnss_time_assistance_command(mip_serializer* serializer, con } } -void extract_mip_3dm_gnss_time_assistance_command(mip_serializer* serializer, mip_3dm_gnss_time_assistance_command* self) +void extract_mip_3dm_gnss_time_assistance_command(microstrain_serializer* serializer, mip_3dm_gnss_time_assistance_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2017,7 +2017,7 @@ void extract_mip_3dm_gnss_time_assistance_command(mip_serializer* serializer, mi } } -void insert_mip_3dm_gnss_time_assistance_response(mip_serializer* serializer, const mip_3dm_gnss_time_assistance_response* self) +void insert_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, const mip_3dm_gnss_time_assistance_response* self) { microstrain_insert_double(serializer, self->tow); @@ -2026,7 +2026,7 @@ void insert_mip_3dm_gnss_time_assistance_response(mip_serializer* serializer, co microstrain_insert_float(serializer, self->accuracy); } -void extract_mip_3dm_gnss_time_assistance_response(mip_serializer* serializer, mip_3dm_gnss_time_assistance_response* self) +void extract_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, mip_3dm_gnss_time_assistance_response* self) { microstrain_extract_double(serializer, &self->tow); @@ -2038,9 +2038,9 @@ void extract_mip_3dm_gnss_time_assistance_response(mip_serializer* serializer, m mip_cmd_result mip_3dm_write_gnss_time_assistance(struct mip_interface* device, double tow, uint16_t week_number, float accuracy) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2057,9 +2057,9 @@ mip_cmd_result mip_3dm_write_gnss_time_assistance(struct mip_interface* device, } mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, double* tow_out, uint16_t* week_number_out, float* accuracy_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2071,8 +2071,8 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(tow_out); microstrain_extract_double(&deserializer, tow_out); @@ -2088,7 +2088,7 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d } return result; } -void insert_mip_3dm_imu_lowpass_filter_command(mip_serializer* serializer, const mip_3dm_imu_lowpass_filter_command* self) +void insert_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serializer, const mip_3dm_imu_lowpass_filter_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2106,7 +2106,7 @@ void insert_mip_3dm_imu_lowpass_filter_command(mip_serializer* serializer, const } } -void extract_mip_3dm_imu_lowpass_filter_command(mip_serializer* serializer, mip_3dm_imu_lowpass_filter_command* self) +void extract_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serializer, mip_3dm_imu_lowpass_filter_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2125,7 +2125,7 @@ void extract_mip_3dm_imu_lowpass_filter_command(mip_serializer* serializer, mip_ } } -void insert_mip_3dm_imu_lowpass_filter_response(mip_serializer* serializer, const mip_3dm_imu_lowpass_filter_response* self) +void insert_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_imu_lowpass_filter_response* self) { microstrain_insert_u8(serializer, self->target_descriptor); @@ -2138,7 +2138,7 @@ void insert_mip_3dm_imu_lowpass_filter_response(mip_serializer* serializer, cons microstrain_insert_u8(serializer, self->reserved); } -void extract_mip_3dm_imu_lowpass_filter_response(mip_serializer* serializer, mip_3dm_imu_lowpass_filter_response* self) +void extract_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_imu_lowpass_filter_response* self) { microstrain_extract_u8(serializer, &self->target_descriptor); @@ -2154,9 +2154,9 @@ void extract_mip_3dm_imu_lowpass_filter_response(mip_serializer* serializer, mip mip_cmd_result mip_3dm_write_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2177,9 +2177,9 @@ mip_cmd_result mip_3dm_write_imu_lowpass_filter(struct mip_interface* device, ui } mip_cmd_result mip_3dm_read_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor, bool* enable_out, bool* manual_out, uint16_t* frequency_out, uint8_t* reserved_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2193,8 +2193,8 @@ mip_cmd_result mip_3dm_read_imu_lowpass_filter(struct mip_interface* device, uin if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &target_descriptor); @@ -2217,9 +2217,9 @@ mip_cmd_result mip_3dm_read_imu_lowpass_filter(struct mip_interface* device, uin } mip_cmd_result mip_3dm_save_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2232,9 +2232,9 @@ mip_cmd_result mip_3dm_save_imu_lowpass_filter(struct mip_interface* device, uin } mip_cmd_result mip_3dm_load_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2247,9 +2247,9 @@ mip_cmd_result mip_3dm_load_imu_lowpass_filter(struct mip_interface* device, uin } mip_cmd_result mip_3dm_default_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2260,7 +2260,7 @@ mip_cmd_result mip_3dm_default_imu_lowpass_filter(struct mip_interface* device, return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_pps_source_command(mip_serializer* serializer, const mip_3dm_pps_source_command* self) +void insert_mip_3dm_pps_source_command(microstrain_serializer* serializer, const mip_3dm_pps_source_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2270,7 +2270,7 @@ void insert_mip_3dm_pps_source_command(mip_serializer* serializer, const mip_3dm } } -void extract_mip_3dm_pps_source_command(mip_serializer* serializer, mip_3dm_pps_source_command* self) +void extract_mip_3dm_pps_source_command(microstrain_serializer* serializer, mip_3dm_pps_source_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2281,22 +2281,22 @@ void extract_mip_3dm_pps_source_command(mip_serializer* serializer, mip_3dm_pps_ } } -void insert_mip_3dm_pps_source_response(mip_serializer* serializer, const mip_3dm_pps_source_response* self) +void insert_mip_3dm_pps_source_response(microstrain_serializer* serializer, const mip_3dm_pps_source_response* self) { insert_mip_3dm_pps_source_command_source(serializer, self->source); } -void extract_mip_3dm_pps_source_response(mip_serializer* serializer, mip_3dm_pps_source_response* self) +void extract_mip_3dm_pps_source_response(microstrain_serializer* serializer, mip_3dm_pps_source_response* self) { extract_mip_3dm_pps_source_command_source(serializer, &self->source); } -void insert_mip_3dm_pps_source_command_source(struct mip_serializer* serializer, const mip_3dm_pps_source_command_source self) +void insert_mip_3dm_pps_source_command_source(struct microstrain_serializer* serializer, const mip_3dm_pps_source_command_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_pps_source_command_source(struct mip_serializer* serializer, mip_3dm_pps_source_command_source* self) +void extract_mip_3dm_pps_source_command_source(struct microstrain_serializer* serializer, mip_3dm_pps_source_command_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2305,9 +2305,9 @@ void extract_mip_3dm_pps_source_command_source(struct mip_serializer* serializer mip_cmd_result mip_3dm_write_pps_source(struct mip_interface* device, mip_3dm_pps_source_command_source source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2320,9 +2320,9 @@ mip_cmd_result mip_3dm_write_pps_source(struct mip_interface* device, mip_3dm_pp } mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps_source_command_source* source_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2334,8 +2334,8 @@ mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(source_out); extract_mip_3dm_pps_source_command_source(&deserializer, source_out); @@ -2347,9 +2347,9 @@ mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps } mip_cmd_result mip_3dm_save_pps_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2360,9 +2360,9 @@ mip_cmd_result mip_3dm_save_pps_source(struct mip_interface* device) } mip_cmd_result mip_3dm_load_pps_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2373,9 +2373,9 @@ mip_cmd_result mip_3dm_load_pps_source(struct mip_interface* device) } mip_cmd_result mip_3dm_default_pps_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2384,7 +2384,7 @@ mip_cmd_result mip_3dm_default_pps_source(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_gpio_config_command(mip_serializer* serializer, const mip_3dm_gpio_config_command* self) +void insert_mip_3dm_gpio_config_command(microstrain_serializer* serializer, const mip_3dm_gpio_config_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2400,7 +2400,7 @@ void insert_mip_3dm_gpio_config_command(mip_serializer* serializer, const mip_3d } } -void extract_mip_3dm_gpio_config_command(mip_serializer* serializer, mip_3dm_gpio_config_command* self) +void extract_mip_3dm_gpio_config_command(microstrain_serializer* serializer, mip_3dm_gpio_config_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2417,7 +2417,7 @@ void extract_mip_3dm_gpio_config_command(mip_serializer* serializer, mip_3dm_gpi } } -void insert_mip_3dm_gpio_config_response(mip_serializer* serializer, const mip_3dm_gpio_config_response* self) +void insert_mip_3dm_gpio_config_response(microstrain_serializer* serializer, const mip_3dm_gpio_config_response* self) { microstrain_insert_u8(serializer, self->pin); @@ -2428,7 +2428,7 @@ void insert_mip_3dm_gpio_config_response(mip_serializer* serializer, const mip_3 insert_mip_3dm_gpio_config_command_pin_mode(serializer, self->pin_mode); } -void extract_mip_3dm_gpio_config_response(mip_serializer* serializer, mip_3dm_gpio_config_response* self) +void extract_mip_3dm_gpio_config_response(microstrain_serializer* serializer, mip_3dm_gpio_config_response* self) { microstrain_extract_u8(serializer, &self->pin); @@ -2440,33 +2440,33 @@ void extract_mip_3dm_gpio_config_response(mip_serializer* serializer, mip_3dm_gp } -void insert_mip_3dm_gpio_config_command_feature(struct mip_serializer* serializer, const mip_3dm_gpio_config_command_feature self) +void insert_mip_3dm_gpio_config_command_feature(struct microstrain_serializer* serializer, const mip_3dm_gpio_config_command_feature self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_gpio_config_command_feature(struct mip_serializer* serializer, mip_3dm_gpio_config_command_feature* self) +void extract_mip_3dm_gpio_config_command_feature(struct microstrain_serializer* serializer, mip_3dm_gpio_config_command_feature* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_gpio_config_command_behavior(struct mip_serializer* serializer, const mip_3dm_gpio_config_command_behavior self) +void insert_mip_3dm_gpio_config_command_behavior(struct microstrain_serializer* serializer, const mip_3dm_gpio_config_command_behavior self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_gpio_config_command_behavior(struct mip_serializer* serializer, mip_3dm_gpio_config_command_behavior* self) +void extract_mip_3dm_gpio_config_command_behavior(struct microstrain_serializer* serializer, mip_3dm_gpio_config_command_behavior* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_gpio_config_command_pin_mode(struct mip_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self) +void insert_mip_3dm_gpio_config_command_pin_mode(struct microstrain_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_gpio_config_command_pin_mode(struct mip_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self) +void extract_mip_3dm_gpio_config_command_pin_mode(struct microstrain_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2475,9 +2475,9 @@ void extract_mip_3dm_gpio_config_command_pin_mode(struct mip_serializer* seriali mip_cmd_result mip_3dm_write_gpio_config(struct mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature feature, mip_3dm_gpio_config_command_behavior behavior, mip_3dm_gpio_config_command_pin_mode pin_mode) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2496,9 +2496,9 @@ mip_cmd_result mip_3dm_write_gpio_config(struct mip_interface* device, uint8_t p } mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature* feature_out, mip_3dm_gpio_config_command_behavior* behavior_out, mip_3dm_gpio_config_command_pin_mode* pin_mode_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2512,8 +2512,8 @@ mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pi if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &pin); @@ -2533,9 +2533,9 @@ mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pi } mip_cmd_result mip_3dm_save_gpio_config(struct mip_interface* device, uint8_t pin) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2548,9 +2548,9 @@ mip_cmd_result mip_3dm_save_gpio_config(struct mip_interface* device, uint8_t pi } mip_cmd_result mip_3dm_load_gpio_config(struct mip_interface* device, uint8_t pin) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2563,9 +2563,9 @@ mip_cmd_result mip_3dm_load_gpio_config(struct mip_interface* device, uint8_t pi } mip_cmd_result mip_3dm_default_gpio_config(struct mip_interface* device, uint8_t pin) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2576,7 +2576,7 @@ mip_cmd_result mip_3dm_default_gpio_config(struct mip_interface* device, uint8_t return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_gpio_state_command(mip_serializer* serializer, const mip_3dm_gpio_state_command* self) +void insert_mip_3dm_gpio_state_command(microstrain_serializer* serializer, const mip_3dm_gpio_state_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2591,7 +2591,7 @@ void insert_mip_3dm_gpio_state_command(mip_serializer* serializer, const mip_3dm } } -void extract_mip_3dm_gpio_state_command(mip_serializer* serializer, mip_3dm_gpio_state_command* self) +void extract_mip_3dm_gpio_state_command(microstrain_serializer* serializer, mip_3dm_gpio_state_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2607,14 +2607,14 @@ void extract_mip_3dm_gpio_state_command(mip_serializer* serializer, mip_3dm_gpio } } -void insert_mip_3dm_gpio_state_response(mip_serializer* serializer, const mip_3dm_gpio_state_response* self) +void insert_mip_3dm_gpio_state_response(microstrain_serializer* serializer, const mip_3dm_gpio_state_response* self) { microstrain_insert_u8(serializer, self->pin); microstrain_insert_bool(serializer, self->state); } -void extract_mip_3dm_gpio_state_response(mip_serializer* serializer, mip_3dm_gpio_state_response* self) +void extract_mip_3dm_gpio_state_response(microstrain_serializer* serializer, mip_3dm_gpio_state_response* self) { microstrain_extract_u8(serializer, &self->pin); @@ -2624,9 +2624,9 @@ void extract_mip_3dm_gpio_state_response(mip_serializer* serializer, mip_3dm_gpi mip_cmd_result mip_3dm_write_gpio_state(struct mip_interface* device, uint8_t pin, bool state) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2641,9 +2641,9 @@ mip_cmd_result mip_3dm_write_gpio_state(struct mip_interface* device, uint8_t pi } mip_cmd_result mip_3dm_read_gpio_state(struct mip_interface* device, uint8_t pin, bool* state_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2657,8 +2657,8 @@ mip_cmd_result mip_3dm_read_gpio_state(struct mip_interface* device, uint8_t pin if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &pin); @@ -2670,7 +2670,7 @@ mip_cmd_result mip_3dm_read_gpio_state(struct mip_interface* device, uint8_t pin } return result; } -void insert_mip_3dm_odometer_command(mip_serializer* serializer, const mip_3dm_odometer_command* self) +void insert_mip_3dm_odometer_command(microstrain_serializer* serializer, const mip_3dm_odometer_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2684,7 +2684,7 @@ void insert_mip_3dm_odometer_command(mip_serializer* serializer, const mip_3dm_o } } -void extract_mip_3dm_odometer_command(mip_serializer* serializer, mip_3dm_odometer_command* self) +void extract_mip_3dm_odometer_command(microstrain_serializer* serializer, mip_3dm_odometer_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2699,7 +2699,7 @@ void extract_mip_3dm_odometer_command(mip_serializer* serializer, mip_3dm_odomet } } -void insert_mip_3dm_odometer_response(mip_serializer* serializer, const mip_3dm_odometer_response* self) +void insert_mip_3dm_odometer_response(microstrain_serializer* serializer, const mip_3dm_odometer_response* self) { insert_mip_3dm_odometer_command_mode(serializer, self->mode); @@ -2708,7 +2708,7 @@ void insert_mip_3dm_odometer_response(mip_serializer* serializer, const mip_3dm_ microstrain_insert_float(serializer, self->uncertainty); } -void extract_mip_3dm_odometer_response(mip_serializer* serializer, mip_3dm_odometer_response* self) +void extract_mip_3dm_odometer_response(microstrain_serializer* serializer, mip_3dm_odometer_response* self) { extract_mip_3dm_odometer_command_mode(serializer, &self->mode); @@ -2718,11 +2718,11 @@ void extract_mip_3dm_odometer_response(mip_serializer* serializer, mip_3dm_odome } -void insert_mip_3dm_odometer_command_mode(struct mip_serializer* serializer, const mip_3dm_odometer_command_mode self) +void insert_mip_3dm_odometer_command_mode(struct microstrain_serializer* serializer, const mip_3dm_odometer_command_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_odometer_command_mode(struct mip_serializer* serializer, mip_3dm_odometer_command_mode* self) +void extract_mip_3dm_odometer_command_mode(struct microstrain_serializer* serializer, mip_3dm_odometer_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2731,9 +2731,9 @@ void extract_mip_3dm_odometer_command_mode(struct mip_serializer* serializer, mi mip_cmd_result mip_3dm_write_odometer(struct mip_interface* device, mip_3dm_odometer_command_mode mode, float scaling, float uncertainty) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2750,9 +2750,9 @@ mip_cmd_result mip_3dm_write_odometer(struct mip_interface* device, mip_3dm_odom } mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odometer_command_mode* mode_out, float* scaling_out, float* uncertainty_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2764,8 +2764,8 @@ mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odome if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(mode_out); extract_mip_3dm_odometer_command_mode(&deserializer, mode_out); @@ -2783,9 +2783,9 @@ mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odome } mip_cmd_result mip_3dm_save_odometer(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2796,9 +2796,9 @@ mip_cmd_result mip_3dm_save_odometer(struct mip_interface* device) } mip_cmd_result mip_3dm_load_odometer(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2809,9 +2809,9 @@ mip_cmd_result mip_3dm_load_odometer(struct mip_interface* device) } mip_cmd_result mip_3dm_default_odometer(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2820,18 +2820,18 @@ mip_cmd_result mip_3dm_default_odometer(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_get_event_support_command(mip_serializer* serializer, const mip_3dm_get_event_support_command* self) +void insert_mip_3dm_get_event_support_command(microstrain_serializer* serializer, const mip_3dm_get_event_support_command* self) { insert_mip_3dm_get_event_support_command_query(serializer, self->query); } -void extract_mip_3dm_get_event_support_command(mip_serializer* serializer, mip_3dm_get_event_support_command* self) +void extract_mip_3dm_get_event_support_command(microstrain_serializer* serializer, mip_3dm_get_event_support_command* self) { extract_mip_3dm_get_event_support_command_query(serializer, &self->query); } -void insert_mip_3dm_get_event_support_response(mip_serializer* serializer, const mip_3dm_get_event_support_response* self) +void insert_mip_3dm_get_event_support_response(microstrain_serializer* serializer, const mip_3dm_get_event_support_response* self) { insert_mip_3dm_get_event_support_command_query(serializer, self->query); @@ -2844,7 +2844,7 @@ void insert_mip_3dm_get_event_support_response(mip_serializer* serializer, const insert_mip_3dm_get_event_support_command_info(serializer, &self->entries[i]); } -void extract_mip_3dm_get_event_support_response(mip_serializer* serializer, mip_3dm_get_event_support_response* self) +void extract_mip_3dm_get_event_support_response(microstrain_serializer* serializer, mip_3dm_get_event_support_response* self) { extract_mip_3dm_get_event_support_command_query(serializer, &self->query); @@ -2858,25 +2858,25 @@ void extract_mip_3dm_get_event_support_response(mip_serializer* serializer, mip_ } -void insert_mip_3dm_get_event_support_command_query(struct mip_serializer* serializer, const mip_3dm_get_event_support_command_query self) +void insert_mip_3dm_get_event_support_command_query(struct microstrain_serializer* serializer, const mip_3dm_get_event_support_command_query self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_get_event_support_command_query(struct mip_serializer* serializer, mip_3dm_get_event_support_command_query* self) +void extract_mip_3dm_get_event_support_command_query(struct microstrain_serializer* serializer, mip_3dm_get_event_support_command_query* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_get_event_support_command_info(mip_serializer* serializer, const mip_3dm_get_event_support_command_info* self) +void insert_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_info* self) { microstrain_insert_u8(serializer, self->type); microstrain_insert_u8(serializer, self->count); } -void extract_mip_3dm_get_event_support_command_info(mip_serializer* serializer, mip_3dm_get_event_support_command_info* self) +void extract_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, mip_3dm_get_event_support_command_info* self) { microstrain_extract_u8(serializer, &self->type); @@ -2886,9 +2886,9 @@ void extract_mip_3dm_get_event_support_command_info(mip_serializer* serializer, mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_get_event_support_command_query query, uint8_t* max_instances_out, uint8_t* num_entries_out, uint8_t num_entries_out_max, mip_3dm_get_event_support_command_info* entries_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_3dm_get_event_support_command_query(&serializer, query); @@ -2900,8 +2900,8 @@ mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_g if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); extract_mip_3dm_get_event_support_command_query(&deserializer, &query); @@ -2920,7 +2920,7 @@ mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_g } return result; } -void insert_mip_3dm_event_control_command(mip_serializer* serializer, const mip_3dm_event_control_command* self) +void insert_mip_3dm_event_control_command(microstrain_serializer* serializer, const mip_3dm_event_control_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2932,7 +2932,7 @@ void insert_mip_3dm_event_control_command(mip_serializer* serializer, const mip_ } } -void extract_mip_3dm_event_control_command(mip_serializer* serializer, mip_3dm_event_control_command* self) +void extract_mip_3dm_event_control_command(microstrain_serializer* serializer, mip_3dm_event_control_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2945,14 +2945,14 @@ void extract_mip_3dm_event_control_command(mip_serializer* serializer, mip_3dm_e } } -void insert_mip_3dm_event_control_response(mip_serializer* serializer, const mip_3dm_event_control_response* self) +void insert_mip_3dm_event_control_response(microstrain_serializer* serializer, const mip_3dm_event_control_response* self) { microstrain_insert_u8(serializer, self->instance); insert_mip_3dm_event_control_command_mode(serializer, self->mode); } -void extract_mip_3dm_event_control_response(mip_serializer* serializer, mip_3dm_event_control_response* self) +void extract_mip_3dm_event_control_response(microstrain_serializer* serializer, mip_3dm_event_control_response* self) { microstrain_extract_u8(serializer, &self->instance); @@ -2960,11 +2960,11 @@ void extract_mip_3dm_event_control_response(mip_serializer* serializer, mip_3dm_ } -void insert_mip_3dm_event_control_command_mode(struct mip_serializer* serializer, const mip_3dm_event_control_command_mode self) +void insert_mip_3dm_event_control_command_mode(struct microstrain_serializer* serializer, const mip_3dm_event_control_command_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_control_command_mode(struct mip_serializer* serializer, mip_3dm_event_control_command_mode* self) +void extract_mip_3dm_event_control_command_mode(struct microstrain_serializer* serializer, mip_3dm_event_control_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2973,9 +2973,9 @@ void extract_mip_3dm_event_control_command_mode(struct mip_serializer* serialize mip_cmd_result mip_3dm_write_event_control(struct mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode mode) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2990,9 +2990,9 @@ mip_cmd_result mip_3dm_write_event_control(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_read_event_control(struct mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode* mode_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3006,8 +3006,8 @@ mip_cmd_result mip_3dm_read_event_control(struct mip_interface* device, uint8_t if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &instance); @@ -3021,9 +3021,9 @@ mip_cmd_result mip_3dm_read_event_control(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_save_event_control(struct mip_interface* device, uint8_t instance) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3036,9 +3036,9 @@ mip_cmd_result mip_3dm_save_event_control(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_load_event_control(struct mip_interface* device, uint8_t instance) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3051,9 +3051,9 @@ mip_cmd_result mip_3dm_load_event_control(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_default_event_control(struct mip_interface* device, uint8_t instance) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3064,7 +3064,7 @@ mip_cmd_result mip_3dm_default_event_control(struct mip_interface* device, uint8 return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_get_event_trigger_status_command(mip_serializer* serializer, const mip_3dm_get_event_trigger_status_command* self) +void insert_mip_3dm_get_event_trigger_status_command(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command* self) { microstrain_insert_u8(serializer, self->requested_count); @@ -3073,7 +3073,7 @@ void insert_mip_3dm_get_event_trigger_status_command(mip_serializer* serializer, microstrain_insert_u8(serializer, self->requested_instances[i]); } -void extract_mip_3dm_get_event_trigger_status_command(mip_serializer* serializer, mip_3dm_get_event_trigger_status_command* self) +void extract_mip_3dm_get_event_trigger_status_command(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command* self) { assert(self->requested_count); microstrain_extract_count(serializer, &self->requested_count, @@ -3084,7 +3084,7 @@ void extract_mip_3dm_get_event_trigger_status_command(mip_serializer* serializer } -void insert_mip_3dm_get_event_trigger_status_response(mip_serializer* serializer, const mip_3dm_get_event_trigger_status_response* self) +void insert_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_response* self) { microstrain_insert_u8(serializer, self->count); @@ -3093,7 +3093,7 @@ void insert_mip_3dm_get_event_trigger_status_response(mip_serializer* serializer insert_mip_3dm_get_event_trigger_status_command_entry(serializer, &self->triggers[i]); } -void extract_mip_3dm_get_event_trigger_status_response(mip_serializer* serializer, mip_3dm_get_event_trigger_status_response* self) +void extract_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_response* self) { assert(self->count); microstrain_extract_count(serializer, &self->count, sizeof(self->triggers) / sizeof(self->triggers[0])); @@ -3103,25 +3103,25 @@ void extract_mip_3dm_get_event_trigger_status_response(mip_serializer* serialize } -void insert_mip_3dm_get_event_trigger_status_command_status(struct mip_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self) +void insert_mip_3dm_get_event_trigger_status_command_status(struct microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_get_event_trigger_status_command_status(struct mip_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self) +void extract_mip_3dm_get_event_trigger_status_command_status(struct microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_get_event_trigger_status_command_entry(mip_serializer* serializer, const mip_3dm_get_event_trigger_status_command_entry* self) +void insert_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_entry* self) { microstrain_insert_u8(serializer, self->type); insert_mip_3dm_get_event_trigger_status_command_status(serializer, self->status); } -void extract_mip_3dm_get_event_trigger_status_command_entry(mip_serializer* serializer, mip_3dm_get_event_trigger_status_command_entry* self) +void extract_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_entry* self) { microstrain_extract_u8(serializer, &self->type); @@ -3131,9 +3131,9 @@ void extract_mip_3dm_get_event_trigger_status_command_entry(mip_serializer* seri mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_trigger_status_command_entry* triggers_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_u8(&serializer, requested_count); @@ -3149,8 +3149,8 @@ mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, ui if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(count_out); microstrain_extract_count(&deserializer, count_out, count_out_max); @@ -3164,7 +3164,7 @@ mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, ui } return result; } -void insert_mip_3dm_get_event_action_status_command(mip_serializer* serializer, const mip_3dm_get_event_action_status_command* self) +void insert_mip_3dm_get_event_action_status_command(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command* self) { microstrain_insert_u8(serializer, self->requested_count); @@ -3173,7 +3173,7 @@ void insert_mip_3dm_get_event_action_status_command(mip_serializer* serializer, microstrain_insert_u8(serializer, self->requested_instances[i]); } -void extract_mip_3dm_get_event_action_status_command(mip_serializer* serializer, mip_3dm_get_event_action_status_command* self) +void extract_mip_3dm_get_event_action_status_command(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command* self) { assert(self->requested_count); microstrain_extract_count(serializer, &self->requested_count, @@ -3184,7 +3184,7 @@ void extract_mip_3dm_get_event_action_status_command(mip_serializer* serializer, } -void insert_mip_3dm_get_event_action_status_response(mip_serializer* serializer, const mip_3dm_get_event_action_status_response* self) +void insert_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_response* self) { microstrain_insert_u8(serializer, self->count); @@ -3193,7 +3193,7 @@ void insert_mip_3dm_get_event_action_status_response(mip_serializer* serializer, insert_mip_3dm_get_event_action_status_command_entry(serializer, &self->actions[i]); } -void extract_mip_3dm_get_event_action_status_response(mip_serializer* serializer, mip_3dm_get_event_action_status_response* self) +void extract_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, mip_3dm_get_event_action_status_response* self) { assert(self->count); microstrain_extract_count(serializer, &self->count, sizeof(self->actions) / sizeof(self->actions[0])); @@ -3203,14 +3203,14 @@ void extract_mip_3dm_get_event_action_status_response(mip_serializer* serializer } -void insert_mip_3dm_get_event_action_status_command_entry(mip_serializer* serializer, const mip_3dm_get_event_action_status_command_entry* self) +void insert_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command_entry* self) { microstrain_insert_u8(serializer, self->action_type); microstrain_insert_u8(serializer, self->trigger_id); } -void extract_mip_3dm_get_event_action_status_command_entry(mip_serializer* serializer, mip_3dm_get_event_action_status_command_entry* self) +void extract_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command_entry* self) { microstrain_extract_u8(serializer, &self->action_type); @@ -3220,9 +3220,9 @@ void extract_mip_3dm_get_event_action_status_command_entry(mip_serializer* seria mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_action_status_command_entry* actions_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_u8(&serializer, requested_count); @@ -3238,8 +3238,8 @@ mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uin if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(count_out); microstrain_extract_count(&deserializer, count_out, count_out_max); @@ -3253,7 +3253,7 @@ mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uin } return result; } -void insert_mip_3dm_event_trigger_command(mip_serializer* serializer, const mip_3dm_event_trigger_command* self) +void insert_mip_3dm_event_trigger_command(microstrain_serializer* serializer, const mip_3dm_event_trigger_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3280,7 +3280,7 @@ void insert_mip_3dm_event_trigger_command(mip_serializer* serializer, const mip_ } } } -void extract_mip_3dm_event_trigger_command(mip_serializer* serializer, mip_3dm_event_trigger_command* self) +void extract_mip_3dm_event_trigger_command(microstrain_serializer* serializer, mip_3dm_event_trigger_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3308,7 +3308,7 @@ void extract_mip_3dm_event_trigger_command(mip_serializer* serializer, mip_3dm_e } } -void insert_mip_3dm_event_trigger_response(mip_serializer* serializer, const mip_3dm_event_trigger_response* self) +void insert_mip_3dm_event_trigger_response(microstrain_serializer* serializer, const mip_3dm_event_trigger_response* self) { microstrain_insert_u8(serializer, self->instance); @@ -3330,7 +3330,7 @@ void insert_mip_3dm_event_trigger_response(mip_serializer* serializer, const mip } } -void extract_mip_3dm_event_trigger_response(mip_serializer* serializer, mip_3dm_event_trigger_response* self) +void extract_mip_3dm_event_trigger_response(microstrain_serializer* serializer, mip_3dm_event_trigger_response* self) { microstrain_extract_u8(serializer, &self->instance); @@ -3353,14 +3353,14 @@ void extract_mip_3dm_event_trigger_response(mip_serializer* serializer, mip_3dm_ } } -void insert_mip_3dm_event_trigger_command_gpio_params(mip_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params* self) +void insert_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params* self) { microstrain_insert_u8(serializer, self->pin); insert_mip_3dm_event_trigger_command_gpio_params_mode(serializer, self->mode); } -void extract_mip_3dm_event_trigger_command_gpio_params(mip_serializer* serializer, mip_3dm_event_trigger_command_gpio_params* self) +void extract_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params* self) { microstrain_extract_u8(serializer, &self->pin); @@ -3368,18 +3368,18 @@ void extract_mip_3dm_event_trigger_command_gpio_params(mip_serializer* serialize } -void insert_mip_3dm_event_trigger_command_gpio_params_mode(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self) +void insert_mip_3dm_event_trigger_command_gpio_params_mode(struct microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_trigger_command_gpio_params_mode(struct mip_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self) +void extract_mip_3dm_event_trigger_command_gpio_params_mode(struct microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_event_trigger_command_threshold_params(mip_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params* self) +void insert_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params* self) { microstrain_insert_u8(serializer, self->desc_set); @@ -3410,7 +3410,7 @@ void insert_mip_3dm_event_trigger_command_threshold_params(mip_serializer* seria } } -void extract_mip_3dm_event_trigger_command_threshold_params(mip_serializer* serializer, mip_3dm_event_trigger_command_threshold_params* self) +void extract_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params* self) { microstrain_extract_u8(serializer, &self->desc_set); @@ -3442,18 +3442,18 @@ void extract_mip_3dm_event_trigger_command_threshold_params(mip_serializer* seri } } -void insert_mip_3dm_event_trigger_command_threshold_params_type(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self) +void insert_mip_3dm_event_trigger_command_threshold_params_type(struct microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_trigger_command_threshold_params_type(struct mip_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self) +void extract_mip_3dm_event_trigger_command_threshold_params_type(struct microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_event_trigger_command_combination_params(mip_serializer* serializer, const mip_3dm_event_trigger_command_combination_params* self) +void insert_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_combination_params* self) { microstrain_insert_u16(serializer, self->logic_table); @@ -3461,7 +3461,7 @@ void insert_mip_3dm_event_trigger_command_combination_params(mip_serializer* ser microstrain_insert_u8(serializer, self->input_triggers[i]); } -void extract_mip_3dm_event_trigger_command_combination_params(mip_serializer* serializer, mip_3dm_event_trigger_command_combination_params* self) +void extract_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_combination_params* self) { microstrain_extract_u16(serializer, &self->logic_table); @@ -3470,11 +3470,11 @@ void extract_mip_3dm_event_trigger_command_combination_params(mip_serializer* se } -void insert_mip_3dm_event_trigger_command_type(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_type self) +void insert_mip_3dm_event_trigger_command_type(struct microstrain_serializer* serializer, const mip_3dm_event_trigger_command_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_trigger_command_type(struct mip_serializer* serializer, mip_3dm_event_trigger_command_type* self) +void extract_mip_3dm_event_trigger_command_type(struct microstrain_serializer* serializer, mip_3dm_event_trigger_command_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -3483,9 +3483,9 @@ void extract_mip_3dm_event_trigger_command_type(struct mip_serializer* serialize mip_cmd_result mip_3dm_write_event_trigger(struct mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type type, const mip_3dm_event_trigger_command_parameters* parameters) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3515,9 +3515,9 @@ mip_cmd_result mip_3dm_write_event_trigger(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type* type_out, mip_3dm_event_trigger_command_parameters* parameters_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3531,8 +3531,8 @@ mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &instance); @@ -3561,9 +3561,9 @@ mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_save_event_trigger(struct mip_interface* device, uint8_t instance) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3576,9 +3576,9 @@ mip_cmd_result mip_3dm_save_event_trigger(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_load_event_trigger(struct mip_interface* device, uint8_t instance) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3591,9 +3591,9 @@ mip_cmd_result mip_3dm_load_event_trigger(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_default_event_trigger(struct mip_interface* device, uint8_t instance) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3604,7 +3604,7 @@ mip_cmd_result mip_3dm_default_event_trigger(struct mip_interface* device, uint8 return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_event_action_command(mip_serializer* serializer, const mip_3dm_event_action_command* self) +void insert_mip_3dm_event_action_command(microstrain_serializer* serializer, const mip_3dm_event_action_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3628,7 +3628,7 @@ void insert_mip_3dm_event_action_command(mip_serializer* serializer, const mip_3 } } } -void extract_mip_3dm_event_action_command(mip_serializer* serializer, mip_3dm_event_action_command* self) +void extract_mip_3dm_event_action_command(microstrain_serializer* serializer, mip_3dm_event_action_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3653,7 +3653,7 @@ void extract_mip_3dm_event_action_command(mip_serializer* serializer, mip_3dm_ev } } -void insert_mip_3dm_event_action_response(mip_serializer* serializer, const mip_3dm_event_action_response* self) +void insert_mip_3dm_event_action_response(microstrain_serializer* serializer, const mip_3dm_event_action_response* self) { microstrain_insert_u8(serializer, self->instance); @@ -3672,7 +3672,7 @@ void insert_mip_3dm_event_action_response(mip_serializer* serializer, const mip_ } } -void extract_mip_3dm_event_action_response(mip_serializer* serializer, mip_3dm_event_action_response* self) +void extract_mip_3dm_event_action_response(microstrain_serializer* serializer, mip_3dm_event_action_response* self) { microstrain_extract_u8(serializer, &self->instance); @@ -3692,14 +3692,14 @@ void extract_mip_3dm_event_action_response(mip_serializer* serializer, mip_3dm_e } } -void insert_mip_3dm_event_action_command_gpio_params(mip_serializer* serializer, const mip_3dm_event_action_command_gpio_params* self) +void insert_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params* self) { microstrain_insert_u8(serializer, self->pin); insert_mip_3dm_event_action_command_gpio_params_mode(serializer, self->mode); } -void extract_mip_3dm_event_action_command_gpio_params(mip_serializer* serializer, mip_3dm_event_action_command_gpio_params* self) +void extract_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params* self) { microstrain_extract_u8(serializer, &self->pin); @@ -3707,18 +3707,18 @@ void extract_mip_3dm_event_action_command_gpio_params(mip_serializer* serializer } -void insert_mip_3dm_event_action_command_gpio_params_mode(struct mip_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self) +void insert_mip_3dm_event_action_command_gpio_params_mode(struct microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_action_command_gpio_params_mode(struct mip_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self) +void extract_mip_3dm_event_action_command_gpio_params_mode(struct microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_event_action_command_message_params(mip_serializer* serializer, const mip_3dm_event_action_command_message_params* self) +void insert_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_message_params* self) { microstrain_insert_u8(serializer, self->desc_set); @@ -3731,7 +3731,7 @@ void insert_mip_3dm_event_action_command_message_params(mip_serializer* serializ microstrain_insert_u8(serializer, self->descriptors[i]); } -void extract_mip_3dm_event_action_command_message_params(mip_serializer* serializer, mip_3dm_event_action_command_message_params* self) +void extract_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, mip_3dm_event_action_command_message_params* self) { microstrain_extract_u8(serializer, &self->desc_set); @@ -3745,11 +3745,11 @@ void extract_mip_3dm_event_action_command_message_params(mip_serializer* seriali } -void insert_mip_3dm_event_action_command_type(struct mip_serializer* serializer, const mip_3dm_event_action_command_type self) +void insert_mip_3dm_event_action_command_type(struct microstrain_serializer* serializer, const mip_3dm_event_action_command_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_action_command_type(struct mip_serializer* serializer, mip_3dm_event_action_command_type* self) +void extract_mip_3dm_event_action_command_type(struct microstrain_serializer* serializer, mip_3dm_event_action_command_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -3758,9 +3758,9 @@ void extract_mip_3dm_event_action_command_type(struct mip_serializer* serializer mip_cmd_result mip_3dm_write_event_action(struct mip_interface* device, uint8_t instance, uint8_t trigger, mip_3dm_event_action_command_type type, const mip_3dm_event_action_command_parameters* parameters) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3787,9 +3787,9 @@ mip_cmd_result mip_3dm_write_event_action(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t instance, uint8_t* trigger_out, mip_3dm_event_action_command_type* type_out, mip_3dm_event_action_command_parameters* parameters_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3803,8 +3803,8 @@ mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t i if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &instance); @@ -3831,9 +3831,9 @@ mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t i } mip_cmd_result mip_3dm_save_event_action(struct mip_interface* device, uint8_t instance) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3846,9 +3846,9 @@ mip_cmd_result mip_3dm_save_event_action(struct mip_interface* device, uint8_t i } mip_cmd_result mip_3dm_load_event_action(struct mip_interface* device, uint8_t instance) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3861,9 +3861,9 @@ mip_cmd_result mip_3dm_load_event_action(struct mip_interface* device, uint8_t i } mip_cmd_result mip_3dm_default_event_action(struct mip_interface* device, uint8_t instance) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3874,7 +3874,7 @@ mip_cmd_result mip_3dm_default_event_action(struct mip_interface* device, uint8_ return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_accel_bias_command(mip_serializer* serializer, const mip_3dm_accel_bias_command* self) +void insert_mip_3dm_accel_bias_command(microstrain_serializer* serializer, const mip_3dm_accel_bias_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3885,7 +3885,7 @@ void insert_mip_3dm_accel_bias_command(mip_serializer* serializer, const mip_3dm } } -void extract_mip_3dm_accel_bias_command(mip_serializer* serializer, mip_3dm_accel_bias_command* self) +void extract_mip_3dm_accel_bias_command(microstrain_serializer* serializer, mip_3dm_accel_bias_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3897,13 +3897,13 @@ void extract_mip_3dm_accel_bias_command(mip_serializer* serializer, mip_3dm_acce } } -void insert_mip_3dm_accel_bias_response(mip_serializer* serializer, const mip_3dm_accel_bias_response* self) +void insert_mip_3dm_accel_bias_response(microstrain_serializer* serializer, const mip_3dm_accel_bias_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->bias[i]); } -void extract_mip_3dm_accel_bias_response(mip_serializer* serializer, mip_3dm_accel_bias_response* self) +void extract_mip_3dm_accel_bias_response(microstrain_serializer* serializer, mip_3dm_accel_bias_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->bias[i]); @@ -3912,9 +3912,9 @@ void extract_mip_3dm_accel_bias_response(mip_serializer* serializer, mip_3dm_acc mip_cmd_result mip_3dm_write_accel_bias(struct mip_interface* device, const float* bias) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3929,9 +3929,9 @@ mip_cmd_result mip_3dm_write_accel_bias(struct mip_interface* device, const floa } mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3943,8 +3943,8 @@ mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(bias_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3957,9 +3957,9 @@ mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias } mip_cmd_result mip_3dm_save_accel_bias(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3970,9 +3970,9 @@ mip_cmd_result mip_3dm_save_accel_bias(struct mip_interface* device) } mip_cmd_result mip_3dm_load_accel_bias(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3983,9 +3983,9 @@ mip_cmd_result mip_3dm_load_accel_bias(struct mip_interface* device) } mip_cmd_result mip_3dm_default_accel_bias(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3994,7 +3994,7 @@ mip_cmd_result mip_3dm_default_accel_bias(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_gyro_bias_command(mip_serializer* serializer, const mip_3dm_gyro_bias_command* self) +void insert_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, const mip_3dm_gyro_bias_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4005,7 +4005,7 @@ void insert_mip_3dm_gyro_bias_command(mip_serializer* serializer, const mip_3dm_ } } -void extract_mip_3dm_gyro_bias_command(mip_serializer* serializer, mip_3dm_gyro_bias_command* self) +void extract_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, mip_3dm_gyro_bias_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4017,13 +4017,13 @@ void extract_mip_3dm_gyro_bias_command(mip_serializer* serializer, mip_3dm_gyro_ } } -void insert_mip_3dm_gyro_bias_response(mip_serializer* serializer, const mip_3dm_gyro_bias_response* self) +void insert_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_gyro_bias_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->bias[i]); } -void extract_mip_3dm_gyro_bias_response(mip_serializer* serializer, mip_3dm_gyro_bias_response* self) +void extract_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_gyro_bias_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->bias[i]); @@ -4032,9 +4032,9 @@ void extract_mip_3dm_gyro_bias_response(mip_serializer* serializer, mip_3dm_gyro mip_cmd_result mip_3dm_write_gyro_bias(struct mip_interface* device, const float* bias) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4049,9 +4049,9 @@ mip_cmd_result mip_3dm_write_gyro_bias(struct mip_interface* device, const float } mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4063,8 +4063,8 @@ mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_ if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(bias_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -4077,9 +4077,9 @@ mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_ } mip_cmd_result mip_3dm_save_gyro_bias(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4090,9 +4090,9 @@ mip_cmd_result mip_3dm_save_gyro_bias(struct mip_interface* device) } mip_cmd_result mip_3dm_load_gyro_bias(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4103,9 +4103,9 @@ mip_cmd_result mip_3dm_load_gyro_bias(struct mip_interface* device) } mip_cmd_result mip_3dm_default_gyro_bias(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4114,24 +4114,24 @@ mip_cmd_result mip_3dm_default_gyro_bias(struct mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_capture_gyro_bias_command(mip_serializer* serializer, const mip_3dm_capture_gyro_bias_command* self) +void insert_mip_3dm_capture_gyro_bias_command(microstrain_serializer* serializer, const mip_3dm_capture_gyro_bias_command* self) { microstrain_insert_u16(serializer, self->averaging_time_ms); } -void extract_mip_3dm_capture_gyro_bias_command(mip_serializer* serializer, mip_3dm_capture_gyro_bias_command* self) +void extract_mip_3dm_capture_gyro_bias_command(microstrain_serializer* serializer, mip_3dm_capture_gyro_bias_command* self) { microstrain_extract_u16(serializer, &self->averaging_time_ms); } -void insert_mip_3dm_capture_gyro_bias_response(mip_serializer* serializer, const mip_3dm_capture_gyro_bias_response* self) +void insert_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_capture_gyro_bias_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->bias[i]); } -void extract_mip_3dm_capture_gyro_bias_response(mip_serializer* serializer, mip_3dm_capture_gyro_bias_response* self) +void extract_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_capture_gyro_bias_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->bias[i]); @@ -4140,9 +4140,9 @@ void extract_mip_3dm_capture_gyro_bias_response(mip_serializer* serializer, mip_ mip_cmd_result mip_3dm_capture_gyro_bias(struct mip_interface* device, uint16_t averaging_time_ms, float* bias_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_u16(&serializer, averaging_time_ms); @@ -4154,8 +4154,8 @@ mip_cmd_result mip_3dm_capture_gyro_bias(struct mip_interface* device, uint16_t if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(bias_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -4166,7 +4166,7 @@ mip_cmd_result mip_3dm_capture_gyro_bias(struct mip_interface* device, uint16_t } return result; } -void insert_mip_3dm_mag_hard_iron_offset_command(mip_serializer* serializer, const mip_3dm_mag_hard_iron_offset_command* self) +void insert_mip_3dm_mag_hard_iron_offset_command(microstrain_serializer* serializer, const mip_3dm_mag_hard_iron_offset_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4177,7 +4177,7 @@ void insert_mip_3dm_mag_hard_iron_offset_command(mip_serializer* serializer, con } } -void extract_mip_3dm_mag_hard_iron_offset_command(mip_serializer* serializer, mip_3dm_mag_hard_iron_offset_command* self) +void extract_mip_3dm_mag_hard_iron_offset_command(microstrain_serializer* serializer, mip_3dm_mag_hard_iron_offset_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4189,13 +4189,13 @@ void extract_mip_3dm_mag_hard_iron_offset_command(mip_serializer* serializer, mi } } -void insert_mip_3dm_mag_hard_iron_offset_response(mip_serializer* serializer, const mip_3dm_mag_hard_iron_offset_response* self) +void insert_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, const mip_3dm_mag_hard_iron_offset_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->offset[i]); } -void extract_mip_3dm_mag_hard_iron_offset_response(mip_serializer* serializer, mip_3dm_mag_hard_iron_offset_response* self) +void extract_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, mip_3dm_mag_hard_iron_offset_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->offset[i]); @@ -4204,9 +4204,9 @@ void extract_mip_3dm_mag_hard_iron_offset_response(mip_serializer* serializer, m mip_cmd_result mip_3dm_write_mag_hard_iron_offset(struct mip_interface* device, const float* offset) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4221,9 +4221,9 @@ mip_cmd_result mip_3dm_write_mag_hard_iron_offset(struct mip_interface* device, } mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, float* offset_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4235,8 +4235,8 @@ mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, f if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(offset_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -4249,9 +4249,9 @@ mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, f } mip_cmd_result mip_3dm_save_mag_hard_iron_offset(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4262,9 +4262,9 @@ mip_cmd_result mip_3dm_save_mag_hard_iron_offset(struct mip_interface* device) } mip_cmd_result mip_3dm_load_mag_hard_iron_offset(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4275,9 +4275,9 @@ mip_cmd_result mip_3dm_load_mag_hard_iron_offset(struct mip_interface* device) } mip_cmd_result mip_3dm_default_mag_hard_iron_offset(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4286,7 +4286,7 @@ mip_cmd_result mip_3dm_default_mag_hard_iron_offset(struct mip_interface* device return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_mag_soft_iron_matrix_command(mip_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_command* self) +void insert_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4297,7 +4297,7 @@ void insert_mip_3dm_mag_soft_iron_matrix_command(mip_serializer* serializer, con } } -void extract_mip_3dm_mag_soft_iron_matrix_command(mip_serializer* serializer, mip_3dm_mag_soft_iron_matrix_command* self) +void extract_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* serializer, mip_3dm_mag_soft_iron_matrix_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4309,13 +4309,13 @@ void extract_mip_3dm_mag_soft_iron_matrix_command(mip_serializer* serializer, mi } } -void insert_mip_3dm_mag_soft_iron_matrix_response(mip_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_response* self) +void insert_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_response* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->offset[i]); } -void extract_mip_3dm_mag_soft_iron_matrix_response(mip_serializer* serializer, mip_3dm_mag_soft_iron_matrix_response* self) +void extract_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, mip_3dm_mag_soft_iron_matrix_response* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->offset[i]); @@ -4324,9 +4324,9 @@ void extract_mip_3dm_mag_soft_iron_matrix_response(mip_serializer* serializer, m mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(struct mip_interface* device, const float* offset) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4341,9 +4341,9 @@ mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(struct mip_interface* device, } mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, float* offset_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4355,8 +4355,8 @@ mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, f if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(offset_out || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -4369,9 +4369,9 @@ mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, f } mip_cmd_result mip_3dm_save_mag_soft_iron_matrix(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4382,9 +4382,9 @@ mip_cmd_result mip_3dm_save_mag_soft_iron_matrix(struct mip_interface* device) } mip_cmd_result mip_3dm_load_mag_soft_iron_matrix(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4395,9 +4395,9 @@ mip_cmd_result mip_3dm_load_mag_soft_iron_matrix(struct mip_interface* device) } mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4406,7 +4406,7 @@ mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(struct mip_interface* device return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_coning_sculling_enable_command(mip_serializer* serializer, const mip_3dm_coning_sculling_enable_command* self) +void insert_mip_3dm_coning_sculling_enable_command(microstrain_serializer* serializer, const mip_3dm_coning_sculling_enable_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4416,7 +4416,7 @@ void insert_mip_3dm_coning_sculling_enable_command(mip_serializer* serializer, c } } -void extract_mip_3dm_coning_sculling_enable_command(mip_serializer* serializer, mip_3dm_coning_sculling_enable_command* self) +void extract_mip_3dm_coning_sculling_enable_command(microstrain_serializer* serializer, mip_3dm_coning_sculling_enable_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4427,12 +4427,12 @@ void extract_mip_3dm_coning_sculling_enable_command(mip_serializer* serializer, } } -void insert_mip_3dm_coning_sculling_enable_response(mip_serializer* serializer, const mip_3dm_coning_sculling_enable_response* self) +void insert_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, const mip_3dm_coning_sculling_enable_response* self) { microstrain_insert_bool(serializer, self->enable); } -void extract_mip_3dm_coning_sculling_enable_response(mip_serializer* serializer, mip_3dm_coning_sculling_enable_response* self) +void extract_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, mip_3dm_coning_sculling_enable_response* self) { microstrain_extract_bool(serializer, &self->enable); @@ -4440,9 +4440,9 @@ void extract_mip_3dm_coning_sculling_enable_response(mip_serializer* serializer, mip_cmd_result mip_3dm_write_coning_sculling_enable(struct mip_interface* device, bool enable) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4455,9 +4455,9 @@ mip_cmd_result mip_3dm_write_coning_sculling_enable(struct mip_interface* device } mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, bool* enable_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4469,8 +4469,8 @@ mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_bool(&deserializer, enable_out); @@ -4482,9 +4482,9 @@ mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, } mip_cmd_result mip_3dm_save_coning_sculling_enable(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4495,9 +4495,9 @@ mip_cmd_result mip_3dm_save_coning_sculling_enable(struct mip_interface* device) } mip_cmd_result mip_3dm_load_coning_sculling_enable(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4508,9 +4508,9 @@ mip_cmd_result mip_3dm_load_coning_sculling_enable(struct mip_interface* device) } mip_cmd_result mip_3dm_default_coning_sculling_enable(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4519,7 +4519,7 @@ mip_cmd_result mip_3dm_default_coning_sculling_enable(struct mip_interface* devi return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_command* self) +void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4533,7 +4533,7 @@ void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(mip_serializer* ser } } -void extract_mip_3dm_sensor_2_vehicle_transform_euler_command(mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_command* self) +void extract_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4548,7 +4548,7 @@ void extract_mip_3dm_sensor_2_vehicle_transform_euler_command(mip_serializer* se } } -void insert_mip_3dm_sensor_2_vehicle_transform_euler_response(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_response* self) +void insert_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_response* self) { microstrain_insert_float(serializer, self->roll); @@ -4557,7 +4557,7 @@ void insert_mip_3dm_sensor_2_vehicle_transform_euler_response(mip_serializer* se microstrain_insert_float(serializer, self->yaw); } -void extract_mip_3dm_sensor_2_vehicle_transform_euler_response(mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_response* self) +void extract_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_response* self) { microstrain_extract_float(serializer, &self->roll); @@ -4569,9 +4569,9 @@ void extract_mip_3dm_sensor_2_vehicle_transform_euler_response(mip_serializer* s mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_euler(struct mip_interface* device, float roll, float pitch, float yaw) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4588,9 +4588,9 @@ mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_euler(struct mip_interfa } mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4602,8 +4602,8 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interfac if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(roll_out); microstrain_extract_float(&deserializer, roll_out); @@ -4621,9 +4621,9 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interfac } mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_euler(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4634,9 +4634,9 @@ mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_euler(struct mip_interfac } mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_euler(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4647,9 +4647,9 @@ mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_euler(struct mip_interfac } mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4658,7 +4658,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(struct mip_inter return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_command* self) +void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4669,7 +4669,7 @@ void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(mip_serializer } } -void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_command* self) +void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4681,13 +4681,13 @@ void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(mip_serialize } } -void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_response(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) +void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) { for(unsigned int i=0; i < 4; i++) microstrain_insert_float(serializer, self->q[i]); } -void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_response(mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) +void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) { for(unsigned int i=0; i < 4; i++) microstrain_extract_float(serializer, &self->q[i]); @@ -4696,9 +4696,9 @@ void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_response(mip_serializ mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(struct mip_interface* device, const float* q) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4713,9 +4713,9 @@ mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(struct mip_in } mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_interface* device, float* q_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4727,8 +4727,8 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_int if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(q_out || (4 == 0)); for(unsigned int i=0; i < 4; i++) @@ -4741,9 +4741,9 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_int } mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_quaternion(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4754,9 +4754,9 @@ mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_quaternion(struct mip_int } mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_quaternion(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4767,9 +4767,9 @@ mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_quaternion(struct mip_int } mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4778,7 +4778,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(struct mip_ return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_command* self) +void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4789,7 +4789,7 @@ void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(mip_serializer* seria } } -void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_command* self) +void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4801,13 +4801,13 @@ void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(mip_serializer* seri } } -void insert_mip_3dm_sensor_2_vehicle_transform_dcm_response(mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_response* self) +void insert_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_response* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->dcm[i]); } -void extract_mip_3dm_sensor_2_vehicle_transform_dcm_response(mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_response* self) +void extract_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_response* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->dcm[i]); @@ -4816,9 +4816,9 @@ void extract_mip_3dm_sensor_2_vehicle_transform_dcm_response(mip_serializer* ser mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(struct mip_interface* device, const float* dcm) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4833,9 +4833,9 @@ mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(struct mip_interface } mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* device, float* dcm_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4847,8 +4847,8 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(dcm_out || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -4861,9 +4861,9 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* } mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_dcm(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4874,9 +4874,9 @@ mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_dcm(struct mip_interface* } mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_dcm(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4887,9 +4887,9 @@ mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_dcm(struct mip_interface* } mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4898,7 +4898,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(struct mip_interfa return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_complementary_filter_command(mip_serializer* serializer, const mip_3dm_complementary_filter_command* self) +void insert_mip_3dm_complementary_filter_command(microstrain_serializer* serializer, const mip_3dm_complementary_filter_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4914,7 +4914,7 @@ void insert_mip_3dm_complementary_filter_command(mip_serializer* serializer, con } } -void extract_mip_3dm_complementary_filter_command(mip_serializer* serializer, mip_3dm_complementary_filter_command* self) +void extract_mip_3dm_complementary_filter_command(microstrain_serializer* serializer, mip_3dm_complementary_filter_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4931,7 +4931,7 @@ void extract_mip_3dm_complementary_filter_command(mip_serializer* serializer, mi } } -void insert_mip_3dm_complementary_filter_response(mip_serializer* serializer, const mip_3dm_complementary_filter_response* self) +void insert_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, const mip_3dm_complementary_filter_response* self) { microstrain_insert_bool(serializer, self->pitch_roll_enable); @@ -4942,7 +4942,7 @@ void insert_mip_3dm_complementary_filter_response(mip_serializer* serializer, co microstrain_insert_float(serializer, self->heading_time_constant); } -void extract_mip_3dm_complementary_filter_response(mip_serializer* serializer, mip_3dm_complementary_filter_response* self) +void extract_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, mip_3dm_complementary_filter_response* self) { microstrain_extract_bool(serializer, &self->pitch_roll_enable); @@ -4956,9 +4956,9 @@ void extract_mip_3dm_complementary_filter_response(mip_serializer* serializer, m mip_cmd_result mip_3dm_write_complementary_filter(struct mip_interface* device, bool pitch_roll_enable, bool heading_enable, float pitch_roll_time_constant, float heading_time_constant) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4977,9 +4977,9 @@ mip_cmd_result mip_3dm_write_complementary_filter(struct mip_interface* device, } mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, bool* pitch_roll_enable_out, bool* heading_enable_out, float* pitch_roll_time_constant_out, float* heading_time_constant_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4991,8 +4991,8 @@ mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, b if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(pitch_roll_enable_out); microstrain_extract_bool(&deserializer, pitch_roll_enable_out); @@ -5013,9 +5013,9 @@ mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, b } mip_cmd_result mip_3dm_save_complementary_filter(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5026,9 +5026,9 @@ mip_cmd_result mip_3dm_save_complementary_filter(struct mip_interface* device) } mip_cmd_result mip_3dm_load_complementary_filter(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5039,9 +5039,9 @@ mip_cmd_result mip_3dm_load_complementary_filter(struct mip_interface* device) } mip_cmd_result mip_3dm_default_complementary_filter(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5050,7 +5050,7 @@ mip_cmd_result mip_3dm_default_complementary_filter(struct mip_interface* device return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_sensor_range_command(mip_serializer* serializer, const mip_3dm_sensor_range_command* self) +void insert_mip_3dm_sensor_range_command(microstrain_serializer* serializer, const mip_3dm_sensor_range_command* self) { insert_mip_function_selector(serializer, self->function); @@ -5062,7 +5062,7 @@ void insert_mip_3dm_sensor_range_command(mip_serializer* serializer, const mip_3 } } -void extract_mip_3dm_sensor_range_command(mip_serializer* serializer, mip_3dm_sensor_range_command* self) +void extract_mip_3dm_sensor_range_command(microstrain_serializer* serializer, mip_3dm_sensor_range_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -5075,14 +5075,14 @@ void extract_mip_3dm_sensor_range_command(mip_serializer* serializer, mip_3dm_se } } -void insert_mip_3dm_sensor_range_response(mip_serializer* serializer, const mip_3dm_sensor_range_response* self) +void insert_mip_3dm_sensor_range_response(microstrain_serializer* serializer, const mip_3dm_sensor_range_response* self) { insert_mip_sensor_range_type(serializer, self->sensor); microstrain_insert_u8(serializer, self->setting); } -void extract_mip_3dm_sensor_range_response(mip_serializer* serializer, mip_3dm_sensor_range_response* self) +void extract_mip_3dm_sensor_range_response(microstrain_serializer* serializer, mip_3dm_sensor_range_response* self) { extract_mip_sensor_range_type(serializer, &self->sensor); @@ -5092,9 +5092,9 @@ void extract_mip_3dm_sensor_range_response(mip_serializer* serializer, mip_3dm_s mip_cmd_result mip_3dm_write_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t setting) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -5109,9 +5109,9 @@ mip_cmd_result mip_3dm_write_sensor_range(struct mip_interface* device, mip_sens } mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t* setting_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -5125,8 +5125,8 @@ mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_senso if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); extract_mip_sensor_range_type(&deserializer, &sensor); @@ -5140,9 +5140,9 @@ mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_senso } mip_cmd_result mip_3dm_save_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5155,9 +5155,9 @@ mip_cmd_result mip_3dm_save_sensor_range(struct mip_interface* device, mip_senso } mip_cmd_result mip_3dm_load_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5170,9 +5170,9 @@ mip_cmd_result mip_3dm_load_sensor_range(struct mip_interface* device, mip_senso } mip_cmd_result mip_3dm_default_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5183,18 +5183,18 @@ mip_cmd_result mip_3dm_default_sensor_range(struct mip_interface* device, mip_se return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_3dm_calibrated_sensor_ranges_command(mip_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command* self) +void insert_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command* self) { insert_mip_sensor_range_type(serializer, self->sensor); } -void extract_mip_3dm_calibrated_sensor_ranges_command(mip_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command* self) +void extract_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command* self) { extract_mip_sensor_range_type(serializer, &self->sensor); } -void insert_mip_3dm_calibrated_sensor_ranges_response(mip_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_response* self) +void insert_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_response* self) { insert_mip_sensor_range_type(serializer, self->sensor); @@ -5205,7 +5205,7 @@ void insert_mip_3dm_calibrated_sensor_ranges_response(mip_serializer* serializer insert_mip_3dm_calibrated_sensor_ranges_command_entry(serializer, &self->ranges[i]); } -void extract_mip_3dm_calibrated_sensor_ranges_response(mip_serializer* serializer, mip_3dm_calibrated_sensor_ranges_response* self) +void extract_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_response* self) { extract_mip_sensor_range_type(serializer, &self->sensor); @@ -5217,14 +5217,14 @@ void extract_mip_3dm_calibrated_sensor_ranges_response(mip_serializer* serialize } -void insert_mip_3dm_calibrated_sensor_ranges_command_entry(mip_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command_entry* self) +void insert_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command_entry* self) { microstrain_insert_u8(serializer, self->setting); microstrain_insert_float(serializer, self->range); } -void extract_mip_3dm_calibrated_sensor_ranges_command_entry(mip_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command_entry* self) +void extract_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command_entry* self) { microstrain_extract_u8(serializer, &self->setting); @@ -5234,9 +5234,9 @@ void extract_mip_3dm_calibrated_sensor_ranges_command_entry(mip_serializer* seri mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t* num_ranges_out, uint8_t num_ranges_out_max, mip_3dm_calibrated_sensor_ranges_command_entry* ranges_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_sensor_range_type(&serializer, sensor); @@ -5248,8 +5248,8 @@ mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mi if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); extract_mip_sensor_range_type(&deserializer, &sensor); @@ -5265,7 +5265,7 @@ mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mi } return result; } -void insert_mip_3dm_lowpass_filter_command(mip_serializer* serializer, const mip_3dm_lowpass_filter_command* self) +void insert_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, const mip_3dm_lowpass_filter_command* self) { insert_mip_function_selector(serializer, self->function); @@ -5283,7 +5283,7 @@ void insert_mip_3dm_lowpass_filter_command(mip_serializer* serializer, const mip } } -void extract_mip_3dm_lowpass_filter_command(mip_serializer* serializer, mip_3dm_lowpass_filter_command* self) +void extract_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, mip_3dm_lowpass_filter_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -5302,7 +5302,7 @@ void extract_mip_3dm_lowpass_filter_command(mip_serializer* serializer, mip_3dm_ } } -void insert_mip_3dm_lowpass_filter_response(mip_serializer* serializer, const mip_3dm_lowpass_filter_response* self) +void insert_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_lowpass_filter_response* self) { microstrain_insert_u8(serializer, self->desc_set); @@ -5315,7 +5315,7 @@ void insert_mip_3dm_lowpass_filter_response(mip_serializer* serializer, const mi microstrain_insert_float(serializer, self->frequency); } -void extract_mip_3dm_lowpass_filter_response(mip_serializer* serializer, mip_3dm_lowpass_filter_response* self) +void extract_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_lowpass_filter_response* self) { microstrain_extract_u8(serializer, &self->desc_set); @@ -5331,9 +5331,9 @@ void extract_mip_3dm_lowpass_filter_response(mip_serializer* serializer, mip_3dm mip_cmd_result mip_3dm_write_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool enable, bool manual, float frequency) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -5354,9 +5354,9 @@ mip_cmd_result mip_3dm_write_lowpass_filter(struct mip_interface* device, uint8_ } mip_cmd_result mip_3dm_read_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool* enable_out, bool* manual_out, float* frequency_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -5372,8 +5372,8 @@ mip_cmd_result mip_3dm_read_lowpass_filter(struct mip_interface* device, uint8_t if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &desc_set); @@ -5395,9 +5395,9 @@ mip_cmd_result mip_3dm_read_lowpass_filter(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_save_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5412,9 +5412,9 @@ mip_cmd_result mip_3dm_save_lowpass_filter(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_load_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5429,9 +5429,9 @@ mip_cmd_result mip_3dm_load_lowpass_filter(struct mip_interface* device, uint8_t } mip_cmd_result mip_3dm_default_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); diff --git a/src/mip/definitions/commands_3dm.cpp b/src/mip/definitions/commands_3dm.cpp index 48e6186a1..be0d7fb52 100644 --- a/src/mip/definitions/commands_3dm.cpp +++ b/src/mip/definitions/commands_3dm.cpp @@ -87,7 +87,7 @@ TypedResult pollImuMessage(C::mip_interface& device, bool suppre assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_IMU_MESSAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_IMU_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const PollGnssMessage& self) { @@ -124,7 +124,7 @@ TypedResult pollGnssMessage(C::mip_interface& device, bool supp assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_GNSS_MESSAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_GNSS_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const PollFilterMessage& self) { @@ -161,7 +161,7 @@ TypedResult pollFilterMessage(C::mip_interface& device, bool assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_FILTER_MESSAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_FILTER_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ImuMessageFormat& self) { @@ -219,7 +219,7 @@ TypedResult writeImuMessageFormat(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { @@ -230,7 +230,7 @@ TypedResult readImuMessageFormat(C::mip_interface& device, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_IMU_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_IMU_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -254,7 +254,7 @@ TypedResult saveImuMessageFormat(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadImuMessageFormat(C::mip_interface& device) { @@ -264,7 +264,7 @@ TypedResult loadImuMessageFormat(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultImuMessageFormat(C::mip_interface& device) { @@ -274,7 +274,7 @@ TypedResult defaultImuMessageFormat(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GpsMessageFormat& self) { @@ -332,7 +332,7 @@ TypedResult writeGpsMessageFormat(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { @@ -343,7 +343,7 @@ TypedResult readGpsMessageFormat(C::mip_interface& device, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GNSS_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -367,7 +367,7 @@ TypedResult saveGpsMessageFormat(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGpsMessageFormat(C::mip_interface& device) { @@ -377,7 +377,7 @@ TypedResult loadGpsMessageFormat(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGpsMessageFormat(C::mip_interface& device) { @@ -387,7 +387,7 @@ TypedResult defaultGpsMessageFormat(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const FilterMessageFormat& self) { @@ -445,7 +445,7 @@ TypedResult writeFilterMessageFormat(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { @@ -456,7 +456,7 @@ TypedResult readFilterMessageFormat(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_FILTER_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_FILTER_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -480,7 +480,7 @@ TypedResult saveFilterMessageFormat(C::mip_interface& devic insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadFilterMessageFormat(C::mip_interface& device) { @@ -490,7 +490,7 @@ TypedResult loadFilterMessageFormat(C::mip_interface& devic insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultFilterMessageFormat(C::mip_interface& device) { @@ -500,7 +500,7 @@ TypedResult defaultFilterMessageFormat(C::mip_interface& de insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ImuGetBaseRate& self) { @@ -666,7 +666,7 @@ TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool s assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_DATA, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_DATA, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GetBaseRate& self) { @@ -704,7 +704,7 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_BASE_RATE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_BASE_RATE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_BASE_RATE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_BASE_RATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -786,7 +786,7 @@ TypedResult writeMessageFormat(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { @@ -799,7 +799,7 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -827,7 +827,7 @@ TypedResult saveMessageFormat(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) { @@ -839,7 +839,7 @@ TypedResult loadMessageFormat(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet) { @@ -851,7 +851,7 @@ TypedResult defaultMessageFormat(C::mip_interface& device, uint8_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const NmeaPollData& self) { @@ -888,7 +888,7 @@ TypedResult nmeaPollData(C::mip_interface& device, bool suppressAc assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_NMEA_MESSAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_NMEA_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const NmeaMessageFormat& self) { @@ -946,7 +946,7 @@ TypedResult writeNmeaMessageFormat(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut) { @@ -957,7 +957,7 @@ TypedResult readNmeaMessageFormat(C::mip_interface& device, u assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_NMEA_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_NMEA_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -981,7 +981,7 @@ TypedResult saveNmeaMessageFormat(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadNmeaMessageFormat(C::mip_interface& device) { @@ -991,7 +991,7 @@ TypedResult loadNmeaMessageFormat(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultNmeaMessageFormat(C::mip_interface& device) { @@ -1001,7 +1001,7 @@ TypedResult defaultNmeaMessageFormat(C::mip_interface& device insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const DeviceSettings& self) { @@ -1022,7 +1022,7 @@ TypedResult saveDeviceSettings(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadDeviceSettings(C::mip_interface& device) { @@ -1032,7 +1032,7 @@ TypedResult loadDeviceSettings(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultDeviceSettings(C::mip_interface& device) { @@ -1042,7 +1042,7 @@ TypedResult defaultDeviceSettings(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const UartBaudrate& self) { @@ -1086,7 +1086,7 @@ TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t b assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) { @@ -1097,7 +1097,7 @@ TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* b assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_UART_BAUDRATE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_UART_BAUDRATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1119,7 +1119,7 @@ TypedResult saveUartBaudrate(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadUartBaudrate(C::mip_interface& device) { @@ -1129,7 +1129,7 @@ TypedResult loadUartBaudrate(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultUartBaudrate(C::mip_interface& device) { @@ -1139,7 +1139,7 @@ TypedResult defaultUartBaudrate(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const FactoryStreaming& self) { @@ -1167,7 +1167,7 @@ TypedResult factoryStreaming(C::mip_interface& device, Factory assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const DatastreamControl& self) { @@ -1221,7 +1221,7 @@ TypedResult writeDatastreamControl(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut) { @@ -1234,7 +1234,7 @@ TypedResult readDatastreamControl(C::mip_interface& device, u assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_DATASTREAM_ENABLE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_DATASTREAM_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1260,7 +1260,7 @@ TypedResult saveDatastreamControl(C::mip_interface& device, u assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) { @@ -1272,7 +1272,7 @@ TypedResult loadDatastreamControl(C::mip_interface& device, u assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) { @@ -1284,7 +1284,7 @@ TypedResult defaultDatastreamControl(C::mip_interface& device assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ConstellationSettings& self) { @@ -1383,7 +1383,7 @@ TypedResult writeConstellationSettings(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut) { @@ -1394,7 +1394,7 @@ TypedResult readConstellationSettings(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1424,7 +1424,7 @@ TypedResult saveConstellationSettings(C::mip_interface& d insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadConstellationSettings(C::mip_interface& device) { @@ -1434,7 +1434,7 @@ TypedResult loadConstellationSettings(C::mip_interface& d insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultConstellationSettings(C::mip_interface& device) { @@ -1444,7 +1444,7 @@ TypedResult defaultConstellationSettings(C::mip_interface insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GnssSbasSettings& self) { @@ -1522,7 +1522,7 @@ TypedResult writeGnssSbasSettings(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut) { @@ -1533,7 +1533,7 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GNSS_SBAS_SETTINGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_SBAS_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1563,7 +1563,7 @@ TypedResult saveGnssSbasSettings(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGnssSbasSettings(C::mip_interface& device) { @@ -1573,7 +1573,7 @@ TypedResult loadGnssSbasSettings(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGnssSbasSettings(C::mip_interface& device) { @@ -1583,7 +1583,7 @@ TypedResult defaultGnssSbasSettings(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GnssAssistedFix& self) { @@ -1637,7 +1637,7 @@ TypedResult writeGnssAssistedFix(C::mip_interface& device, Gnss assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut) { @@ -1648,7 +1648,7 @@ TypedResult readGnssAssistedFix(C::mip_interface& device, GnssA assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1673,7 +1673,7 @@ TypedResult saveGnssAssistedFix(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGnssAssistedFix(C::mip_interface& device) { @@ -1683,7 +1683,7 @@ TypedResult loadGnssAssistedFix(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGnssAssistedFix(C::mip_interface& device) { @@ -1693,7 +1693,7 @@ TypedResult defaultGnssAssistedFix(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GnssTimeAssistance& self) { @@ -1757,7 +1757,7 @@ TypedResult writeGnssTimeAssistance(C::mip_interface& device assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut) { @@ -1768,7 +1768,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GNSS_TIME_ASSISTANCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_TIME_ASSISTANCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1870,7 +1870,7 @@ TypedResult writeImuLowpassFilter(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut) { @@ -1883,7 +1883,7 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ADVANCED_DATA_FILTER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ADVANCED_DATA_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1918,7 +1918,7 @@ TypedResult saveImuLowpassFilter(C::mip_interface& device, uin assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { @@ -1930,7 +1930,7 @@ TypedResult loadImuLowpassFilter(C::mip_interface& device, uin assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { @@ -1942,7 +1942,7 @@ TypedResult defaultImuLowpassFilter(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const PpsSource& self) { @@ -1986,7 +1986,7 @@ TypedResult writePpsSource(C::mip_interface& device, PpsSource::Sourc assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) { @@ -1997,7 +1997,7 @@ TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_PPS_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_PPS_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2019,7 +2019,7 @@ TypedResult savePpsSource(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadPpsSource(C::mip_interface& device) { @@ -2029,7 +2029,7 @@ TypedResult loadPpsSource(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultPpsSource(C::mip_interface& device) { @@ -2039,7 +2039,7 @@ TypedResult defaultPpsSource(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GpioConfig& self) { @@ -2113,7 +2113,7 @@ TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, G assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut) { @@ -2126,7 +2126,7 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GPIO_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GPIO_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2158,7 +2158,7 @@ TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) { @@ -2170,7 +2170,7 @@ TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) { @@ -2182,7 +2182,7 @@ TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GpioState& self) { @@ -2242,7 +2242,7 @@ TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, boo assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) { @@ -2255,7 +2255,7 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GPIO_STATE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GPIO_STATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2333,7 +2333,7 @@ TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mod assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut) { @@ -2344,7 +2344,7 @@ TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* mod assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ODOMETER_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ODOMETER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2372,7 +2372,7 @@ TypedResult saveOdometer(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadOdometer(C::mip_interface& device) { @@ -2382,7 +2382,7 @@ TypedResult loadOdometer(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultOdometer(C::mip_interface& device) { @@ -2392,7 +2392,7 @@ TypedResult defaultOdometer(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GetEventSupport& self) { @@ -2454,7 +2454,7 @@ TypedResult getEventSupport(C::mip_interface& device, GetEventS assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_SUPPORT, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_EVENT_SUPPORT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_SUPPORT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_SUPPORT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2527,7 +2527,7 @@ TypedResult writeEventControl(C::mip_interface& device, uint8_t in assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut) { @@ -2540,7 +2540,7 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_EVENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2566,7 +2566,7 @@ TypedResult saveEventControl(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadEventControl(C::mip_interface& device, uint8_t instance) { @@ -2578,7 +2578,7 @@ TypedResult loadEventControl(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultEventControl(C::mip_interface& device, uint8_t instance) { @@ -2590,7 +2590,7 @@ TypedResult defaultEventControl(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GetEventTriggerStatus& self) { @@ -2653,7 +2653,7 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_STATUS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_STATUS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2730,7 +2730,7 @@ TypedResult getEventActionStatus(C::mip_interface& device, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_STATUS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_EVENT_ACTION_STATUS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_STATUS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_ACTION_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2968,7 +2968,7 @@ TypedResult writeEventTrigger(C::mip_interface& device, uint8_t in } assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut) { @@ -2981,7 +2981,7 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_EVENT_TRIGGER_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_TRIGGER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3022,7 +3022,7 @@ TypedResult saveEventTrigger(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadEventTrigger(C::mip_interface& device, uint8_t instance) { @@ -3034,7 +3034,7 @@ TypedResult loadEventTrigger(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t instance) { @@ -3046,7 +3046,7 @@ TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const EventAction& self) { @@ -3199,7 +3199,7 @@ TypedResult writeEventAction(C::mip_interface& device, uint8_t inst } assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut) { @@ -3212,7 +3212,7 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_EVENT_ACTION_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_ACTION_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3251,7 +3251,7 @@ TypedResult saveEventAction(C::mip_interface& device, uint8_t insta assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadEventAction(C::mip_interface& device, uint8_t instance) { @@ -3263,7 +3263,7 @@ TypedResult loadEventAction(C::mip_interface& device, uint8_t insta assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultEventAction(C::mip_interface& device, uint8_t instance) { @@ -3275,7 +3275,7 @@ TypedResult defaultEventAction(C::mip_interface& device, uint8_t in assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AccelBias& self) { @@ -3325,7 +3325,7 @@ TypedResult writeAccelBias(C::mip_interface& device, const float* bia assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAccelBias(C::mip_interface& device, float* biasOut) { @@ -3336,7 +3336,7 @@ TypedResult readAccelBias(C::mip_interface& device, float* biasOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ACCEL_BIAS_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ACCEL_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3359,7 +3359,7 @@ TypedResult saveAccelBias(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAccelBias(C::mip_interface& device) { @@ -3369,7 +3369,7 @@ TypedResult loadAccelBias(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAccelBias(C::mip_interface& device) { @@ -3379,7 +3379,7 @@ TypedResult defaultAccelBias(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GyroBias& self) { @@ -3429,7 +3429,7 @@ TypedResult writeGyroBias(C::mip_interface& device, const float* bias) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGyroBias(C::mip_interface& device, float* biasOut) { @@ -3440,7 +3440,7 @@ TypedResult readGyroBias(C::mip_interface& device, float* biasOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3463,7 +3463,7 @@ TypedResult saveGyroBias(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGyroBias(C::mip_interface& device) { @@ -3473,7 +3473,7 @@ TypedResult loadGyroBias(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGyroBias(C::mip_interface& device) { @@ -3483,7 +3483,7 @@ TypedResult defaultGyroBias(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const CaptureGyroBias& self) { @@ -3519,7 +3519,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CAPTURE_GYRO_BIAS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CAPTURE_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3582,7 +3582,7 @@ TypedResult writeMagHardIronOffset(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) { @@ -3593,7 +3593,7 @@ TypedResult readMagHardIronOffset(C::mip_interface& device, f assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3616,7 +3616,7 @@ TypedResult saveMagHardIronOffset(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadMagHardIronOffset(C::mip_interface& device) { @@ -3626,7 +3626,7 @@ TypedResult loadMagHardIronOffset(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultMagHardIronOffset(C::mip_interface& device) { @@ -3636,7 +3636,7 @@ TypedResult defaultMagHardIronOffset(C::mip_interface& device insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const MagSoftIronMatrix& self) { @@ -3686,7 +3686,7 @@ TypedResult writeMagSoftIronMatrix(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) { @@ -3697,7 +3697,7 @@ TypedResult readMagSoftIronMatrix(C::mip_interface& device, f assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3720,7 +3720,7 @@ TypedResult saveMagSoftIronMatrix(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadMagSoftIronMatrix(C::mip_interface& device) { @@ -3730,7 +3730,7 @@ TypedResult loadMagSoftIronMatrix(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultMagSoftIronMatrix(C::mip_interface& device) { @@ -3740,7 +3740,7 @@ TypedResult defaultMagSoftIronMatrix(C::mip_interface& device insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ConingScullingEnable& self) { @@ -3784,7 +3784,7 @@ TypedResult writeConingScullingEnable(C::mip_interface& de assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut) { @@ -3795,7 +3795,7 @@ TypedResult readConingScullingEnable(C::mip_interface& dev assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3817,7 +3817,7 @@ TypedResult saveConingScullingEnable(C::mip_interface& dev insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadConingScullingEnable(C::mip_interface& device) { @@ -3827,7 +3827,7 @@ TypedResult loadConingScullingEnable(C::mip_interface& dev insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultConingScullingEnable(C::mip_interface& device) { @@ -3837,7 +3837,7 @@ TypedResult defaultConingScullingEnable(C::mip_interface& insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const Sensor2VehicleTransformEuler& self) { @@ -3901,7 +3901,7 @@ TypedResult writeSensor2VehicleTransformEuler(C::m assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { @@ -3912,7 +3912,7 @@ TypedResult readSensor2VehicleTransformEuler(C::mi assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3940,7 +3940,7 @@ TypedResult saveSensor2VehicleTransformEuler(C::mi insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSensor2VehicleTransformEuler(C::mip_interface& device) { @@ -3950,7 +3950,7 @@ TypedResult loadSensor2VehicleTransformEuler(C::mi insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSensor2VehicleTransformEuler(C::mip_interface& device) { @@ -3960,7 +3960,7 @@ TypedResult defaultSensor2VehicleTransformEuler(C: insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const Sensor2VehicleTransformQuaternion& self) { @@ -4010,7 +4010,7 @@ TypedResult writeSensor2VehicleTransformQuate assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut) { @@ -4021,7 +4021,7 @@ TypedResult readSensor2VehicleTransformQuater assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4044,7 +4044,7 @@ TypedResult saveSensor2VehicleTransformQuater insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) { @@ -4054,7 +4054,7 @@ TypedResult loadSensor2VehicleTransformQuater insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device) { @@ -4064,7 +4064,7 @@ TypedResult defaultSensor2VehicleTransformQua insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const Sensor2VehicleTransformDcm& self) { @@ -4114,7 +4114,7 @@ TypedResult writeSensor2VehicleTransformDcm(C::mip_i assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut) { @@ -4125,7 +4125,7 @@ TypedResult readSensor2VehicleTransformDcm(C::mip_in assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4148,7 +4148,7 @@ TypedResult saveSensor2VehicleTransformDcm(C::mip_in insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSensor2VehicleTransformDcm(C::mip_interface& device) { @@ -4158,7 +4158,7 @@ TypedResult loadSensor2VehicleTransformDcm(C::mip_in insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSensor2VehicleTransformDcm(C::mip_interface& device) { @@ -4168,7 +4168,7 @@ TypedResult defaultSensor2VehicleTransformDcm(C::mip insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ComplementaryFilter& self) { @@ -4242,7 +4242,7 @@ TypedResult writeComplementaryFilter(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut) { @@ -4253,7 +4253,7 @@ TypedResult readComplementaryFilter(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_LEGACY_COMP_FILTER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_LEGACY_COMP_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4284,7 +4284,7 @@ TypedResult saveComplementaryFilter(C::mip_interface& devic insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadComplementaryFilter(C::mip_interface& device) { @@ -4294,7 +4294,7 @@ TypedResult loadComplementaryFilter(C::mip_interface& devic insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultComplementaryFilter(C::mip_interface& device) { @@ -4304,7 +4304,7 @@ TypedResult defaultComplementaryFilter(C::mip_interface& de insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SensorRange& self) { @@ -4358,7 +4358,7 @@ TypedResult writeSensorRange(C::mip_interface& device, SensorRangeT assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut) { @@ -4371,7 +4371,7 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SENSOR_RANGE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR_RANGE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4397,7 +4397,7 @@ TypedResult saveSensorRange(C::mip_interface& device, SensorRangeTy assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) { @@ -4409,7 +4409,7 @@ TypedResult loadSensorRange(C::mip_interface& device, SensorRangeTy assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor) { @@ -4421,7 +4421,7 @@ TypedResult defaultSensorRange(C::mip_interface& device, SensorRang assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const CalibratedSensorRanges& self) { @@ -4479,7 +4479,7 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CALIBRATED_RANGES, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_CALIBRATED_RANGES, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CALIBRATED_RANGES, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_CALIBRATED_RANGES, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4579,7 +4579,7 @@ TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut) { @@ -4594,7 +4594,7 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_LOWPASS_FILTER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_LOWPASS_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4630,7 +4630,7 @@ TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { @@ -4644,7 +4644,7 @@ TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { @@ -4658,7 +4658,7 @@ TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } } // namespace commands_3dm diff --git a/src/mip/definitions/commands_3dm.h b/src/mip/definitions/commands_3dm.h index b98e35c98..0aec3750e 100644 --- a/src/mip/definitions/commands_3dm.h +++ b/src/mip/definitions/commands_3dm.h @@ -15,7 +15,6 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -172,14 +171,14 @@ struct mip_nmea_message }; typedef struct mip_nmea_message mip_nmea_message; -void insert_mip_nmea_message(struct mip_serializer* serializer, const mip_nmea_message* self); -void extract_mip_nmea_message(struct mip_serializer* serializer, mip_nmea_message* self); +void insert_mip_nmea_message(microstrain_serializer* serializer, const mip_nmea_message* self); +void extract_mip_nmea_message(microstrain_serializer* serializer, mip_nmea_message* self); -void insert_mip_nmea_message_message_id(struct mip_serializer* serializer, const mip_nmea_message_message_id self); -void extract_mip_nmea_message_message_id(struct mip_serializer* serializer, mip_nmea_message_message_id* self); +void insert_mip_nmea_message_message_id(microstrain_serializer* serializer, const mip_nmea_message_message_id self); +void extract_mip_nmea_message_message_id(microstrain_serializer* serializer, mip_nmea_message_message_id* self); -void insert_mip_nmea_message_talker_id(struct mip_serializer* serializer, const mip_nmea_message_talker_id self); -void extract_mip_nmea_message_talker_id(struct mip_serializer* serializer, mip_nmea_message_talker_id* self); +void insert_mip_nmea_message_talker_id(microstrain_serializer* serializer, const mip_nmea_message_talker_id self); +void extract_mip_nmea_message_talker_id(microstrain_serializer* serializer, mip_nmea_message_talker_id* self); typedef uint8_t mip_sensor_range_type; static const mip_sensor_range_type MIP_SENSOR_RANGE_TYPE_ALL = 0; ///< Only allowed for SAVE, LOAD, and DEFAULT function selectors. @@ -188,8 +187,8 @@ static const mip_sensor_range_type MIP_SENSOR_RANGE_TYPE_GYRO = 2; ///< Gyrosc static const mip_sensor_range_type MIP_SENSOR_RANGE_TYPE_MAG = 3; ///< Magnetometer. Range is specified in Gauss. static const mip_sensor_range_type MIP_SENSOR_RANGE_TYPE_PRESS = 4; ///< Pressure sensor. Range is specified in hPa. -void insert_mip_sensor_range_type(struct mip_serializer* serializer, const mip_sensor_range_type self); -void extract_mip_sensor_range_type(struct mip_serializer* serializer, mip_sensor_range_type* self); +void insert_mip_sensor_range_type(microstrain_serializer* serializer, const mip_sensor_range_type self); +void extract_mip_sensor_range_type(microstrain_serializer* serializer, mip_sensor_range_type* self); //////////////////////////////////////////////////////////////////////////////// @@ -217,8 +216,8 @@ struct mip_3dm_poll_imu_message_command }; typedef struct mip_3dm_poll_imu_message_command mip_3dm_poll_imu_message_command; -void insert_mip_3dm_poll_imu_message_command(struct mip_serializer* serializer, const mip_3dm_poll_imu_message_command* self); -void extract_mip_3dm_poll_imu_message_command(struct mip_serializer* serializer, mip_3dm_poll_imu_message_command* self); +void insert_mip_3dm_poll_imu_message_command(microstrain_serializer* serializer, const mip_3dm_poll_imu_message_command* self); +void extract_mip_3dm_poll_imu_message_command(microstrain_serializer* serializer, mip_3dm_poll_imu_message_command* self); mip_cmd_result mip_3dm_poll_imu_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); @@ -245,8 +244,8 @@ struct mip_3dm_poll_gnss_message_command }; typedef struct mip_3dm_poll_gnss_message_command mip_3dm_poll_gnss_message_command; -void insert_mip_3dm_poll_gnss_message_command(struct mip_serializer* serializer, const mip_3dm_poll_gnss_message_command* self); -void extract_mip_3dm_poll_gnss_message_command(struct mip_serializer* serializer, mip_3dm_poll_gnss_message_command* self); +void insert_mip_3dm_poll_gnss_message_command(microstrain_serializer* serializer, const mip_3dm_poll_gnss_message_command* self); +void extract_mip_3dm_poll_gnss_message_command(microstrain_serializer* serializer, mip_3dm_poll_gnss_message_command* self); mip_cmd_result mip_3dm_poll_gnss_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); @@ -273,8 +272,8 @@ struct mip_3dm_poll_filter_message_command }; typedef struct mip_3dm_poll_filter_message_command mip_3dm_poll_filter_message_command; -void insert_mip_3dm_poll_filter_message_command(struct mip_serializer* serializer, const mip_3dm_poll_filter_message_command* self); -void extract_mip_3dm_poll_filter_message_command(struct mip_serializer* serializer, mip_3dm_poll_filter_message_command* self); +void insert_mip_3dm_poll_filter_message_command(microstrain_serializer* serializer, const mip_3dm_poll_filter_message_command* self); +void extract_mip_3dm_poll_filter_message_command(microstrain_serializer* serializer, mip_3dm_poll_filter_message_command* self); mip_cmd_result mip_3dm_poll_filter_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); @@ -296,8 +295,8 @@ struct mip_3dm_imu_message_format_command }; typedef struct mip_3dm_imu_message_format_command mip_3dm_imu_message_format_command; -void insert_mip_3dm_imu_message_format_command(struct mip_serializer* serializer, const mip_3dm_imu_message_format_command* self); -void extract_mip_3dm_imu_message_format_command(struct mip_serializer* serializer, mip_3dm_imu_message_format_command* self); +void insert_mip_3dm_imu_message_format_command(microstrain_serializer* serializer, const mip_3dm_imu_message_format_command* self); +void extract_mip_3dm_imu_message_format_command(microstrain_serializer* serializer, mip_3dm_imu_message_format_command* self); struct mip_3dm_imu_message_format_response { @@ -306,8 +305,8 @@ struct mip_3dm_imu_message_format_response }; typedef struct mip_3dm_imu_message_format_response mip_3dm_imu_message_format_response; -void insert_mip_3dm_imu_message_format_response(struct mip_serializer* serializer, const mip_3dm_imu_message_format_response* self); -void extract_mip_3dm_imu_message_format_response(struct mip_serializer* serializer, mip_3dm_imu_message_format_response* self); +void insert_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, const mip_3dm_imu_message_format_response* self); +void extract_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, mip_3dm_imu_message_format_response* self); mip_cmd_result mip_3dm_write_imu_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); @@ -333,8 +332,8 @@ struct mip_3dm_gps_message_format_command }; typedef struct mip_3dm_gps_message_format_command mip_3dm_gps_message_format_command; -void insert_mip_3dm_gps_message_format_command(struct mip_serializer* serializer, const mip_3dm_gps_message_format_command* self); -void extract_mip_3dm_gps_message_format_command(struct mip_serializer* serializer, mip_3dm_gps_message_format_command* self); +void insert_mip_3dm_gps_message_format_command(microstrain_serializer* serializer, const mip_3dm_gps_message_format_command* self); +void extract_mip_3dm_gps_message_format_command(microstrain_serializer* serializer, mip_3dm_gps_message_format_command* self); struct mip_3dm_gps_message_format_response { @@ -343,8 +342,8 @@ struct mip_3dm_gps_message_format_response }; typedef struct mip_3dm_gps_message_format_response mip_3dm_gps_message_format_response; -void insert_mip_3dm_gps_message_format_response(struct mip_serializer* serializer, const mip_3dm_gps_message_format_response* self); -void extract_mip_3dm_gps_message_format_response(struct mip_serializer* serializer, mip_3dm_gps_message_format_response* self); +void insert_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, const mip_3dm_gps_message_format_response* self); +void extract_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, mip_3dm_gps_message_format_response* self); mip_cmd_result mip_3dm_write_gps_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); @@ -370,8 +369,8 @@ struct mip_3dm_filter_message_format_command }; typedef struct mip_3dm_filter_message_format_command mip_3dm_filter_message_format_command; -void insert_mip_3dm_filter_message_format_command(struct mip_serializer* serializer, const mip_3dm_filter_message_format_command* self); -void extract_mip_3dm_filter_message_format_command(struct mip_serializer* serializer, mip_3dm_filter_message_format_command* self); +void insert_mip_3dm_filter_message_format_command(microstrain_serializer* serializer, const mip_3dm_filter_message_format_command* self); +void extract_mip_3dm_filter_message_format_command(microstrain_serializer* serializer, mip_3dm_filter_message_format_command* self); struct mip_3dm_filter_message_format_response { @@ -380,8 +379,8 @@ struct mip_3dm_filter_message_format_response }; typedef struct mip_3dm_filter_message_format_response mip_3dm_filter_message_format_response; -void insert_mip_3dm_filter_message_format_response(struct mip_serializer* serializer, const mip_3dm_filter_message_format_response* self); -void extract_mip_3dm_filter_message_format_response(struct mip_serializer* serializer, mip_3dm_filter_message_format_response* self); +void insert_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, const mip_3dm_filter_message_format_response* self); +void extract_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, mip_3dm_filter_message_format_response* self); mip_cmd_result mip_3dm_write_filter_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); @@ -406,8 +405,8 @@ struct mip_3dm_imu_get_base_rate_response }; typedef struct mip_3dm_imu_get_base_rate_response mip_3dm_imu_get_base_rate_response; -void insert_mip_3dm_imu_get_base_rate_response(struct mip_serializer* serializer, const mip_3dm_imu_get_base_rate_response* self); -void extract_mip_3dm_imu_get_base_rate_response(struct mip_serializer* serializer, mip_3dm_imu_get_base_rate_response* self); +void insert_mip_3dm_imu_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_imu_get_base_rate_response* self); +void extract_mip_3dm_imu_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_imu_get_base_rate_response* self); mip_cmd_result mip_3dm_imu_get_base_rate(struct mip_interface* device, uint16_t* rate_out); @@ -428,8 +427,8 @@ struct mip_3dm_gps_get_base_rate_response }; typedef struct mip_3dm_gps_get_base_rate_response mip_3dm_gps_get_base_rate_response; -void insert_mip_3dm_gps_get_base_rate_response(struct mip_serializer* serializer, const mip_3dm_gps_get_base_rate_response* self); -void extract_mip_3dm_gps_get_base_rate_response(struct mip_serializer* serializer, mip_3dm_gps_get_base_rate_response* self); +void insert_mip_3dm_gps_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_gps_get_base_rate_response* self); +void extract_mip_3dm_gps_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_gps_get_base_rate_response* self); mip_cmd_result mip_3dm_gps_get_base_rate(struct mip_interface* device, uint16_t* rate_out); @@ -450,8 +449,8 @@ struct mip_3dm_filter_get_base_rate_response }; typedef struct mip_3dm_filter_get_base_rate_response mip_3dm_filter_get_base_rate_response; -void insert_mip_3dm_filter_get_base_rate_response(struct mip_serializer* serializer, const mip_3dm_filter_get_base_rate_response* self); -void extract_mip_3dm_filter_get_base_rate_response(struct mip_serializer* serializer, mip_3dm_filter_get_base_rate_response* self); +void insert_mip_3dm_filter_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_filter_get_base_rate_response* self); +void extract_mip_3dm_filter_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_filter_get_base_rate_response* self); mip_cmd_result mip_3dm_filter_get_base_rate(struct mip_interface* device, uint16_t* rate_out); @@ -479,8 +478,8 @@ struct mip_3dm_poll_data_command }; typedef struct mip_3dm_poll_data_command mip_3dm_poll_data_command; -void insert_mip_3dm_poll_data_command(struct mip_serializer* serializer, const mip_3dm_poll_data_command* self); -void extract_mip_3dm_poll_data_command(struct mip_serializer* serializer, mip_3dm_poll_data_command* self); +void insert_mip_3dm_poll_data_command(microstrain_serializer* serializer, const mip_3dm_poll_data_command* self); +void extract_mip_3dm_poll_data_command(microstrain_serializer* serializer, mip_3dm_poll_data_command* self); mip_cmd_result mip_3dm_poll_data(struct mip_interface* device, uint8_t desc_set, bool suppress_ack, uint8_t num_descriptors, const uint8_t* descriptors); @@ -498,8 +497,8 @@ struct mip_3dm_get_base_rate_command }; typedef struct mip_3dm_get_base_rate_command mip_3dm_get_base_rate_command; -void insert_mip_3dm_get_base_rate_command(struct mip_serializer* serializer, const mip_3dm_get_base_rate_command* self); -void extract_mip_3dm_get_base_rate_command(struct mip_serializer* serializer, mip_3dm_get_base_rate_command* self); +void insert_mip_3dm_get_base_rate_command(microstrain_serializer* serializer, const mip_3dm_get_base_rate_command* self); +void extract_mip_3dm_get_base_rate_command(microstrain_serializer* serializer, mip_3dm_get_base_rate_command* self); struct mip_3dm_get_base_rate_response { @@ -508,8 +507,8 @@ struct mip_3dm_get_base_rate_response }; typedef struct mip_3dm_get_base_rate_response mip_3dm_get_base_rate_response; -void insert_mip_3dm_get_base_rate_response(struct mip_serializer* serializer, const mip_3dm_get_base_rate_response* self); -void extract_mip_3dm_get_base_rate_response(struct mip_serializer* serializer, mip_3dm_get_base_rate_response* self); +void insert_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_get_base_rate_response* self); +void extract_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_get_base_rate_response* self); mip_cmd_result mip_3dm_get_base_rate(struct mip_interface* device, uint8_t desc_set, uint16_t* rate_out); @@ -532,8 +531,8 @@ struct mip_3dm_message_format_command }; typedef struct mip_3dm_message_format_command mip_3dm_message_format_command; -void insert_mip_3dm_message_format_command(struct mip_serializer* serializer, const mip_3dm_message_format_command* self); -void extract_mip_3dm_message_format_command(struct mip_serializer* serializer, mip_3dm_message_format_command* self); +void insert_mip_3dm_message_format_command(microstrain_serializer* serializer, const mip_3dm_message_format_command* self); +void extract_mip_3dm_message_format_command(microstrain_serializer* serializer, mip_3dm_message_format_command* self); struct mip_3dm_message_format_response { @@ -543,8 +542,8 @@ struct mip_3dm_message_format_response }; typedef struct mip_3dm_message_format_response mip_3dm_message_format_response; -void insert_mip_3dm_message_format_response(struct mip_serializer* serializer, const mip_3dm_message_format_response* self); -void extract_mip_3dm_message_format_response(struct mip_serializer* serializer, mip_3dm_message_format_response* self); +void insert_mip_3dm_message_format_response(microstrain_serializer* serializer, const mip_3dm_message_format_response* self); +void extract_mip_3dm_message_format_response(microstrain_serializer* serializer, mip_3dm_message_format_response* self); mip_cmd_result mip_3dm_write_message_format(struct mip_interface* device, uint8_t desc_set, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); mip_cmd_result mip_3dm_read_message_format(struct mip_interface* device, uint8_t desc_set, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); @@ -574,8 +573,8 @@ struct mip_3dm_nmea_poll_data_command }; typedef struct mip_3dm_nmea_poll_data_command mip_3dm_nmea_poll_data_command; -void insert_mip_3dm_nmea_poll_data_command(struct mip_serializer* serializer, const mip_3dm_nmea_poll_data_command* self); -void extract_mip_3dm_nmea_poll_data_command(struct mip_serializer* serializer, mip_3dm_nmea_poll_data_command* self); +void insert_mip_3dm_nmea_poll_data_command(microstrain_serializer* serializer, const mip_3dm_nmea_poll_data_command* self); +void extract_mip_3dm_nmea_poll_data_command(microstrain_serializer* serializer, mip_3dm_nmea_poll_data_command* self); mip_cmd_result mip_3dm_nmea_poll_data(struct mip_interface* device, bool suppress_ack, uint8_t count, const mip_nmea_message* format_entries); @@ -595,8 +594,8 @@ struct mip_3dm_nmea_message_format_command }; typedef struct mip_3dm_nmea_message_format_command mip_3dm_nmea_message_format_command; -void insert_mip_3dm_nmea_message_format_command(struct mip_serializer* serializer, const mip_3dm_nmea_message_format_command* self); -void extract_mip_3dm_nmea_message_format_command(struct mip_serializer* serializer, mip_3dm_nmea_message_format_command* self); +void insert_mip_3dm_nmea_message_format_command(microstrain_serializer* serializer, const mip_3dm_nmea_message_format_command* self); +void extract_mip_3dm_nmea_message_format_command(microstrain_serializer* serializer, mip_3dm_nmea_message_format_command* self); struct mip_3dm_nmea_message_format_response { @@ -605,8 +604,8 @@ struct mip_3dm_nmea_message_format_response }; typedef struct mip_3dm_nmea_message_format_response mip_3dm_nmea_message_format_response; -void insert_mip_3dm_nmea_message_format_response(struct mip_serializer* serializer, const mip_3dm_nmea_message_format_response* self); -void extract_mip_3dm_nmea_message_format_response(struct mip_serializer* serializer, mip_3dm_nmea_message_format_response* self); +void insert_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, const mip_3dm_nmea_message_format_response* self); +void extract_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, mip_3dm_nmea_message_format_response* self); mip_cmd_result mip_3dm_write_nmea_message_format(struct mip_interface* device, uint8_t count, const mip_nmea_message* format_entries); mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, uint8_t* count_out, uint8_t count_out_max, mip_nmea_message* format_entries_out); @@ -632,8 +631,8 @@ struct mip_3dm_device_settings_command }; typedef struct mip_3dm_device_settings_command mip_3dm_device_settings_command; -void insert_mip_3dm_device_settings_command(struct mip_serializer* serializer, const mip_3dm_device_settings_command* self); -void extract_mip_3dm_device_settings_command(struct mip_serializer* serializer, mip_3dm_device_settings_command* self); +void insert_mip_3dm_device_settings_command(microstrain_serializer* serializer, const mip_3dm_device_settings_command* self); +void extract_mip_3dm_device_settings_command(microstrain_serializer* serializer, mip_3dm_device_settings_command* self); mip_cmd_result mip_3dm_save_device_settings(struct mip_interface* device); mip_cmd_result mip_3dm_load_device_settings(struct mip_interface* device); @@ -668,8 +667,8 @@ struct mip_3dm_uart_baudrate_command }; typedef struct mip_3dm_uart_baudrate_command mip_3dm_uart_baudrate_command; -void insert_mip_3dm_uart_baudrate_command(struct mip_serializer* serializer, const mip_3dm_uart_baudrate_command* self); -void extract_mip_3dm_uart_baudrate_command(struct mip_serializer* serializer, mip_3dm_uart_baudrate_command* self); +void insert_mip_3dm_uart_baudrate_command(microstrain_serializer* serializer, const mip_3dm_uart_baudrate_command* self); +void extract_mip_3dm_uart_baudrate_command(microstrain_serializer* serializer, mip_3dm_uart_baudrate_command* self); struct mip_3dm_uart_baudrate_response { @@ -677,8 +676,8 @@ struct mip_3dm_uart_baudrate_response }; typedef struct mip_3dm_uart_baudrate_response mip_3dm_uart_baudrate_response; -void insert_mip_3dm_uart_baudrate_response(struct mip_serializer* serializer, const mip_3dm_uart_baudrate_response* self); -void extract_mip_3dm_uart_baudrate_response(struct mip_serializer* serializer, mip_3dm_uart_baudrate_response* self); +void insert_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, const mip_3dm_uart_baudrate_response* self); +void extract_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, mip_3dm_uart_baudrate_response* self); mip_cmd_result mip_3dm_write_uart_baudrate(struct mip_interface* device, uint32_t baud); mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t* baud_out); @@ -709,11 +708,11 @@ struct mip_3dm_factory_streaming_command }; typedef struct mip_3dm_factory_streaming_command mip_3dm_factory_streaming_command; -void insert_mip_3dm_factory_streaming_command(struct mip_serializer* serializer, const mip_3dm_factory_streaming_command* self); -void extract_mip_3dm_factory_streaming_command(struct mip_serializer* serializer, mip_3dm_factory_streaming_command* self); +void insert_mip_3dm_factory_streaming_command(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command* self); +void extract_mip_3dm_factory_streaming_command(microstrain_serializer* serializer, mip_3dm_factory_streaming_command* self); -void insert_mip_3dm_factory_streaming_command_action(struct mip_serializer* serializer, const mip_3dm_factory_streaming_command_action self); -void extract_mip_3dm_factory_streaming_command_action(struct mip_serializer* serializer, mip_3dm_factory_streaming_command_action* self); +void insert_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command_action self); +void extract_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, mip_3dm_factory_streaming_command_action* self); mip_cmd_result mip_3dm_factory_streaming(struct mip_interface* device, mip_3dm_factory_streaming_command_action action, uint8_t reserved); @@ -742,8 +741,8 @@ struct mip_3dm_datastream_control_command }; typedef struct mip_3dm_datastream_control_command mip_3dm_datastream_control_command; -void insert_mip_3dm_datastream_control_command(struct mip_serializer* serializer, const mip_3dm_datastream_control_command* self); -void extract_mip_3dm_datastream_control_command(struct mip_serializer* serializer, mip_3dm_datastream_control_command* self); +void insert_mip_3dm_datastream_control_command(microstrain_serializer* serializer, const mip_3dm_datastream_control_command* self); +void extract_mip_3dm_datastream_control_command(microstrain_serializer* serializer, mip_3dm_datastream_control_command* self); struct mip_3dm_datastream_control_response { @@ -752,8 +751,8 @@ struct mip_3dm_datastream_control_response }; typedef struct mip_3dm_datastream_control_response mip_3dm_datastream_control_response; -void insert_mip_3dm_datastream_control_response(struct mip_serializer* serializer, const mip_3dm_datastream_control_response* self); -void extract_mip_3dm_datastream_control_response(struct mip_serializer* serializer, mip_3dm_datastream_control_response* self); +void insert_mip_3dm_datastream_control_response(microstrain_serializer* serializer, const mip_3dm_datastream_control_response* self); +void extract_mip_3dm_datastream_control_response(microstrain_serializer* serializer, mip_3dm_datastream_control_response* self); mip_cmd_result mip_3dm_write_datastream_control(struct mip_interface* device, uint8_t desc_set, bool enable); mip_cmd_result mip_3dm_read_datastream_control(struct mip_interface* device, uint8_t desc_set, bool* enabled_out); @@ -818,17 +817,17 @@ struct mip_3dm_constellation_settings_command }; typedef struct mip_3dm_constellation_settings_command mip_3dm_constellation_settings_command; -void insert_mip_3dm_constellation_settings_command(struct mip_serializer* serializer, const mip_3dm_constellation_settings_command* self); -void extract_mip_3dm_constellation_settings_command(struct mip_serializer* serializer, mip_3dm_constellation_settings_command* self); +void insert_mip_3dm_constellation_settings_command(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command* self); +void extract_mip_3dm_constellation_settings_command(microstrain_serializer* serializer, mip_3dm_constellation_settings_command* self); -void insert_mip_3dm_constellation_settings_command_constellation_id(struct mip_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self); -void extract_mip_3dm_constellation_settings_command_constellation_id(struct mip_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self); +void insert_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self); +void extract_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self); -void insert_mip_3dm_constellation_settings_command_option_flags(struct mip_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self); -void extract_mip_3dm_constellation_settings_command_option_flags(struct mip_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self); +void insert_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self); +void extract_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self); -void insert_mip_3dm_constellation_settings_command_settings(struct mip_serializer* serializer, const mip_3dm_constellation_settings_command_settings* self); -void extract_mip_3dm_constellation_settings_command_settings(struct mip_serializer* serializer, mip_3dm_constellation_settings_command_settings* self); +void insert_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_settings* self); +void extract_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_settings* self); struct mip_3dm_constellation_settings_response { @@ -839,8 +838,8 @@ struct mip_3dm_constellation_settings_response }; typedef struct mip_3dm_constellation_settings_response mip_3dm_constellation_settings_response; -void insert_mip_3dm_constellation_settings_response(struct mip_serializer* serializer, const mip_3dm_constellation_settings_response* self); -void extract_mip_3dm_constellation_settings_response(struct mip_serializer* serializer, mip_3dm_constellation_settings_response* self); +void insert_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, const mip_3dm_constellation_settings_response* self); +void extract_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, mip_3dm_constellation_settings_response* self); mip_cmd_result mip_3dm_write_constellation_settings(struct mip_interface* device, uint16_t max_channels, uint8_t config_count, const mip_3dm_constellation_settings_command_settings* settings); mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, uint16_t* max_channels_available_out, uint16_t* max_channels_use_out, uint8_t* config_count_out, uint8_t config_count_out_max, mip_3dm_constellation_settings_command_settings* settings_out); @@ -876,11 +875,11 @@ struct mip_3dm_gnss_sbas_settings_command }; typedef struct mip_3dm_gnss_sbas_settings_command mip_3dm_gnss_sbas_settings_command; -void insert_mip_3dm_gnss_sbas_settings_command(struct mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_command* self); -void extract_mip_3dm_gnss_sbas_settings_command(struct mip_serializer* serializer, mip_3dm_gnss_sbas_settings_command* self); +void insert_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command* self); +void extract_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command* self); -void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self); -void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct mip_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self); +void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self); +void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self); struct mip_3dm_gnss_sbas_settings_response { @@ -891,8 +890,8 @@ struct mip_3dm_gnss_sbas_settings_response }; typedef struct mip_3dm_gnss_sbas_settings_response mip_3dm_gnss_sbas_settings_response; -void insert_mip_3dm_gnss_sbas_settings_response(struct mip_serializer* serializer, const mip_3dm_gnss_sbas_settings_response* self); -void extract_mip_3dm_gnss_sbas_settings_response(struct mip_serializer* serializer, mip_3dm_gnss_sbas_settings_response* self); +void insert_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_response* self); +void extract_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_response* self); mip_cmd_result mip_3dm_write_gnss_sbas_settings(struct mip_interface* device, uint8_t enable_sbas, mip_3dm_gnss_sbas_settings_command_sbasoptions sbas_options, uint8_t num_included_prns, const uint16_t* included_prns); mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uint8_t* enable_sbas_out, mip_3dm_gnss_sbas_settings_command_sbasoptions* sbas_options_out, uint8_t* num_included_prns_out, uint8_t num_included_prns_out_max, uint16_t* included_prns_out); @@ -930,11 +929,11 @@ struct mip_3dm_gnss_assisted_fix_command }; typedef struct mip_3dm_gnss_assisted_fix_command mip_3dm_gnss_assisted_fix_command; -void insert_mip_3dm_gnss_assisted_fix_command(struct mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_command* self); -void extract_mip_3dm_gnss_assisted_fix_command(struct mip_serializer* serializer, mip_3dm_gnss_assisted_fix_command* self); +void insert_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command* self); +void extract_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command* self); -void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self); -void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct mip_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self); +void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self); +void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self); struct mip_3dm_gnss_assisted_fix_response { @@ -943,8 +942,8 @@ struct mip_3dm_gnss_assisted_fix_response }; typedef struct mip_3dm_gnss_assisted_fix_response mip_3dm_gnss_assisted_fix_response; -void insert_mip_3dm_gnss_assisted_fix_response(struct mip_serializer* serializer, const mip_3dm_gnss_assisted_fix_response* self); -void extract_mip_3dm_gnss_assisted_fix_response(struct mip_serializer* serializer, mip_3dm_gnss_assisted_fix_response* self); +void insert_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_response* self); +void extract_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_response* self); mip_cmd_result mip_3dm_write_gnss_assisted_fix(struct mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option option, uint8_t flags); mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* option_out, uint8_t* flags_out); @@ -972,8 +971,8 @@ struct mip_3dm_gnss_time_assistance_command }; typedef struct mip_3dm_gnss_time_assistance_command mip_3dm_gnss_time_assistance_command; -void insert_mip_3dm_gnss_time_assistance_command(struct mip_serializer* serializer, const mip_3dm_gnss_time_assistance_command* self); -void extract_mip_3dm_gnss_time_assistance_command(struct mip_serializer* serializer, mip_3dm_gnss_time_assistance_command* self); +void insert_mip_3dm_gnss_time_assistance_command(microstrain_serializer* serializer, const mip_3dm_gnss_time_assistance_command* self); +void extract_mip_3dm_gnss_time_assistance_command(microstrain_serializer* serializer, mip_3dm_gnss_time_assistance_command* self); struct mip_3dm_gnss_time_assistance_response { @@ -983,8 +982,8 @@ struct mip_3dm_gnss_time_assistance_response }; typedef struct mip_3dm_gnss_time_assistance_response mip_3dm_gnss_time_assistance_response; -void insert_mip_3dm_gnss_time_assistance_response(struct mip_serializer* serializer, const mip_3dm_gnss_time_assistance_response* self); -void extract_mip_3dm_gnss_time_assistance_response(struct mip_serializer* serializer, mip_3dm_gnss_time_assistance_response* self); +void insert_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, const mip_3dm_gnss_time_assistance_response* self); +void extract_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, mip_3dm_gnss_time_assistance_response* self); mip_cmd_result mip_3dm_write_gnss_time_assistance(struct mip_interface* device, double tow, uint16_t week_number, float accuracy); mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, double* tow_out, uint16_t* week_number_out, float* accuracy_out); @@ -1023,8 +1022,8 @@ struct mip_3dm_imu_lowpass_filter_command }; typedef struct mip_3dm_imu_lowpass_filter_command mip_3dm_imu_lowpass_filter_command; -void insert_mip_3dm_imu_lowpass_filter_command(struct mip_serializer* serializer, const mip_3dm_imu_lowpass_filter_command* self); -void extract_mip_3dm_imu_lowpass_filter_command(struct mip_serializer* serializer, mip_3dm_imu_lowpass_filter_command* self); +void insert_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serializer, const mip_3dm_imu_lowpass_filter_command* self); +void extract_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serializer, mip_3dm_imu_lowpass_filter_command* self); struct mip_3dm_imu_lowpass_filter_response { @@ -1036,8 +1035,8 @@ struct mip_3dm_imu_lowpass_filter_response }; typedef struct mip_3dm_imu_lowpass_filter_response mip_3dm_imu_lowpass_filter_response; -void insert_mip_3dm_imu_lowpass_filter_response(struct mip_serializer* serializer, const mip_3dm_imu_lowpass_filter_response* self); -void extract_mip_3dm_imu_lowpass_filter_response(struct mip_serializer* serializer, mip_3dm_imu_lowpass_filter_response* self); +void insert_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_imu_lowpass_filter_response* self); +void extract_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_imu_lowpass_filter_response* self); mip_cmd_result mip_3dm_write_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved); mip_cmd_result mip_3dm_read_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor, bool* enable_out, bool* manual_out, uint16_t* frequency_out, uint8_t* reserved_out); @@ -1067,11 +1066,11 @@ struct mip_3dm_pps_source_command }; typedef struct mip_3dm_pps_source_command mip_3dm_pps_source_command; -void insert_mip_3dm_pps_source_command(struct mip_serializer* serializer, const mip_3dm_pps_source_command* self); -void extract_mip_3dm_pps_source_command(struct mip_serializer* serializer, mip_3dm_pps_source_command* self); +void insert_mip_3dm_pps_source_command(microstrain_serializer* serializer, const mip_3dm_pps_source_command* self); +void extract_mip_3dm_pps_source_command(microstrain_serializer* serializer, mip_3dm_pps_source_command* self); -void insert_mip_3dm_pps_source_command_source(struct mip_serializer* serializer, const mip_3dm_pps_source_command_source self); -void extract_mip_3dm_pps_source_command_source(struct mip_serializer* serializer, mip_3dm_pps_source_command_source* self); +void insert_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, const mip_3dm_pps_source_command_source self); +void extract_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, mip_3dm_pps_source_command_source* self); struct mip_3dm_pps_source_response { @@ -1079,8 +1078,8 @@ struct mip_3dm_pps_source_response }; typedef struct mip_3dm_pps_source_response mip_3dm_pps_source_response; -void insert_mip_3dm_pps_source_response(struct mip_serializer* serializer, const mip_3dm_pps_source_response* self); -void extract_mip_3dm_pps_source_response(struct mip_serializer* serializer, mip_3dm_pps_source_response* self); +void insert_mip_3dm_pps_source_response(microstrain_serializer* serializer, const mip_3dm_pps_source_response* self); +void extract_mip_3dm_pps_source_response(microstrain_serializer* serializer, mip_3dm_pps_source_response* self); mip_cmd_result mip_3dm_write_pps_source(struct mip_interface* device, mip_3dm_pps_source_command_source source); mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps_source_command_source* source_out); @@ -1154,17 +1153,17 @@ struct mip_3dm_gpio_config_command }; typedef struct mip_3dm_gpio_config_command mip_3dm_gpio_config_command; -void insert_mip_3dm_gpio_config_command(struct mip_serializer* serializer, const mip_3dm_gpio_config_command* self); -void extract_mip_3dm_gpio_config_command(struct mip_serializer* serializer, mip_3dm_gpio_config_command* self); +void insert_mip_3dm_gpio_config_command(microstrain_serializer* serializer, const mip_3dm_gpio_config_command* self); +void extract_mip_3dm_gpio_config_command(microstrain_serializer* serializer, mip_3dm_gpio_config_command* self); -void insert_mip_3dm_gpio_config_command_feature(struct mip_serializer* serializer, const mip_3dm_gpio_config_command_feature self); -void extract_mip_3dm_gpio_config_command_feature(struct mip_serializer* serializer, mip_3dm_gpio_config_command_feature* self); +void insert_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_feature self); +void extract_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, mip_3dm_gpio_config_command_feature* self); -void insert_mip_3dm_gpio_config_command_behavior(struct mip_serializer* serializer, const mip_3dm_gpio_config_command_behavior self); -void extract_mip_3dm_gpio_config_command_behavior(struct mip_serializer* serializer, mip_3dm_gpio_config_command_behavior* self); +void insert_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_behavior self); +void extract_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, mip_3dm_gpio_config_command_behavior* self); -void insert_mip_3dm_gpio_config_command_pin_mode(struct mip_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self); -void extract_mip_3dm_gpio_config_command_pin_mode(struct mip_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self); +void insert_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self); +void extract_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self); struct mip_3dm_gpio_config_response { @@ -1175,8 +1174,8 @@ struct mip_3dm_gpio_config_response }; typedef struct mip_3dm_gpio_config_response mip_3dm_gpio_config_response; -void insert_mip_3dm_gpio_config_response(struct mip_serializer* serializer, const mip_3dm_gpio_config_response* self); -void extract_mip_3dm_gpio_config_response(struct mip_serializer* serializer, mip_3dm_gpio_config_response* self); +void insert_mip_3dm_gpio_config_response(microstrain_serializer* serializer, const mip_3dm_gpio_config_response* self); +void extract_mip_3dm_gpio_config_response(microstrain_serializer* serializer, mip_3dm_gpio_config_response* self); mip_cmd_result mip_3dm_write_gpio_config(struct mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature feature, mip_3dm_gpio_config_command_behavior behavior, mip_3dm_gpio_config_command_pin_mode pin_mode); mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature* feature_out, mip_3dm_gpio_config_command_behavior* behavior_out, mip_3dm_gpio_config_command_pin_mode* pin_mode_out); @@ -1215,8 +1214,8 @@ struct mip_3dm_gpio_state_command }; typedef struct mip_3dm_gpio_state_command mip_3dm_gpio_state_command; -void insert_mip_3dm_gpio_state_command(struct mip_serializer* serializer, const mip_3dm_gpio_state_command* self); -void extract_mip_3dm_gpio_state_command(struct mip_serializer* serializer, mip_3dm_gpio_state_command* self); +void insert_mip_3dm_gpio_state_command(microstrain_serializer* serializer, const mip_3dm_gpio_state_command* self); +void extract_mip_3dm_gpio_state_command(microstrain_serializer* serializer, mip_3dm_gpio_state_command* self); struct mip_3dm_gpio_state_response { @@ -1225,8 +1224,8 @@ struct mip_3dm_gpio_state_response }; typedef struct mip_3dm_gpio_state_response mip_3dm_gpio_state_response; -void insert_mip_3dm_gpio_state_response(struct mip_serializer* serializer, const mip_3dm_gpio_state_response* self); -void extract_mip_3dm_gpio_state_response(struct mip_serializer* serializer, mip_3dm_gpio_state_response* self); +void insert_mip_3dm_gpio_state_response(microstrain_serializer* serializer, const mip_3dm_gpio_state_response* self); +void extract_mip_3dm_gpio_state_response(microstrain_serializer* serializer, mip_3dm_gpio_state_response* self); mip_cmd_result mip_3dm_write_gpio_state(struct mip_interface* device, uint8_t pin, bool state); mip_cmd_result mip_3dm_read_gpio_state(struct mip_interface* device, uint8_t pin, bool* state_out); @@ -1253,11 +1252,11 @@ struct mip_3dm_odometer_command }; typedef struct mip_3dm_odometer_command mip_3dm_odometer_command; -void insert_mip_3dm_odometer_command(struct mip_serializer* serializer, const mip_3dm_odometer_command* self); -void extract_mip_3dm_odometer_command(struct mip_serializer* serializer, mip_3dm_odometer_command* self); +void insert_mip_3dm_odometer_command(microstrain_serializer* serializer, const mip_3dm_odometer_command* self); +void extract_mip_3dm_odometer_command(microstrain_serializer* serializer, mip_3dm_odometer_command* self); -void insert_mip_3dm_odometer_command_mode(struct mip_serializer* serializer, const mip_3dm_odometer_command_mode self); -void extract_mip_3dm_odometer_command_mode(struct mip_serializer* serializer, mip_3dm_odometer_command_mode* self); +void insert_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, const mip_3dm_odometer_command_mode self); +void extract_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, mip_3dm_odometer_command_mode* self); struct mip_3dm_odometer_response { @@ -1267,8 +1266,8 @@ struct mip_3dm_odometer_response }; typedef struct mip_3dm_odometer_response mip_3dm_odometer_response; -void insert_mip_3dm_odometer_response(struct mip_serializer* serializer, const mip_3dm_odometer_response* self); -void extract_mip_3dm_odometer_response(struct mip_serializer* serializer, mip_3dm_odometer_response* self); +void insert_mip_3dm_odometer_response(microstrain_serializer* serializer, const mip_3dm_odometer_response* self); +void extract_mip_3dm_odometer_response(microstrain_serializer* serializer, mip_3dm_odometer_response* self); mip_cmd_result mip_3dm_write_odometer(struct mip_interface* device, mip_3dm_odometer_command_mode mode, float scaling, float uncertainty); mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odometer_command_mode* mode_out, float* scaling_out, float* uncertainty_out); @@ -1317,14 +1316,14 @@ struct mip_3dm_get_event_support_command }; typedef struct mip_3dm_get_event_support_command mip_3dm_get_event_support_command; -void insert_mip_3dm_get_event_support_command(struct mip_serializer* serializer, const mip_3dm_get_event_support_command* self); -void extract_mip_3dm_get_event_support_command(struct mip_serializer* serializer, mip_3dm_get_event_support_command* self); +void insert_mip_3dm_get_event_support_command(microstrain_serializer* serializer, const mip_3dm_get_event_support_command* self); +void extract_mip_3dm_get_event_support_command(microstrain_serializer* serializer, mip_3dm_get_event_support_command* self); -void insert_mip_3dm_get_event_support_command_query(struct mip_serializer* serializer, const mip_3dm_get_event_support_command_query self); -void extract_mip_3dm_get_event_support_command_query(struct mip_serializer* serializer, mip_3dm_get_event_support_command_query* self); +void insert_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_query self); +void extract_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, mip_3dm_get_event_support_command_query* self); -void insert_mip_3dm_get_event_support_command_info(struct mip_serializer* serializer, const mip_3dm_get_event_support_command_info* self); -void extract_mip_3dm_get_event_support_command_info(struct mip_serializer* serializer, mip_3dm_get_event_support_command_info* self); +void insert_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_info* self); +void extract_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, mip_3dm_get_event_support_command_info* self); struct mip_3dm_get_event_support_response { @@ -1335,8 +1334,8 @@ struct mip_3dm_get_event_support_response }; typedef struct mip_3dm_get_event_support_response mip_3dm_get_event_support_response; -void insert_mip_3dm_get_event_support_response(struct mip_serializer* serializer, const mip_3dm_get_event_support_response* self); -void extract_mip_3dm_get_event_support_response(struct mip_serializer* serializer, mip_3dm_get_event_support_response* self); +void insert_mip_3dm_get_event_support_response(microstrain_serializer* serializer, const mip_3dm_get_event_support_response* self); +void extract_mip_3dm_get_event_support_response(microstrain_serializer* serializer, mip_3dm_get_event_support_response* self); mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_get_event_support_command_query query, uint8_t* max_instances_out, uint8_t* num_entries_out, uint8_t num_entries_out_max, mip_3dm_get_event_support_command_info* entries_out); @@ -1371,11 +1370,11 @@ struct mip_3dm_event_control_command }; typedef struct mip_3dm_event_control_command mip_3dm_event_control_command; -void insert_mip_3dm_event_control_command(struct mip_serializer* serializer, const mip_3dm_event_control_command* self); -void extract_mip_3dm_event_control_command(struct mip_serializer* serializer, mip_3dm_event_control_command* self); +void insert_mip_3dm_event_control_command(microstrain_serializer* serializer, const mip_3dm_event_control_command* self); +void extract_mip_3dm_event_control_command(microstrain_serializer* serializer, mip_3dm_event_control_command* self); -void insert_mip_3dm_event_control_command_mode(struct mip_serializer* serializer, const mip_3dm_event_control_command_mode self); -void extract_mip_3dm_event_control_command_mode(struct mip_serializer* serializer, mip_3dm_event_control_command_mode* self); +void insert_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, const mip_3dm_event_control_command_mode self); +void extract_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, mip_3dm_event_control_command_mode* self); struct mip_3dm_event_control_response { @@ -1384,8 +1383,8 @@ struct mip_3dm_event_control_response }; typedef struct mip_3dm_event_control_response mip_3dm_event_control_response; -void insert_mip_3dm_event_control_response(struct mip_serializer* serializer, const mip_3dm_event_control_response* self); -void extract_mip_3dm_event_control_response(struct mip_serializer* serializer, mip_3dm_event_control_response* self); +void insert_mip_3dm_event_control_response(microstrain_serializer* serializer, const mip_3dm_event_control_response* self); +void extract_mip_3dm_event_control_response(microstrain_serializer* serializer, mip_3dm_event_control_response* self); mip_cmd_result mip_3dm_write_event_control(struct mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode mode); mip_cmd_result mip_3dm_read_event_control(struct mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode* mode_out); @@ -1421,14 +1420,14 @@ struct mip_3dm_get_event_trigger_status_command }; typedef struct mip_3dm_get_event_trigger_status_command mip_3dm_get_event_trigger_status_command; -void insert_mip_3dm_get_event_trigger_status_command(struct mip_serializer* serializer, const mip_3dm_get_event_trigger_status_command* self); -void extract_mip_3dm_get_event_trigger_status_command(struct mip_serializer* serializer, mip_3dm_get_event_trigger_status_command* self); +void insert_mip_3dm_get_event_trigger_status_command(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command* self); +void extract_mip_3dm_get_event_trigger_status_command(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command* self); -void insert_mip_3dm_get_event_trigger_status_command_status(struct mip_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self); -void extract_mip_3dm_get_event_trigger_status_command_status(struct mip_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self); +void insert_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self); +void extract_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self); -void insert_mip_3dm_get_event_trigger_status_command_entry(struct mip_serializer* serializer, const mip_3dm_get_event_trigger_status_command_entry* self); -void extract_mip_3dm_get_event_trigger_status_command_entry(struct mip_serializer* serializer, mip_3dm_get_event_trigger_status_command_entry* self); +void insert_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_entry* self); +void extract_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_entry* self); struct mip_3dm_get_event_trigger_status_response { @@ -1437,8 +1436,8 @@ struct mip_3dm_get_event_trigger_status_response }; typedef struct mip_3dm_get_event_trigger_status_response mip_3dm_get_event_trigger_status_response; -void insert_mip_3dm_get_event_trigger_status_response(struct mip_serializer* serializer, const mip_3dm_get_event_trigger_status_response* self); -void extract_mip_3dm_get_event_trigger_status_response(struct mip_serializer* serializer, mip_3dm_get_event_trigger_status_response* self); +void insert_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_response* self); +void extract_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_response* self); mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_trigger_status_command_entry* triggers_out); @@ -1463,11 +1462,11 @@ struct mip_3dm_get_event_action_status_command }; typedef struct mip_3dm_get_event_action_status_command mip_3dm_get_event_action_status_command; -void insert_mip_3dm_get_event_action_status_command(struct mip_serializer* serializer, const mip_3dm_get_event_action_status_command* self); -void extract_mip_3dm_get_event_action_status_command(struct mip_serializer* serializer, mip_3dm_get_event_action_status_command* self); +void insert_mip_3dm_get_event_action_status_command(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command* self); +void extract_mip_3dm_get_event_action_status_command(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command* self); -void insert_mip_3dm_get_event_action_status_command_entry(struct mip_serializer* serializer, const mip_3dm_get_event_action_status_command_entry* self); -void extract_mip_3dm_get_event_action_status_command_entry(struct mip_serializer* serializer, mip_3dm_get_event_action_status_command_entry* self); +void insert_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command_entry* self); +void extract_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command_entry* self); struct mip_3dm_get_event_action_status_response { @@ -1476,8 +1475,8 @@ struct mip_3dm_get_event_action_status_response }; typedef struct mip_3dm_get_event_action_status_response mip_3dm_get_event_action_status_response; -void insert_mip_3dm_get_event_action_status_response(struct mip_serializer* serializer, const mip_3dm_get_event_action_status_response* self); -void extract_mip_3dm_get_event_action_status_response(struct mip_serializer* serializer, mip_3dm_get_event_action_status_response* self); +void insert_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_response* self); +void extract_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, mip_3dm_get_event_action_status_response* self); mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_action_status_command_entry* actions_out); @@ -1568,26 +1567,26 @@ struct mip_3dm_event_trigger_command }; typedef struct mip_3dm_event_trigger_command mip_3dm_event_trigger_command; -void insert_mip_3dm_event_trigger_command(struct mip_serializer* serializer, const mip_3dm_event_trigger_command* self); -void extract_mip_3dm_event_trigger_command(struct mip_serializer* serializer, mip_3dm_event_trigger_command* self); +void insert_mip_3dm_event_trigger_command(microstrain_serializer* serializer, const mip_3dm_event_trigger_command* self); +void extract_mip_3dm_event_trigger_command(microstrain_serializer* serializer, mip_3dm_event_trigger_command* self); -void insert_mip_3dm_event_trigger_command_gpio_params(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params* self); -void extract_mip_3dm_event_trigger_command_gpio_params(struct mip_serializer* serializer, mip_3dm_event_trigger_command_gpio_params* self); +void insert_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params* self); +void extract_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params* self); -void insert_mip_3dm_event_trigger_command_gpio_params_mode(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self); -void extract_mip_3dm_event_trigger_command_gpio_params_mode(struct mip_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self); +void insert_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self); +void extract_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self); -void insert_mip_3dm_event_trigger_command_threshold_params(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params* self); -void extract_mip_3dm_event_trigger_command_threshold_params(struct mip_serializer* serializer, mip_3dm_event_trigger_command_threshold_params* self); +void insert_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params* self); +void extract_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params* self); -void insert_mip_3dm_event_trigger_command_threshold_params_type(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self); -void extract_mip_3dm_event_trigger_command_threshold_params_type(struct mip_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self); +void insert_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self); +void extract_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self); -void insert_mip_3dm_event_trigger_command_combination_params(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_combination_params* self); -void extract_mip_3dm_event_trigger_command_combination_params(struct mip_serializer* serializer, mip_3dm_event_trigger_command_combination_params* self); +void insert_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_combination_params* self); +void extract_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_combination_params* self); -void insert_mip_3dm_event_trigger_command_type(struct mip_serializer* serializer, const mip_3dm_event_trigger_command_type self); -void extract_mip_3dm_event_trigger_command_type(struct mip_serializer* serializer, mip_3dm_event_trigger_command_type* self); +void insert_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_type self); +void extract_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_type* self); struct mip_3dm_event_trigger_response { @@ -1597,8 +1596,8 @@ struct mip_3dm_event_trigger_response }; typedef struct mip_3dm_event_trigger_response mip_3dm_event_trigger_response; -void insert_mip_3dm_event_trigger_response(struct mip_serializer* serializer, const mip_3dm_event_trigger_response* self); -void extract_mip_3dm_event_trigger_response(struct mip_serializer* serializer, mip_3dm_event_trigger_response* self); +void insert_mip_3dm_event_trigger_response(microstrain_serializer* serializer, const mip_3dm_event_trigger_response* self); +void extract_mip_3dm_event_trigger_response(microstrain_serializer* serializer, mip_3dm_event_trigger_response* self); mip_cmd_result mip_3dm_write_event_trigger(struct mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type type, const mip_3dm_event_trigger_command_parameters* parameters); mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type* type_out, mip_3dm_event_trigger_command_parameters* parameters_out); @@ -1660,20 +1659,20 @@ struct mip_3dm_event_action_command }; typedef struct mip_3dm_event_action_command mip_3dm_event_action_command; -void insert_mip_3dm_event_action_command(struct mip_serializer* serializer, const mip_3dm_event_action_command* self); -void extract_mip_3dm_event_action_command(struct mip_serializer* serializer, mip_3dm_event_action_command* self); +void insert_mip_3dm_event_action_command(microstrain_serializer* serializer, const mip_3dm_event_action_command* self); +void extract_mip_3dm_event_action_command(microstrain_serializer* serializer, mip_3dm_event_action_command* self); -void insert_mip_3dm_event_action_command_gpio_params(struct mip_serializer* serializer, const mip_3dm_event_action_command_gpio_params* self); -void extract_mip_3dm_event_action_command_gpio_params(struct mip_serializer* serializer, mip_3dm_event_action_command_gpio_params* self); +void insert_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params* self); +void extract_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params* self); -void insert_mip_3dm_event_action_command_gpio_params_mode(struct mip_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self); -void extract_mip_3dm_event_action_command_gpio_params_mode(struct mip_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self); +void insert_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self); +void extract_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self); -void insert_mip_3dm_event_action_command_message_params(struct mip_serializer* serializer, const mip_3dm_event_action_command_message_params* self); -void extract_mip_3dm_event_action_command_message_params(struct mip_serializer* serializer, mip_3dm_event_action_command_message_params* self); +void insert_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_message_params* self); +void extract_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, mip_3dm_event_action_command_message_params* self); -void insert_mip_3dm_event_action_command_type(struct mip_serializer* serializer, const mip_3dm_event_action_command_type self); -void extract_mip_3dm_event_action_command_type(struct mip_serializer* serializer, mip_3dm_event_action_command_type* self); +void insert_mip_3dm_event_action_command_type(microstrain_serializer* serializer, const mip_3dm_event_action_command_type self); +void extract_mip_3dm_event_action_command_type(microstrain_serializer* serializer, mip_3dm_event_action_command_type* self); struct mip_3dm_event_action_response { @@ -1684,8 +1683,8 @@ struct mip_3dm_event_action_response }; typedef struct mip_3dm_event_action_response mip_3dm_event_action_response; -void insert_mip_3dm_event_action_response(struct mip_serializer* serializer, const mip_3dm_event_action_response* self); -void extract_mip_3dm_event_action_response(struct mip_serializer* serializer, mip_3dm_event_action_response* self); +void insert_mip_3dm_event_action_response(microstrain_serializer* serializer, const mip_3dm_event_action_response* self); +void extract_mip_3dm_event_action_response(microstrain_serializer* serializer, mip_3dm_event_action_response* self); mip_cmd_result mip_3dm_write_event_action(struct mip_interface* device, uint8_t instance, uint8_t trigger, mip_3dm_event_action_command_type type, const mip_3dm_event_action_command_parameters* parameters); mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t instance, uint8_t* trigger_out, mip_3dm_event_action_command_type* type_out, mip_3dm_event_action_command_parameters* parameters_out); @@ -1710,8 +1709,8 @@ struct mip_3dm_accel_bias_command }; typedef struct mip_3dm_accel_bias_command mip_3dm_accel_bias_command; -void insert_mip_3dm_accel_bias_command(struct mip_serializer* serializer, const mip_3dm_accel_bias_command* self); -void extract_mip_3dm_accel_bias_command(struct mip_serializer* serializer, mip_3dm_accel_bias_command* self); +void insert_mip_3dm_accel_bias_command(microstrain_serializer* serializer, const mip_3dm_accel_bias_command* self); +void extract_mip_3dm_accel_bias_command(microstrain_serializer* serializer, mip_3dm_accel_bias_command* self); struct mip_3dm_accel_bias_response { @@ -1719,8 +1718,8 @@ struct mip_3dm_accel_bias_response }; typedef struct mip_3dm_accel_bias_response mip_3dm_accel_bias_response; -void insert_mip_3dm_accel_bias_response(struct mip_serializer* serializer, const mip_3dm_accel_bias_response* self); -void extract_mip_3dm_accel_bias_response(struct mip_serializer* serializer, mip_3dm_accel_bias_response* self); +void insert_mip_3dm_accel_bias_response(microstrain_serializer* serializer, const mip_3dm_accel_bias_response* self); +void extract_mip_3dm_accel_bias_response(microstrain_serializer* serializer, mip_3dm_accel_bias_response* self); mip_cmd_result mip_3dm_write_accel_bias(struct mip_interface* device, const float* bias); mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias_out); @@ -1745,8 +1744,8 @@ struct mip_3dm_gyro_bias_command }; typedef struct mip_3dm_gyro_bias_command mip_3dm_gyro_bias_command; -void insert_mip_3dm_gyro_bias_command(struct mip_serializer* serializer, const mip_3dm_gyro_bias_command* self); -void extract_mip_3dm_gyro_bias_command(struct mip_serializer* serializer, mip_3dm_gyro_bias_command* self); +void insert_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, const mip_3dm_gyro_bias_command* self); +void extract_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, mip_3dm_gyro_bias_command* self); struct mip_3dm_gyro_bias_response { @@ -1754,8 +1753,8 @@ struct mip_3dm_gyro_bias_response }; typedef struct mip_3dm_gyro_bias_response mip_3dm_gyro_bias_response; -void insert_mip_3dm_gyro_bias_response(struct mip_serializer* serializer, const mip_3dm_gyro_bias_response* self); -void extract_mip_3dm_gyro_bias_response(struct mip_serializer* serializer, mip_3dm_gyro_bias_response* self); +void insert_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_gyro_bias_response* self); +void extract_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_gyro_bias_response* self); mip_cmd_result mip_3dm_write_gyro_bias(struct mip_interface* device, const float* bias); mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_out); @@ -1782,8 +1781,8 @@ struct mip_3dm_capture_gyro_bias_command }; typedef struct mip_3dm_capture_gyro_bias_command mip_3dm_capture_gyro_bias_command; -void insert_mip_3dm_capture_gyro_bias_command(struct mip_serializer* serializer, const mip_3dm_capture_gyro_bias_command* self); -void extract_mip_3dm_capture_gyro_bias_command(struct mip_serializer* serializer, mip_3dm_capture_gyro_bias_command* self); +void insert_mip_3dm_capture_gyro_bias_command(microstrain_serializer* serializer, const mip_3dm_capture_gyro_bias_command* self); +void extract_mip_3dm_capture_gyro_bias_command(microstrain_serializer* serializer, mip_3dm_capture_gyro_bias_command* self); struct mip_3dm_capture_gyro_bias_response { @@ -1791,8 +1790,8 @@ struct mip_3dm_capture_gyro_bias_response }; typedef struct mip_3dm_capture_gyro_bias_response mip_3dm_capture_gyro_bias_response; -void insert_mip_3dm_capture_gyro_bias_response(struct mip_serializer* serializer, const mip_3dm_capture_gyro_bias_response* self); -void extract_mip_3dm_capture_gyro_bias_response(struct mip_serializer* serializer, mip_3dm_capture_gyro_bias_response* self); +void insert_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_capture_gyro_bias_response* self); +void extract_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_capture_gyro_bias_response* self); mip_cmd_result mip_3dm_capture_gyro_bias(struct mip_interface* device, uint16_t averaging_time_ms, float* bias_out); @@ -1817,8 +1816,8 @@ struct mip_3dm_mag_hard_iron_offset_command }; typedef struct mip_3dm_mag_hard_iron_offset_command mip_3dm_mag_hard_iron_offset_command; -void insert_mip_3dm_mag_hard_iron_offset_command(struct mip_serializer* serializer, const mip_3dm_mag_hard_iron_offset_command* self); -void extract_mip_3dm_mag_hard_iron_offset_command(struct mip_serializer* serializer, mip_3dm_mag_hard_iron_offset_command* self); +void insert_mip_3dm_mag_hard_iron_offset_command(microstrain_serializer* serializer, const mip_3dm_mag_hard_iron_offset_command* self); +void extract_mip_3dm_mag_hard_iron_offset_command(microstrain_serializer* serializer, mip_3dm_mag_hard_iron_offset_command* self); struct mip_3dm_mag_hard_iron_offset_response { @@ -1826,8 +1825,8 @@ struct mip_3dm_mag_hard_iron_offset_response }; typedef struct mip_3dm_mag_hard_iron_offset_response mip_3dm_mag_hard_iron_offset_response; -void insert_mip_3dm_mag_hard_iron_offset_response(struct mip_serializer* serializer, const mip_3dm_mag_hard_iron_offset_response* self); -void extract_mip_3dm_mag_hard_iron_offset_response(struct mip_serializer* serializer, mip_3dm_mag_hard_iron_offset_response* self); +void insert_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, const mip_3dm_mag_hard_iron_offset_response* self); +void extract_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, mip_3dm_mag_hard_iron_offset_response* self); mip_cmd_result mip_3dm_write_mag_hard_iron_offset(struct mip_interface* device, const float* offset); mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, float* offset_out); @@ -1860,8 +1859,8 @@ struct mip_3dm_mag_soft_iron_matrix_command }; typedef struct mip_3dm_mag_soft_iron_matrix_command mip_3dm_mag_soft_iron_matrix_command; -void insert_mip_3dm_mag_soft_iron_matrix_command(struct mip_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_command* self); -void extract_mip_3dm_mag_soft_iron_matrix_command(struct mip_serializer* serializer, mip_3dm_mag_soft_iron_matrix_command* self); +void insert_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_command* self); +void extract_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* serializer, mip_3dm_mag_soft_iron_matrix_command* self); struct mip_3dm_mag_soft_iron_matrix_response { @@ -1869,8 +1868,8 @@ struct mip_3dm_mag_soft_iron_matrix_response }; typedef struct mip_3dm_mag_soft_iron_matrix_response mip_3dm_mag_soft_iron_matrix_response; -void insert_mip_3dm_mag_soft_iron_matrix_response(struct mip_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_response* self); -void extract_mip_3dm_mag_soft_iron_matrix_response(struct mip_serializer* serializer, mip_3dm_mag_soft_iron_matrix_response* self); +void insert_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_response* self); +void extract_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, mip_3dm_mag_soft_iron_matrix_response* self); mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(struct mip_interface* device, const float* offset); mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, float* offset_out); @@ -1893,8 +1892,8 @@ struct mip_3dm_coning_sculling_enable_command }; typedef struct mip_3dm_coning_sculling_enable_command mip_3dm_coning_sculling_enable_command; -void insert_mip_3dm_coning_sculling_enable_command(struct mip_serializer* serializer, const mip_3dm_coning_sculling_enable_command* self); -void extract_mip_3dm_coning_sculling_enable_command(struct mip_serializer* serializer, mip_3dm_coning_sculling_enable_command* self); +void insert_mip_3dm_coning_sculling_enable_command(microstrain_serializer* serializer, const mip_3dm_coning_sculling_enable_command* self); +void extract_mip_3dm_coning_sculling_enable_command(microstrain_serializer* serializer, mip_3dm_coning_sculling_enable_command* self); struct mip_3dm_coning_sculling_enable_response { @@ -1902,8 +1901,8 @@ struct mip_3dm_coning_sculling_enable_response }; typedef struct mip_3dm_coning_sculling_enable_response mip_3dm_coning_sculling_enable_response; -void insert_mip_3dm_coning_sculling_enable_response(struct mip_serializer* serializer, const mip_3dm_coning_sculling_enable_response* self); -void extract_mip_3dm_coning_sculling_enable_response(struct mip_serializer* serializer, mip_3dm_coning_sculling_enable_response* self); +void insert_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, const mip_3dm_coning_sculling_enable_response* self); +void extract_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, mip_3dm_coning_sculling_enable_response* self); mip_cmd_result mip_3dm_write_coning_sculling_enable(struct mip_interface* device, bool enable); mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, bool* enable_out); @@ -1952,8 +1951,8 @@ struct mip_3dm_sensor_2_vehicle_transform_euler_command }; typedef struct mip_3dm_sensor_2_vehicle_transform_euler_command mip_3dm_sensor_2_vehicle_transform_euler_command; -void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(struct mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_command* self); -void extract_mip_3dm_sensor_2_vehicle_transform_euler_command(struct mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_command* self); +void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_command* self); +void extract_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_command* self); struct mip_3dm_sensor_2_vehicle_transform_euler_response { @@ -1963,8 +1962,8 @@ struct mip_3dm_sensor_2_vehicle_transform_euler_response }; typedef struct mip_3dm_sensor_2_vehicle_transform_euler_response mip_3dm_sensor_2_vehicle_transform_euler_response; -void insert_mip_3dm_sensor_2_vehicle_transform_euler_response(struct mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_response* self); -void extract_mip_3dm_sensor_2_vehicle_transform_euler_response(struct mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_response* self); +void insert_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_response* self); +void extract_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_response* self); mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_euler(struct mip_interface* device, float roll, float pitch, float yaw); mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out); @@ -2019,8 +2018,8 @@ struct mip_3dm_sensor_2_vehicle_transform_quaternion_command }; typedef struct mip_3dm_sensor_2_vehicle_transform_quaternion_command mip_3dm_sensor_2_vehicle_transform_quaternion_command; -void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(struct mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_command* self); -void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(struct mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_command* self); +void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_command* self); +void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_command* self); struct mip_3dm_sensor_2_vehicle_transform_quaternion_response { @@ -2028,8 +2027,8 @@ struct mip_3dm_sensor_2_vehicle_transform_quaternion_response }; typedef struct mip_3dm_sensor_2_vehicle_transform_quaternion_response mip_3dm_sensor_2_vehicle_transform_quaternion_response; -void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_response(struct mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_response* self); -void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_response(struct mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_response* self); +void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_response* self); +void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_response* self); mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(struct mip_interface* device, const float* q); mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_interface* device, float* q_out); @@ -2082,8 +2081,8 @@ struct mip_3dm_sensor_2_vehicle_transform_dcm_command }; typedef struct mip_3dm_sensor_2_vehicle_transform_dcm_command mip_3dm_sensor_2_vehicle_transform_dcm_command; -void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(struct mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_command* self); -void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(struct mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_command* self); +void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_command* self); +void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_command* self); struct mip_3dm_sensor_2_vehicle_transform_dcm_response { @@ -2091,8 +2090,8 @@ struct mip_3dm_sensor_2_vehicle_transform_dcm_response }; typedef struct mip_3dm_sensor_2_vehicle_transform_dcm_response mip_3dm_sensor_2_vehicle_transform_dcm_response; -void insert_mip_3dm_sensor_2_vehicle_transform_dcm_response(struct mip_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_response* self); -void extract_mip_3dm_sensor_2_vehicle_transform_dcm_response(struct mip_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_response* self); +void insert_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_response* self); +void extract_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_response* self); mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(struct mip_interface* device, const float* dcm); mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* device, float* dcm_out); @@ -2122,8 +2121,8 @@ struct mip_3dm_complementary_filter_command }; typedef struct mip_3dm_complementary_filter_command mip_3dm_complementary_filter_command; -void insert_mip_3dm_complementary_filter_command(struct mip_serializer* serializer, const mip_3dm_complementary_filter_command* self); -void extract_mip_3dm_complementary_filter_command(struct mip_serializer* serializer, mip_3dm_complementary_filter_command* self); +void insert_mip_3dm_complementary_filter_command(microstrain_serializer* serializer, const mip_3dm_complementary_filter_command* self); +void extract_mip_3dm_complementary_filter_command(microstrain_serializer* serializer, mip_3dm_complementary_filter_command* self); struct mip_3dm_complementary_filter_response { @@ -2134,8 +2133,8 @@ struct mip_3dm_complementary_filter_response }; typedef struct mip_3dm_complementary_filter_response mip_3dm_complementary_filter_response; -void insert_mip_3dm_complementary_filter_response(struct mip_serializer* serializer, const mip_3dm_complementary_filter_response* self); -void extract_mip_3dm_complementary_filter_response(struct mip_serializer* serializer, mip_3dm_complementary_filter_response* self); +void insert_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, const mip_3dm_complementary_filter_response* self); +void extract_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, mip_3dm_complementary_filter_response* self); mip_cmd_result mip_3dm_write_complementary_filter(struct mip_interface* device, bool pitch_roll_enable, bool heading_enable, float pitch_roll_time_constant, float heading_time_constant); mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, bool* pitch_roll_enable_out, bool* heading_enable_out, float* pitch_roll_time_constant_out, float* heading_time_constant_out); @@ -2166,8 +2165,8 @@ struct mip_3dm_sensor_range_command }; typedef struct mip_3dm_sensor_range_command mip_3dm_sensor_range_command; -void insert_mip_3dm_sensor_range_command(struct mip_serializer* serializer, const mip_3dm_sensor_range_command* self); -void extract_mip_3dm_sensor_range_command(struct mip_serializer* serializer, mip_3dm_sensor_range_command* self); +void insert_mip_3dm_sensor_range_command(microstrain_serializer* serializer, const mip_3dm_sensor_range_command* self); +void extract_mip_3dm_sensor_range_command(microstrain_serializer* serializer, mip_3dm_sensor_range_command* self); struct mip_3dm_sensor_range_response { @@ -2176,8 +2175,8 @@ struct mip_3dm_sensor_range_response }; typedef struct mip_3dm_sensor_range_response mip_3dm_sensor_range_response; -void insert_mip_3dm_sensor_range_response(struct mip_serializer* serializer, const mip_3dm_sensor_range_response* self); -void extract_mip_3dm_sensor_range_response(struct mip_serializer* serializer, mip_3dm_sensor_range_response* self); +void insert_mip_3dm_sensor_range_response(microstrain_serializer* serializer, const mip_3dm_sensor_range_response* self); +void extract_mip_3dm_sensor_range_response(microstrain_serializer* serializer, mip_3dm_sensor_range_response* self); mip_cmd_result mip_3dm_write_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t setting); mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t* setting_out); @@ -2209,11 +2208,11 @@ struct mip_3dm_calibrated_sensor_ranges_command }; typedef struct mip_3dm_calibrated_sensor_ranges_command mip_3dm_calibrated_sensor_ranges_command; -void insert_mip_3dm_calibrated_sensor_ranges_command(struct mip_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command* self); -void extract_mip_3dm_calibrated_sensor_ranges_command(struct mip_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command* self); +void insert_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command* self); +void extract_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command* self); -void insert_mip_3dm_calibrated_sensor_ranges_command_entry(struct mip_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command_entry* self); -void extract_mip_3dm_calibrated_sensor_ranges_command_entry(struct mip_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command_entry* self); +void insert_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command_entry* self); +void extract_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command_entry* self); struct mip_3dm_calibrated_sensor_ranges_response { @@ -2223,8 +2222,8 @@ struct mip_3dm_calibrated_sensor_ranges_response }; typedef struct mip_3dm_calibrated_sensor_ranges_response mip_3dm_calibrated_sensor_ranges_response; -void insert_mip_3dm_calibrated_sensor_ranges_response(struct mip_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_response* self); -void extract_mip_3dm_calibrated_sensor_ranges_response(struct mip_serializer* serializer, mip_3dm_calibrated_sensor_ranges_response* self); +void insert_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_response* self); +void extract_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_response* self); mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t* num_ranges_out, uint8_t num_ranges_out_max, mip_3dm_calibrated_sensor_ranges_command_entry* ranges_out); @@ -2260,8 +2259,8 @@ struct mip_3dm_lowpass_filter_command }; typedef struct mip_3dm_lowpass_filter_command mip_3dm_lowpass_filter_command; -void insert_mip_3dm_lowpass_filter_command(struct mip_serializer* serializer, const mip_3dm_lowpass_filter_command* self); -void extract_mip_3dm_lowpass_filter_command(struct mip_serializer* serializer, mip_3dm_lowpass_filter_command* self); +void insert_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, const mip_3dm_lowpass_filter_command* self); +void extract_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, mip_3dm_lowpass_filter_command* self); struct mip_3dm_lowpass_filter_response { @@ -2273,8 +2272,8 @@ struct mip_3dm_lowpass_filter_response }; typedef struct mip_3dm_lowpass_filter_response mip_3dm_lowpass_filter_response; -void insert_mip_3dm_lowpass_filter_response(struct mip_serializer* serializer, const mip_3dm_lowpass_filter_response* self); -void extract_mip_3dm_lowpass_filter_response(struct mip_serializer* serializer, mip_3dm_lowpass_filter_response* self); +void insert_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_lowpass_filter_response* self); +void extract_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_lowpass_filter_response* self); mip_cmd_result mip_3dm_write_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool enable, bool manual, float frequency); mip_cmd_result mip_3dm_read_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool* enable_out, bool* manual_out, float* frequency_out); diff --git a/src/mip/definitions/commands_aiding.c b/src/mip/definitions/commands_aiding.c index c917ce24d..d2750c518 100644 --- a/src/mip/definitions/commands_aiding.c +++ b/src/mip/definitions/commands_aiding.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -22,7 +22,7 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_time(mip_serializer* serializer, const mip_time* self) +void insert_mip_time(microstrain_serializer* serializer, const mip_time* self) { insert_mip_time_timebase(serializer, self->timebase); @@ -31,7 +31,7 @@ void insert_mip_time(mip_serializer* serializer, const mip_time* self) microstrain_insert_u64(serializer, self->nanoseconds); } -void extract_mip_time(mip_serializer* serializer, mip_time* self) +void extract_mip_time(microstrain_serializer* serializer, mip_time* self) { extract_mip_time_timebase(serializer, &self->timebase); @@ -41,11 +41,11 @@ void extract_mip_time(mip_serializer* serializer, mip_time* self) } -void insert_mip_time_timebase(struct mip_serializer* serializer, const mip_time_timebase self) +void insert_mip_time_timebase(struct microstrain_serializer* serializer, const mip_time_timebase self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_time_timebase(struct mip_serializer* serializer, mip_time_timebase* self) +void extract_mip_time_timebase(struct microstrain_serializer* serializer, mip_time_timebase* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -57,7 +57,7 @@ void extract_mip_time_timebase(struct mip_serializer* serializer, mip_time_timeb // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_aiding_frame_config_command(mip_serializer* serializer, const mip_aiding_frame_config_command* self) +void insert_mip_aiding_frame_config_command(microstrain_serializer* serializer, const mip_aiding_frame_config_command* self) { insert_mip_function_selector(serializer, self->function); @@ -87,7 +87,7 @@ void insert_mip_aiding_frame_config_command(mip_serializer* serializer, const mi } } } -void extract_mip_aiding_frame_config_command(mip_serializer* serializer, mip_aiding_frame_config_command* self) +void extract_mip_aiding_frame_config_command(microstrain_serializer* serializer, mip_aiding_frame_config_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -118,7 +118,7 @@ void extract_mip_aiding_frame_config_command(mip_serializer* serializer, mip_aid } } -void insert_mip_aiding_frame_config_response(mip_serializer* serializer, const mip_aiding_frame_config_response* self) +void insert_mip_aiding_frame_config_response(microstrain_serializer* serializer, const mip_aiding_frame_config_response* self) { microstrain_insert_u8(serializer, self->frame_id); @@ -140,7 +140,7 @@ void insert_mip_aiding_frame_config_response(mip_serializer* serializer, const m } } -void extract_mip_aiding_frame_config_response(mip_serializer* serializer, mip_aiding_frame_config_response* self) +void extract_mip_aiding_frame_config_response(microstrain_serializer* serializer, mip_aiding_frame_config_response* self) { microstrain_extract_u8(serializer, &self->frame_id); @@ -163,11 +163,11 @@ void extract_mip_aiding_frame_config_response(mip_serializer* serializer, mip_ai } } -void insert_mip_aiding_frame_config_command_format(struct mip_serializer* serializer, const mip_aiding_frame_config_command_format self) +void insert_mip_aiding_frame_config_command_format(struct microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_aiding_frame_config_command_format(struct mip_serializer* serializer, mip_aiding_frame_config_command_format* self) +void extract_mip_aiding_frame_config_command_format(struct microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -176,9 +176,9 @@ void extract_mip_aiding_frame_config_command_format(struct mip_serializer* seria mip_cmd_result mip_aiding_write_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool tracking_enabled, const float* translation, const mip_aiding_frame_config_command_rotation* rotation) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -209,9 +209,9 @@ mip_cmd_result mip_aiding_write_frame_config(struct mip_interface* device, uint8 } mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool* tracking_enabled_out, float* translation_out, mip_aiding_frame_config_command_rotation* rotation_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -227,8 +227,8 @@ mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_ if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &frame_id); @@ -258,9 +258,9 @@ mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_ } mip_cmd_result mip_aiding_save_frame_config(struct mip_interface* device, uint8_t frame_id) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -273,9 +273,9 @@ mip_cmd_result mip_aiding_save_frame_config(struct mip_interface* device, uint8_ } mip_cmd_result mip_aiding_load_frame_config(struct mip_interface* device, uint8_t frame_id) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -288,9 +288,9 @@ mip_cmd_result mip_aiding_load_frame_config(struct mip_interface* device, uint8_ } mip_cmd_result mip_aiding_default_frame_config(struct mip_interface* device, uint8_t frame_id) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -301,7 +301,7 @@ mip_cmd_result mip_aiding_default_frame_config(struct mip_interface* device, uin return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_aiding_echo_control_command(mip_serializer* serializer, const mip_aiding_aiding_echo_control_command* self) +void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self) { insert_mip_function_selector(serializer, self->function); @@ -311,7 +311,7 @@ void insert_mip_aiding_aiding_echo_control_command(mip_serializer* serializer, c } } -void extract_mip_aiding_aiding_echo_control_command(mip_serializer* serializer, mip_aiding_aiding_echo_control_command* self) +void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -322,22 +322,22 @@ void extract_mip_aiding_aiding_echo_control_command(mip_serializer* serializer, } } -void insert_mip_aiding_aiding_echo_control_response(mip_serializer* serializer, const mip_aiding_aiding_echo_control_response* self) +void insert_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self) { insert_mip_aiding_aiding_echo_control_command_mode(serializer, self->mode); } -void extract_mip_aiding_aiding_echo_control_response(mip_serializer* serializer, mip_aiding_aiding_echo_control_response* self) +void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self) { extract_mip_aiding_aiding_echo_control_command_mode(serializer, &self->mode); } -void insert_mip_aiding_aiding_echo_control_command_mode(struct mip_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) +void insert_mip_aiding_aiding_echo_control_command_mode(struct microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_aiding_aiding_echo_control_command_mode(struct mip_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) +void extract_mip_aiding_aiding_echo_control_command_mode(struct microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -346,9 +346,9 @@ void extract_mip_aiding_aiding_echo_control_command_mode(struct mip_serializer* mip_cmd_result mip_aiding_write_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -361,9 +361,9 @@ mip_cmd_result mip_aiding_write_aiding_echo_control(struct mip_interface* device } mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -375,8 +375,8 @@ mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(mode_out); extract_mip_aiding_aiding_echo_control_command_mode(&deserializer, mode_out); @@ -388,9 +388,9 @@ mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, } mip_cmd_result mip_aiding_save_aiding_echo_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -401,9 +401,9 @@ mip_cmd_result mip_aiding_save_aiding_echo_control(struct mip_interface* device) } mip_cmd_result mip_aiding_load_aiding_echo_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -414,9 +414,9 @@ mip_cmd_result mip_aiding_load_aiding_echo_control(struct mip_interface* device) } mip_cmd_result mip_aiding_default_aiding_echo_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -425,7 +425,7 @@ mip_cmd_result mip_aiding_default_aiding_echo_control(struct mip_interface* devi return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_ecef_pos_command(mip_serializer* serializer, const mip_aiding_ecef_pos_command* self) +void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self) { insert_mip_time(serializer, &self->time); @@ -440,7 +440,7 @@ void insert_mip_aiding_ecef_pos_command(mip_serializer* serializer, const mip_ai insert_mip_aiding_ecef_pos_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_ecef_pos_command(mip_serializer* serializer, mip_aiding_ecef_pos_command* self) +void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self) { extract_mip_time(serializer, &self->time); @@ -456,11 +456,11 @@ void extract_mip_aiding_ecef_pos_command(mip_serializer* serializer, mip_aiding_ } -void insert_mip_aiding_ecef_pos_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) +void insert_mip_aiding_ecef_pos_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_ecef_pos_command_valid_flags(struct mip_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) +void extract_mip_aiding_ecef_pos_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -469,9 +469,9 @@ void extract_mip_aiding_ecef_pos_command_valid_flags(struct mip_serializer* seri mip_cmd_result mip_aiding_ecef_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(time); insert_mip_time(&serializer, time); @@ -493,7 +493,7 @@ mip_cmd_result mip_aiding_ecef_pos(struct mip_interface* device, const mip_time* return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_ECEF, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_llh_pos_command(mip_serializer* serializer, const mip_aiding_llh_pos_command* self) +void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self) { insert_mip_time(serializer, &self->time); @@ -511,7 +511,7 @@ void insert_mip_aiding_llh_pos_command(mip_serializer* serializer, const mip_aid insert_mip_aiding_llh_pos_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_llh_pos_command(mip_serializer* serializer, mip_aiding_llh_pos_command* self) +void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self) { extract_mip_time(serializer, &self->time); @@ -530,11 +530,11 @@ void extract_mip_aiding_llh_pos_command(mip_serializer* serializer, mip_aiding_l } -void insert_mip_aiding_llh_pos_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) +void insert_mip_aiding_llh_pos_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_llh_pos_command_valid_flags(struct mip_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) +void extract_mip_aiding_llh_pos_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -543,9 +543,9 @@ void extract_mip_aiding_llh_pos_command_valid_flags(struct mip_serializer* seria mip_cmd_result mip_aiding_llh_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(time); insert_mip_time(&serializer, time); @@ -569,7 +569,7 @@ mip_cmd_result mip_aiding_llh_pos(struct mip_interface* device, const mip_time* return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_height_command(mip_serializer* serializer, const mip_aiding_height_command* self) +void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self) { insert_mip_time(serializer, &self->time); @@ -582,7 +582,7 @@ void insert_mip_aiding_height_command(mip_serializer* serializer, const mip_aidi microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_aiding_height_command(mip_serializer* serializer, mip_aiding_height_command* self) +void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self) { extract_mip_time(serializer, &self->time); @@ -598,9 +598,9 @@ void extract_mip_aiding_height_command(mip_serializer* serializer, mip_aiding_he mip_cmd_result mip_aiding_height(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(time); insert_mip_time(&serializer, time); @@ -618,7 +618,7 @@ mip_cmd_result mip_aiding_height(struct mip_interface* device, const mip_time* t return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABS, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_ecef_vel_command(mip_serializer* serializer, const mip_aiding_ecef_vel_command* self) +void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self) { insert_mip_time(serializer, &self->time); @@ -633,7 +633,7 @@ void insert_mip_aiding_ecef_vel_command(mip_serializer* serializer, const mip_ai insert_mip_aiding_ecef_vel_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_ecef_vel_command(mip_serializer* serializer, mip_aiding_ecef_vel_command* self) +void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self) { extract_mip_time(serializer, &self->time); @@ -649,11 +649,11 @@ void extract_mip_aiding_ecef_vel_command(mip_serializer* serializer, mip_aiding_ } -void insert_mip_aiding_ecef_vel_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) +void insert_mip_aiding_ecef_vel_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_ecef_vel_command_valid_flags(struct mip_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) +void extract_mip_aiding_ecef_vel_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -662,9 +662,9 @@ void extract_mip_aiding_ecef_vel_command_valid_flags(struct mip_serializer* seri mip_cmd_result mip_aiding_ecef_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(time); insert_mip_time(&serializer, time); @@ -686,7 +686,7 @@ mip_cmd_result mip_aiding_ecef_vel(struct mip_interface* device, const mip_time* return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ECEF, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_ned_vel_command(mip_serializer* serializer, const mip_aiding_ned_vel_command* self) +void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self) { insert_mip_time(serializer, &self->time); @@ -701,7 +701,7 @@ void insert_mip_aiding_ned_vel_command(mip_serializer* serializer, const mip_aid insert_mip_aiding_ned_vel_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_ned_vel_command(mip_serializer* serializer, mip_aiding_ned_vel_command* self) +void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self) { extract_mip_time(serializer, &self->time); @@ -717,11 +717,11 @@ void extract_mip_aiding_ned_vel_command(mip_serializer* serializer, mip_aiding_n } -void insert_mip_aiding_ned_vel_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) +void insert_mip_aiding_ned_vel_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_ned_vel_command_valid_flags(struct mip_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) +void extract_mip_aiding_ned_vel_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -730,9 +730,9 @@ void extract_mip_aiding_ned_vel_command_valid_flags(struct mip_serializer* seria mip_cmd_result mip_aiding_ned_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(time); insert_mip_time(&serializer, time); @@ -754,7 +754,7 @@ mip_cmd_result mip_aiding_ned_vel(struct mip_interface* device, const mip_time* return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_vehicle_fixed_frame_velocity_command(mip_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self) +void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self) { insert_mip_time(serializer, &self->time); @@ -769,7 +769,7 @@ void insert_mip_aiding_vehicle_fixed_frame_velocity_command(mip_serializer* seri insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_vehicle_fixed_frame_velocity_command(mip_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self) +void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self) { extract_mip_time(serializer, &self->time); @@ -785,11 +785,11 @@ void extract_mip_aiding_vehicle_fixed_frame_velocity_command(mip_serializer* ser } -void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) +void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct mip_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) +void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -798,9 +798,9 @@ void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(time); insert_mip_time(&serializer, time); @@ -822,7 +822,7 @@ mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(struct mip_interface* dev return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ODOM, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_true_heading_command(mip_serializer* serializer, const mip_aiding_true_heading_command* self) +void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self) { insert_mip_time(serializer, &self->time); @@ -835,7 +835,7 @@ void insert_mip_aiding_true_heading_command(mip_serializer* serializer, const mi microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_aiding_true_heading_command(mip_serializer* serializer, mip_aiding_true_heading_command* self) +void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self) { extract_mip_time(serializer, &self->time); @@ -851,9 +851,9 @@ void extract_mip_aiding_true_heading_command(mip_serializer* serializer, mip_aid mip_cmd_result mip_aiding_true_heading(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(time); insert_mip_time(&serializer, time); @@ -871,7 +871,7 @@ mip_cmd_result mip_aiding_true_heading(struct mip_interface* device, const mip_t return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEADING_TRUE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_magnetic_field_command(mip_serializer* serializer, const mip_aiding_magnetic_field_command* self) +void insert_mip_aiding_magnetic_field_command(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command* self) { insert_mip_time(serializer, &self->time); @@ -886,7 +886,7 @@ void insert_mip_aiding_magnetic_field_command(mip_serializer* serializer, const insert_mip_aiding_magnetic_field_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_magnetic_field_command(mip_serializer* serializer, mip_aiding_magnetic_field_command* self) +void extract_mip_aiding_magnetic_field_command(microstrain_serializer* serializer, mip_aiding_magnetic_field_command* self) { extract_mip_time(serializer, &self->time); @@ -902,11 +902,11 @@ void extract_mip_aiding_magnetic_field_command(mip_serializer* serializer, mip_a } -void insert_mip_aiding_magnetic_field_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self) +void insert_mip_aiding_magnetic_field_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_magnetic_field_command_valid_flags(struct mip_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self) +void extract_mip_aiding_magnetic_field_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -915,9 +915,9 @@ void extract_mip_aiding_magnetic_field_command_valid_flags(struct mip_serializer mip_cmd_result mip_aiding_magnetic_field(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* magnetic_field, const float* uncertainty, mip_aiding_magnetic_field_command_valid_flags valid_flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(time); insert_mip_time(&serializer, time); @@ -939,7 +939,7 @@ mip_cmd_result mip_aiding_magnetic_field(struct mip_interface* device, const mip return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_MAGNETIC_FIELD, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_aiding_pressure_command(mip_serializer* serializer, const mip_aiding_pressure_command* self) +void insert_mip_aiding_pressure_command(microstrain_serializer* serializer, const mip_aiding_pressure_command* self) { insert_mip_time(serializer, &self->time); @@ -952,7 +952,7 @@ void insert_mip_aiding_pressure_command(mip_serializer* serializer, const mip_ai microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_aiding_pressure_command(mip_serializer* serializer, mip_aiding_pressure_command* self) +void extract_mip_aiding_pressure_command(microstrain_serializer* serializer, mip_aiding_pressure_command* self) { extract_mip_time(serializer, &self->time); @@ -968,9 +968,9 @@ void extract_mip_aiding_pressure_command(mip_serializer* serializer, mip_aiding_ mip_cmd_result mip_aiding_pressure(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float pressure, float uncertainty, uint16_t valid_flags) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(time); insert_mip_time(&serializer, time); diff --git a/src/mip/definitions/commands_aiding.cpp b/src/mip/definitions/commands_aiding.cpp index f619e07f9..739a6baf6 100644 --- a/src/mip/definitions/commands_aiding.cpp +++ b/src/mip/definitions/commands_aiding.cpp @@ -182,7 +182,7 @@ TypedResult writeFrameConfig(C::mip_interface& device, uint8_t fram } assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut) { @@ -197,7 +197,7 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_FRAME_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_FRAME_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -239,7 +239,7 @@ TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frame assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frameId) { @@ -251,7 +251,7 @@ TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frame assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t frameId) { @@ -263,7 +263,7 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AidingEchoControl& self) { @@ -307,7 +307,7 @@ TypedResult writeAidingEchoControl(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut) { @@ -318,7 +318,7 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ECHO_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ECHO_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -340,7 +340,7 @@ TypedResult saveAidingEchoControl(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAidingEchoControl(C::mip_interface& device) { @@ -350,7 +350,7 @@ TypedResult loadAidingEchoControl(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAidingEchoControl(C::mip_interface& device) { @@ -360,7 +360,7 @@ TypedResult defaultAidingEchoControl(C::mip_interface& device insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const EcefPos& self) { @@ -414,7 +414,7 @@ TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const LlhPos& self) { @@ -476,7 +476,7 @@ TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const Height& self) { @@ -522,7 +522,7 @@ TypedResult height(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const EcefVel& self) { @@ -576,7 +576,7 @@ TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const NedVel& self) { @@ -630,7 +630,7 @@ TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const VehicleFixedFrameVelocity& self) { @@ -684,7 +684,7 @@ TypedResult vehicleFixedFrameVelocity(C::mip_interfac assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ODOM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ODOM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const TrueHeading& self) { @@ -730,7 +730,7 @@ TypedResult trueHeading(C::mip_interface& device, const Time& time, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_TRUE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_TRUE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const MagneticField& self) { @@ -784,7 +784,7 @@ TypedResult magneticField(C::mip_interface& device, const Time& t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_FIELD, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_FIELD, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const Pressure& self) { @@ -830,7 +830,7 @@ TypedResult pressure(C::mip_interface& device, const Time& time, uint8 assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } } // namespace commands_aiding diff --git a/src/mip/definitions/commands_aiding.h b/src/mip/definitions/commands_aiding.h index d2ef69567..f4e01476a 100644 --- a/src/mip/definitions/commands_aiding.h +++ b/src/mip/definitions/commands_aiding.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -73,11 +73,11 @@ struct mip_time }; typedef struct mip_time mip_time; -void insert_mip_time(struct mip_serializer* serializer, const mip_time* self); -void extract_mip_time(struct mip_serializer* serializer, mip_time* self); +void insert_mip_time(struct microstrain_serializer* serializer, const mip_time* self); +void extract_mip_time(struct microstrain_serializer* serializer, mip_time* self); -void insert_mip_time_timebase(struct mip_serializer* serializer, const mip_time_timebase self); -void extract_mip_time_timebase(struct mip_serializer* serializer, mip_time_timebase* self); +void insert_mip_time_timebase(struct microstrain_serializer* serializer, const mip_time_timebase self); +void extract_mip_time_timebase(struct microstrain_serializer* serializer, mip_time_timebase* self); //////////////////////////////////////////////////////////////////////////////// @@ -135,11 +135,11 @@ struct mip_aiding_frame_config_command }; typedef struct mip_aiding_frame_config_command mip_aiding_frame_config_command; -void insert_mip_aiding_frame_config_command(struct mip_serializer* serializer, const mip_aiding_frame_config_command* self); -void extract_mip_aiding_frame_config_command(struct mip_serializer* serializer, mip_aiding_frame_config_command* self); +void insert_mip_aiding_frame_config_command(struct microstrain_serializer* serializer, const mip_aiding_frame_config_command* self); +void extract_mip_aiding_frame_config_command(struct microstrain_serializer* serializer, mip_aiding_frame_config_command* self); -void insert_mip_aiding_frame_config_command_format(struct mip_serializer* serializer, const mip_aiding_frame_config_command_format self); -void extract_mip_aiding_frame_config_command_format(struct mip_serializer* serializer, mip_aiding_frame_config_command_format* self); +void insert_mip_aiding_frame_config_command_format(struct microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self); +void extract_mip_aiding_frame_config_command_format(struct microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self); struct mip_aiding_frame_config_response { @@ -151,8 +151,8 @@ struct mip_aiding_frame_config_response }; typedef struct mip_aiding_frame_config_response mip_aiding_frame_config_response; -void insert_mip_aiding_frame_config_response(struct mip_serializer* serializer, const mip_aiding_frame_config_response* self); -void extract_mip_aiding_frame_config_response(struct mip_serializer* serializer, mip_aiding_frame_config_response* self); +void insert_mip_aiding_frame_config_response(struct microstrain_serializer* serializer, const mip_aiding_frame_config_response* self); +void extract_mip_aiding_frame_config_response(struct microstrain_serializer* serializer, mip_aiding_frame_config_response* self); mip_cmd_result mip_aiding_write_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool tracking_enabled, const float* translation, const mip_aiding_frame_config_command_rotation* rotation); mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool* tracking_enabled_out, float* translation_out, mip_aiding_frame_config_command_rotation* rotation_out); @@ -180,11 +180,11 @@ struct mip_aiding_aiding_echo_control_command }; typedef struct mip_aiding_aiding_echo_control_command mip_aiding_aiding_echo_control_command; -void insert_mip_aiding_aiding_echo_control_command(struct mip_serializer* serializer, const mip_aiding_aiding_echo_control_command* self); -void extract_mip_aiding_aiding_echo_control_command(struct mip_serializer* serializer, mip_aiding_aiding_echo_control_command* self); +void insert_mip_aiding_aiding_echo_control_command(struct microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self); +void extract_mip_aiding_aiding_echo_control_command(struct microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self); -void insert_mip_aiding_aiding_echo_control_command_mode(struct mip_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self); -void extract_mip_aiding_aiding_echo_control_command_mode(struct mip_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self); +void insert_mip_aiding_aiding_echo_control_command_mode(struct microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self); +void extract_mip_aiding_aiding_echo_control_command_mode(struct microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self); struct mip_aiding_aiding_echo_control_response { @@ -192,8 +192,8 @@ struct mip_aiding_aiding_echo_control_response }; typedef struct mip_aiding_aiding_echo_control_response mip_aiding_aiding_echo_control_response; -void insert_mip_aiding_aiding_echo_control_response(struct mip_serializer* serializer, const mip_aiding_aiding_echo_control_response* self); -void extract_mip_aiding_aiding_echo_control_response(struct mip_serializer* serializer, mip_aiding_aiding_echo_control_response* self); +void insert_mip_aiding_aiding_echo_control_response(struct microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self); +void extract_mip_aiding_aiding_echo_control_response(struct microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self); mip_cmd_result mip_aiding_write_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode); mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out); @@ -226,11 +226,11 @@ struct mip_aiding_ecef_pos_command }; typedef struct mip_aiding_ecef_pos_command mip_aiding_ecef_pos_command; -void insert_mip_aiding_ecef_pos_command(struct mip_serializer* serializer, const mip_aiding_ecef_pos_command* self); -void extract_mip_aiding_ecef_pos_command(struct mip_serializer* serializer, mip_aiding_ecef_pos_command* self); +void insert_mip_aiding_ecef_pos_command(struct microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self); +void extract_mip_aiding_ecef_pos_command(struct microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self); -void insert_mip_aiding_ecef_pos_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self); -void extract_mip_aiding_ecef_pos_command_valid_flags(struct mip_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self); +void insert_mip_aiding_ecef_pos_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self); +void extract_mip_aiding_ecef_pos_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self); mip_cmd_result mip_aiding_ecef_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags); @@ -262,11 +262,11 @@ struct mip_aiding_llh_pos_command }; typedef struct mip_aiding_llh_pos_command mip_aiding_llh_pos_command; -void insert_mip_aiding_llh_pos_command(struct mip_serializer* serializer, const mip_aiding_llh_pos_command* self); -void extract_mip_aiding_llh_pos_command(struct mip_serializer* serializer, mip_aiding_llh_pos_command* self); +void insert_mip_aiding_llh_pos_command(struct microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self); +void extract_mip_aiding_llh_pos_command(struct microstrain_serializer* serializer, mip_aiding_llh_pos_command* self); -void insert_mip_aiding_llh_pos_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self); -void extract_mip_aiding_llh_pos_command_valid_flags(struct mip_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self); +void insert_mip_aiding_llh_pos_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self); +void extract_mip_aiding_llh_pos_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self); mip_cmd_result mip_aiding_llh_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags); @@ -288,8 +288,8 @@ struct mip_aiding_height_command }; typedef struct mip_aiding_height_command mip_aiding_height_command; -void insert_mip_aiding_height_command(struct mip_serializer* serializer, const mip_aiding_height_command* self); -void extract_mip_aiding_height_command(struct mip_serializer* serializer, mip_aiding_height_command* self); +void insert_mip_aiding_height_command(struct microstrain_serializer* serializer, const mip_aiding_height_command* self); +void extract_mip_aiding_height_command(struct microstrain_serializer* serializer, mip_aiding_height_command* self); mip_cmd_result mip_aiding_height(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); @@ -318,11 +318,11 @@ struct mip_aiding_ecef_vel_command }; typedef struct mip_aiding_ecef_vel_command mip_aiding_ecef_vel_command; -void insert_mip_aiding_ecef_vel_command(struct mip_serializer* serializer, const mip_aiding_ecef_vel_command* self); -void extract_mip_aiding_ecef_vel_command(struct mip_serializer* serializer, mip_aiding_ecef_vel_command* self); +void insert_mip_aiding_ecef_vel_command(struct microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self); +void extract_mip_aiding_ecef_vel_command(struct microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self); -void insert_mip_aiding_ecef_vel_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self); -void extract_mip_aiding_ecef_vel_command_valid_flags(struct mip_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self); +void insert_mip_aiding_ecef_vel_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self); +void extract_mip_aiding_ecef_vel_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self); mip_cmd_result mip_aiding_ecef_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags); @@ -351,11 +351,11 @@ struct mip_aiding_ned_vel_command }; typedef struct mip_aiding_ned_vel_command mip_aiding_ned_vel_command; -void insert_mip_aiding_ned_vel_command(struct mip_serializer* serializer, const mip_aiding_ned_vel_command* self); -void extract_mip_aiding_ned_vel_command(struct mip_serializer* serializer, mip_aiding_ned_vel_command* self); +void insert_mip_aiding_ned_vel_command(struct microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self); +void extract_mip_aiding_ned_vel_command(struct microstrain_serializer* serializer, mip_aiding_ned_vel_command* self); -void insert_mip_aiding_ned_vel_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self); -void extract_mip_aiding_ned_vel_command_valid_flags(struct mip_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self); +void insert_mip_aiding_ned_vel_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self); +void extract_mip_aiding_ned_vel_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self); mip_cmd_result mip_aiding_ned_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags); @@ -385,11 +385,11 @@ struct mip_aiding_vehicle_fixed_frame_velocity_command }; typedef struct mip_aiding_vehicle_fixed_frame_velocity_command mip_aiding_vehicle_fixed_frame_velocity_command; -void insert_mip_aiding_vehicle_fixed_frame_velocity_command(struct mip_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self); -void extract_mip_aiding_vehicle_fixed_frame_velocity_command(struct mip_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self); +void insert_mip_aiding_vehicle_fixed_frame_velocity_command(struct microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self); +void extract_mip_aiding_vehicle_fixed_frame_velocity_command(struct microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self); -void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self); -void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct mip_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self); +void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self); +void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self); mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags); @@ -410,8 +410,8 @@ struct mip_aiding_true_heading_command }; typedef struct mip_aiding_true_heading_command mip_aiding_true_heading_command; -void insert_mip_aiding_true_heading_command(struct mip_serializer* serializer, const mip_aiding_true_heading_command* self); -void extract_mip_aiding_true_heading_command(struct mip_serializer* serializer, mip_aiding_true_heading_command* self); +void insert_mip_aiding_true_heading_command(struct microstrain_serializer* serializer, const mip_aiding_true_heading_command* self); +void extract_mip_aiding_true_heading_command(struct microstrain_serializer* serializer, mip_aiding_true_heading_command* self); mip_cmd_result mip_aiding_true_heading(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); @@ -440,11 +440,11 @@ struct mip_aiding_magnetic_field_command }; typedef struct mip_aiding_magnetic_field_command mip_aiding_magnetic_field_command; -void insert_mip_aiding_magnetic_field_command(struct mip_serializer* serializer, const mip_aiding_magnetic_field_command* self); -void extract_mip_aiding_magnetic_field_command(struct mip_serializer* serializer, mip_aiding_magnetic_field_command* self); +void insert_mip_aiding_magnetic_field_command(struct microstrain_serializer* serializer, const mip_aiding_magnetic_field_command* self); +void extract_mip_aiding_magnetic_field_command(struct microstrain_serializer* serializer, mip_aiding_magnetic_field_command* self); -void insert_mip_aiding_magnetic_field_command_valid_flags(struct mip_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self); -void extract_mip_aiding_magnetic_field_command_valid_flags(struct mip_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self); +void insert_mip_aiding_magnetic_field_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self); +void extract_mip_aiding_magnetic_field_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self); mip_cmd_result mip_aiding_magnetic_field(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* magnetic_field, const float* uncertainty, mip_aiding_magnetic_field_command_valid_flags valid_flags); @@ -466,8 +466,8 @@ struct mip_aiding_pressure_command }; typedef struct mip_aiding_pressure_command mip_aiding_pressure_command; -void insert_mip_aiding_pressure_command(struct mip_serializer* serializer, const mip_aiding_pressure_command* self); -void extract_mip_aiding_pressure_command(struct mip_serializer* serializer, mip_aiding_pressure_command* self); +void insert_mip_aiding_pressure_command(struct microstrain_serializer* serializer, const mip_aiding_pressure_command* self); +void extract_mip_aiding_pressure_command(struct microstrain_serializer* serializer, mip_aiding_pressure_command* self); mip_cmd_result mip_aiding_pressure(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float pressure, float uncertainty, uint16_t valid_flags); diff --git a/src/mip/definitions/commands_base.c b/src/mip/definitions/commands_base.c index ca9919e91..d31e3984c 100644 --- a/src/mip/definitions/commands_base.c +++ b/src/mip/definitions/commands_base.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -22,7 +22,7 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_base_device_info(mip_serializer* serializer, const mip_base_device_info* self) +void insert_mip_base_device_info(microstrain_serializer* serializer, const mip_base_device_info* self) { microstrain_insert_u16(serializer, self->firmware_version); @@ -42,7 +42,7 @@ void insert_mip_base_device_info(mip_serializer* serializer, const mip_base_devi microstrain_insert_char(serializer, self->device_options[i]); } -void extract_mip_base_device_info(mip_serializer* serializer, mip_base_device_info* self) +void extract_mip_base_device_info(microstrain_serializer* serializer, mip_base_device_info* self) { microstrain_extract_u16(serializer, &self->firmware_version); @@ -63,22 +63,22 @@ void extract_mip_base_device_info(mip_serializer* serializer, mip_base_device_in } -void insert_mip_time_format(struct mip_serializer* serializer, const mip_time_format self) +void insert_mip_time_format(struct microstrain_serializer* serializer, const mip_time_format self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_time_format(struct mip_serializer* serializer, mip_time_format* self) +void extract_mip_time_format(struct microstrain_serializer* serializer, mip_time_format* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_commanded_test_bits_gq7(struct mip_serializer* serializer, const mip_commanded_test_bits_gq7 self) +void insert_mip_commanded_test_bits_gq7(struct microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self) { microstrain_insert_u32(serializer, (uint32_t) (self)); } -void extract_mip_commanded_test_bits_gq7(struct mip_serializer* serializer, mip_commanded_test_bits_gq7* self) +void extract_mip_commanded_test_bits_gq7(struct microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self) { uint32_t tmp = 0; microstrain_extract_u32(serializer, &tmp); @@ -107,8 +107,8 @@ mip_cmd_result mip_base_get_device_info(struct mip_interface* device, mip_base_d if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(device_info_out); extract_mip_base_device_info(&deserializer, device_info_out); @@ -127,8 +127,8 @@ mip_cmd_result mip_base_get_device_descriptors(struct mip_interface* device, uin if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && ( microstrain_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) @@ -148,8 +148,8 @@ mip_cmd_result mip_base_built_in_test(struct mip_interface* device, uint32_t* re if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(result_out); microstrain_extract_u32(&deserializer, result_out); @@ -172,8 +172,8 @@ mip_cmd_result mip_base_get_extended_descriptors(struct mip_interface* device, u if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && ( microstrain_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) @@ -193,8 +193,8 @@ mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* re if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(result_out || (16 == 0)); for(unsigned int i=0; i < 16; i++) @@ -205,7 +205,7 @@ mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* re } return result; } -void insert_mip_base_comm_speed_command(mip_serializer* serializer, const mip_base_comm_speed_command* self) +void insert_mip_base_comm_speed_command(microstrain_serializer* serializer, const mip_base_comm_speed_command* self) { insert_mip_function_selector(serializer, self->function); @@ -217,7 +217,7 @@ void insert_mip_base_comm_speed_command(mip_serializer* serializer, const mip_ba } } -void extract_mip_base_comm_speed_command(mip_serializer* serializer, mip_base_comm_speed_command* self) +void extract_mip_base_comm_speed_command(microstrain_serializer* serializer, mip_base_comm_speed_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -230,14 +230,14 @@ void extract_mip_base_comm_speed_command(mip_serializer* serializer, mip_base_co } } -void insert_mip_base_comm_speed_response(mip_serializer* serializer, const mip_base_comm_speed_response* self) +void insert_mip_base_comm_speed_response(microstrain_serializer* serializer, const mip_base_comm_speed_response* self) { microstrain_insert_u8(serializer, self->port); microstrain_insert_u32(serializer, self->baud); } -void extract_mip_base_comm_speed_response(mip_serializer* serializer, mip_base_comm_speed_response* self) +void extract_mip_base_comm_speed_response(microstrain_serializer* serializer, mip_base_comm_speed_response* self) { microstrain_extract_u8(serializer, &self->port); @@ -247,9 +247,9 @@ void extract_mip_base_comm_speed_response(mip_serializer* serializer, mip_base_c mip_cmd_result mip_base_write_comm_speed(struct mip_interface* device, uint8_t port, uint32_t baud) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -264,9 +264,9 @@ mip_cmd_result mip_base_write_comm_speed(struct mip_interface* device, uint8_t p } mip_cmd_result mip_base_read_comm_speed(struct mip_interface* device, uint8_t port, uint32_t* baud_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -280,8 +280,8 @@ mip_cmd_result mip_base_read_comm_speed(struct mip_interface* device, uint8_t po if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &port); @@ -295,9 +295,9 @@ mip_cmd_result mip_base_read_comm_speed(struct mip_interface* device, uint8_t po } mip_cmd_result mip_base_save_comm_speed(struct mip_interface* device, uint8_t port) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -310,9 +310,9 @@ mip_cmd_result mip_base_save_comm_speed(struct mip_interface* device, uint8_t po } mip_cmd_result mip_base_load_comm_speed(struct mip_interface* device, uint8_t port) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -325,9 +325,9 @@ mip_cmd_result mip_base_load_comm_speed(struct mip_interface* device, uint8_t po } mip_cmd_result mip_base_default_comm_speed(struct mip_interface* device, uint8_t port) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -338,7 +338,7 @@ mip_cmd_result mip_base_default_comm_speed(struct mip_interface* device, uint8_t return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_base_gps_time_update_command(mip_serializer* serializer, const mip_base_gps_time_update_command* self) +void insert_mip_base_gps_time_update_command(microstrain_serializer* serializer, const mip_base_gps_time_update_command* self) { insert_mip_function_selector(serializer, self->function); @@ -350,7 +350,7 @@ void insert_mip_base_gps_time_update_command(mip_serializer* serializer, const m } } -void extract_mip_base_gps_time_update_command(mip_serializer* serializer, mip_base_gps_time_update_command* self) +void extract_mip_base_gps_time_update_command(microstrain_serializer* serializer, mip_base_gps_time_update_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -363,11 +363,11 @@ void extract_mip_base_gps_time_update_command(mip_serializer* serializer, mip_ba } } -void insert_mip_base_gps_time_update_command_field_id(struct mip_serializer* serializer, const mip_base_gps_time_update_command_field_id self) +void insert_mip_base_gps_time_update_command_field_id(struct microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_base_gps_time_update_command_field_id(struct mip_serializer* serializer, mip_base_gps_time_update_command_field_id* self) +void extract_mip_base_gps_time_update_command_field_id(struct microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -376,9 +376,9 @@ void extract_mip_base_gps_time_update_command_field_id(struct mip_serializer* se mip_cmd_result mip_base_write_gps_time_update(struct mip_interface* device, mip_base_gps_time_update_command_field_id field_id, uint32_t value) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); diff --git a/src/mip/definitions/commands_base.cpp b/src/mip/definitions/commands_base.cpp index 0c4a53034..1190f9486 100644 --- a/src/mip/definitions/commands_base.cpp +++ b/src/mip/definitions/commands_base.cpp @@ -379,7 +379,7 @@ TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) { @@ -392,7 +392,7 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_COMM_SPEED, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_COMM_SPEED, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -418,7 +418,7 @@ TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) { @@ -430,7 +430,7 @@ TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) { @@ -442,7 +442,7 @@ TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GpsTimeUpdate& self) { @@ -481,7 +481,7 @@ TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeU assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SoftReset& self) { diff --git a/src/mip/definitions/commands_base.h b/src/mip/definitions/commands_base.h index 6d30392c6..14959e835 100644 --- a/src/mip/definitions/commands_base.h +++ b/src/mip/definitions/commands_base.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -70,14 +70,14 @@ struct mip_base_device_info }; typedef struct mip_base_device_info mip_base_device_info; -void insert_mip_base_device_info(struct mip_serializer* serializer, const mip_base_device_info* self); -void extract_mip_base_device_info(struct mip_serializer* serializer, mip_base_device_info* self); +void insert_mip_base_device_info(struct microstrain_serializer* serializer, const mip_base_device_info* self); +void extract_mip_base_device_info(struct microstrain_serializer* serializer, mip_base_device_info* self); typedef uint8_t mip_time_format; static const mip_time_format MIP_TIME_FORMAT_GPS = 1; ///< GPS time, a = week number since 1980, b = time of week in milliseconds. -void insert_mip_time_format(struct mip_serializer* serializer, const mip_time_format self); -void extract_mip_time_format(struct mip_serializer* serializer, mip_time_format* self); +void insert_mip_time_format(struct microstrain_serializer* serializer, const mip_time_format self); +void extract_mip_time_format(struct microstrain_serializer* serializer, mip_time_format* self); typedef uint32_t mip_commanded_test_bits_gq7; static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_NONE = 0x00000000; @@ -110,8 +110,8 @@ static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_SOLUTI static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_GENERAL_FAULT = 0x80000000; ///< static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_ALL = 0xFFFFFFFF; -void insert_mip_commanded_test_bits_gq7(struct mip_serializer* serializer, const mip_commanded_test_bits_gq7 self); -void extract_mip_commanded_test_bits_gq7(struct mip_serializer* serializer, mip_commanded_test_bits_gq7* self); +void insert_mip_commanded_test_bits_gq7(struct microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self); +void extract_mip_commanded_test_bits_gq7(struct microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self); //////////////////////////////////////////////////////////////////////////////// @@ -158,8 +158,8 @@ struct mip_base_get_device_info_response }; typedef struct mip_base_get_device_info_response mip_base_get_device_info_response; -void insert_mip_base_get_device_info_response(struct mip_serializer* serializer, const mip_base_get_device_info_response* self); -void extract_mip_base_get_device_info_response(struct mip_serializer* serializer, mip_base_get_device_info_response* self); +void insert_mip_base_get_device_info_response(struct microstrain_serializer* serializer, const mip_base_get_device_info_response* self); +void extract_mip_base_get_device_info_response(struct microstrain_serializer* serializer, mip_base_get_device_info_response* self); mip_cmd_result mip_base_get_device_info(struct mip_interface* device, mip_base_device_info* device_info_out); @@ -181,8 +181,8 @@ struct mip_base_get_device_descriptors_response }; typedef struct mip_base_get_device_descriptors_response mip_base_get_device_descriptors_response; -void insert_mip_base_get_device_descriptors_response(struct mip_serializer* serializer, const mip_base_get_device_descriptors_response* self); -void extract_mip_base_get_device_descriptors_response(struct mip_serializer* serializer, mip_base_get_device_descriptors_response* self); +void insert_mip_base_get_device_descriptors_response(struct microstrain_serializer* serializer, const mip_base_get_device_descriptors_response* self); +void extract_mip_base_get_device_descriptors_response(struct microstrain_serializer* serializer, mip_base_get_device_descriptors_response* self); mip_cmd_result mip_base_get_device_descriptors(struct mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count); @@ -205,8 +205,8 @@ struct mip_base_built_in_test_response }; typedef struct mip_base_built_in_test_response mip_base_built_in_test_response; -void insert_mip_base_built_in_test_response(struct mip_serializer* serializer, const mip_base_built_in_test_response* self); -void extract_mip_base_built_in_test_response(struct mip_serializer* serializer, mip_base_built_in_test_response* self); +void insert_mip_base_built_in_test_response(struct microstrain_serializer* serializer, const mip_base_built_in_test_response* self); +void extract_mip_base_built_in_test_response(struct microstrain_serializer* serializer, mip_base_built_in_test_response* self); mip_cmd_result mip_base_built_in_test(struct mip_interface* device, uint32_t* result_out); @@ -240,8 +240,8 @@ struct mip_base_get_extended_descriptors_response }; typedef struct mip_base_get_extended_descriptors_response mip_base_get_extended_descriptors_response; -void insert_mip_base_get_extended_descriptors_response(struct mip_serializer* serializer, const mip_base_get_extended_descriptors_response* self); -void extract_mip_base_get_extended_descriptors_response(struct mip_serializer* serializer, mip_base_get_extended_descriptors_response* self); +void insert_mip_base_get_extended_descriptors_response(struct microstrain_serializer* serializer, const mip_base_get_extended_descriptors_response* self); +void extract_mip_base_get_extended_descriptors_response(struct microstrain_serializer* serializer, mip_base_get_extended_descriptors_response* self); mip_cmd_result mip_base_get_extended_descriptors(struct mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count); @@ -261,8 +261,8 @@ struct mip_base_continuous_bit_response }; typedef struct mip_base_continuous_bit_response mip_base_continuous_bit_response; -void insert_mip_base_continuous_bit_response(struct mip_serializer* serializer, const mip_base_continuous_bit_response* self); -void extract_mip_base_continuous_bit_response(struct mip_serializer* serializer, mip_base_continuous_bit_response* self); +void insert_mip_base_continuous_bit_response(struct microstrain_serializer* serializer, const mip_base_continuous_bit_response* self); +void extract_mip_base_continuous_bit_response(struct microstrain_serializer* serializer, mip_base_continuous_bit_response* self); mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* result_out); @@ -296,8 +296,8 @@ struct mip_base_comm_speed_command }; typedef struct mip_base_comm_speed_command mip_base_comm_speed_command; -void insert_mip_base_comm_speed_command(struct mip_serializer* serializer, const mip_base_comm_speed_command* self); -void extract_mip_base_comm_speed_command(struct mip_serializer* serializer, mip_base_comm_speed_command* self); +void insert_mip_base_comm_speed_command(struct microstrain_serializer* serializer, const mip_base_comm_speed_command* self); +void extract_mip_base_comm_speed_command(struct microstrain_serializer* serializer, mip_base_comm_speed_command* self); struct mip_base_comm_speed_response { @@ -306,8 +306,8 @@ struct mip_base_comm_speed_response }; typedef struct mip_base_comm_speed_response mip_base_comm_speed_response; -void insert_mip_base_comm_speed_response(struct mip_serializer* serializer, const mip_base_comm_speed_response* self); -void extract_mip_base_comm_speed_response(struct mip_serializer* serializer, mip_base_comm_speed_response* self); +void insert_mip_base_comm_speed_response(struct microstrain_serializer* serializer, const mip_base_comm_speed_response* self); +void extract_mip_base_comm_speed_response(struct microstrain_serializer* serializer, mip_base_comm_speed_response* self); mip_cmd_result mip_base_write_comm_speed(struct mip_interface* device, uint8_t port, uint32_t baud); mip_cmd_result mip_base_read_comm_speed(struct mip_interface* device, uint8_t port, uint32_t* baud_out); @@ -338,11 +338,11 @@ struct mip_base_gps_time_update_command }; typedef struct mip_base_gps_time_update_command mip_base_gps_time_update_command; -void insert_mip_base_gps_time_update_command(struct mip_serializer* serializer, const mip_base_gps_time_update_command* self); -void extract_mip_base_gps_time_update_command(struct mip_serializer* serializer, mip_base_gps_time_update_command* self); +void insert_mip_base_gps_time_update_command(struct microstrain_serializer* serializer, const mip_base_gps_time_update_command* self); +void extract_mip_base_gps_time_update_command(struct microstrain_serializer* serializer, mip_base_gps_time_update_command* self); -void insert_mip_base_gps_time_update_command_field_id(struct mip_serializer* serializer, const mip_base_gps_time_update_command_field_id self); -void extract_mip_base_gps_time_update_command_field_id(struct mip_serializer* serializer, mip_base_gps_time_update_command_field_id* self); +void insert_mip_base_gps_time_update_command_field_id(struct microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self); +void extract_mip_base_gps_time_update_command_field_id(struct microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self); mip_cmd_result mip_base_write_gps_time_update(struct mip_interface* device, mip_base_gps_time_update_command_field_id field_id, uint32_t value); diff --git a/src/mip/definitions/commands_filter.c b/src/mip/definitions/commands_filter.c index 6c21204ac..f3d95d7ed 100644 --- a/src/mip/definitions/commands_filter.c +++ b/src/mip/definitions/commands_filter.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -22,33 +22,33 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_filter_reference_frame(struct mip_serializer* serializer, const mip_filter_reference_frame self) +void insert_mip_filter_reference_frame(struct microstrain_serializer* serializer, const mip_filter_reference_frame self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_reference_frame(struct mip_serializer* serializer, mip_filter_reference_frame* self) +void extract_mip_filter_reference_frame(struct microstrain_serializer* serializer, mip_filter_reference_frame* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_mag_param_source(struct mip_serializer* serializer, const mip_filter_mag_param_source self) +void insert_mip_filter_mag_param_source(struct microstrain_serializer* serializer, const mip_filter_mag_param_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_mag_param_source(struct mip_serializer* serializer, mip_filter_mag_param_source* self) +void extract_mip_filter_mag_param_source(struct microstrain_serializer* serializer, mip_filter_mag_param_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_adaptive_measurement(struct mip_serializer* serializer, const mip_filter_adaptive_measurement self) +void insert_mip_filter_adaptive_measurement(struct microstrain_serializer* serializer, const mip_filter_adaptive_measurement self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_adaptive_measurement(struct mip_serializer* serializer, mip_filter_adaptive_measurement* self) +void extract_mip_filter_adaptive_measurement(struct microstrain_serializer* serializer, mip_filter_adaptive_measurement* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -64,7 +64,7 @@ mip_cmd_result mip_filter_reset(struct mip_interface* device) { return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_RESET_FILTER, NULL, 0); } -void insert_mip_filter_set_initial_attitude_command(mip_serializer* serializer, const mip_filter_set_initial_attitude_command* self) +void insert_mip_filter_set_initial_attitude_command(microstrain_serializer* serializer, const mip_filter_set_initial_attitude_command* self) { microstrain_insert_float(serializer, self->roll); @@ -73,7 +73,7 @@ void insert_mip_filter_set_initial_attitude_command(mip_serializer* serializer, microstrain_insert_float(serializer, self->heading); } -void extract_mip_filter_set_initial_attitude_command(mip_serializer* serializer, mip_filter_set_initial_attitude_command* self) +void extract_mip_filter_set_initial_attitude_command(microstrain_serializer* serializer, mip_filter_set_initial_attitude_command* self) { microstrain_extract_float(serializer, &self->roll); @@ -85,9 +85,9 @@ void extract_mip_filter_set_initial_attitude_command(mip_serializer* serializer, mip_cmd_result mip_filter_set_initial_attitude(struct mip_interface* device, float roll, float pitch, float heading) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_float(&serializer, roll); @@ -100,7 +100,7 @@ mip_cmd_result mip_filter_set_initial_attitude(struct mip_interface* device, flo return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SET_INITIAL_ATTITUDE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_estimation_control_command(mip_serializer* serializer, const mip_filter_estimation_control_command* self) +void insert_mip_filter_estimation_control_command(microstrain_serializer* serializer, const mip_filter_estimation_control_command* self) { insert_mip_function_selector(serializer, self->function); @@ -110,7 +110,7 @@ void insert_mip_filter_estimation_control_command(mip_serializer* serializer, co } } -void extract_mip_filter_estimation_control_command(mip_serializer* serializer, mip_filter_estimation_control_command* self) +void extract_mip_filter_estimation_control_command(microstrain_serializer* serializer, mip_filter_estimation_control_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -121,22 +121,22 @@ void extract_mip_filter_estimation_control_command(mip_serializer* serializer, m } } -void insert_mip_filter_estimation_control_response(mip_serializer* serializer, const mip_filter_estimation_control_response* self) +void insert_mip_filter_estimation_control_response(microstrain_serializer* serializer, const mip_filter_estimation_control_response* self) { insert_mip_filter_estimation_control_command_enable_flags(serializer, self->enable); } -void extract_mip_filter_estimation_control_response(mip_serializer* serializer, mip_filter_estimation_control_response* self) +void extract_mip_filter_estimation_control_response(microstrain_serializer* serializer, mip_filter_estimation_control_response* self) { extract_mip_filter_estimation_control_command_enable_flags(serializer, &self->enable); } -void insert_mip_filter_estimation_control_command_enable_flags(struct mip_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self) +void insert_mip_filter_estimation_control_command_enable_flags(struct microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_estimation_control_command_enable_flags(struct mip_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self) +void extract_mip_filter_estimation_control_command_enable_flags(struct microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -145,9 +145,9 @@ void extract_mip_filter_estimation_control_command_enable_flags(struct mip_seria mip_cmd_result mip_filter_write_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags enable) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -160,9 +160,9 @@ mip_cmd_result mip_filter_write_estimation_control(struct mip_interface* device, } mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags* enable_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -174,8 +174,8 @@ mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); extract_mip_filter_estimation_control_command_enable_flags(&deserializer, enable_out); @@ -187,9 +187,9 @@ mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, } mip_cmd_result mip_filter_save_estimation_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -200,9 +200,9 @@ mip_cmd_result mip_filter_save_estimation_control(struct mip_interface* device) } mip_cmd_result mip_filter_load_estimation_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -213,9 +213,9 @@ mip_cmd_result mip_filter_load_estimation_control(struct mip_interface* device) } mip_cmd_result mip_filter_default_estimation_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -224,7 +224,7 @@ mip_cmd_result mip_filter_default_estimation_control(struct mip_interface* devic return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_external_gnss_update_command(mip_serializer* serializer, const mip_filter_external_gnss_update_command* self) +void insert_mip_filter_external_gnss_update_command(microstrain_serializer* serializer, const mip_filter_external_gnss_update_command* self) { microstrain_insert_double(serializer, self->gps_time); @@ -246,7 +246,7 @@ void insert_mip_filter_external_gnss_update_command(mip_serializer* serializer, microstrain_insert_float(serializer, self->vel_uncertainty[i]); } -void extract_mip_filter_external_gnss_update_command(mip_serializer* serializer, mip_filter_external_gnss_update_command* self) +void extract_mip_filter_external_gnss_update_command(microstrain_serializer* serializer, mip_filter_external_gnss_update_command* self) { microstrain_extract_double(serializer, &self->gps_time); @@ -271,9 +271,9 @@ void extract_mip_filter_external_gnss_update_command(mip_serializer* serializer, mip_cmd_result mip_filter_external_gnss_update(struct mip_interface* device, double gps_time, uint16_t gps_week, double latitude, double longitude, double height, const float* velocity, const float* pos_uncertainty, const float* vel_uncertainty) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_double(&serializer, gps_time); @@ -302,7 +302,7 @@ mip_cmd_result mip_filter_external_gnss_update(struct mip_interface* device, dou return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_external_heading_update_command(mip_serializer* serializer, const mip_filter_external_heading_update_command* self) +void insert_mip_filter_external_heading_update_command(microstrain_serializer* serializer, const mip_filter_external_heading_update_command* self) { microstrain_insert_float(serializer, self->heading); @@ -311,7 +311,7 @@ void insert_mip_filter_external_heading_update_command(mip_serializer* serialize microstrain_insert_u8(serializer, self->type); } -void extract_mip_filter_external_heading_update_command(mip_serializer* serializer, mip_filter_external_heading_update_command* self) +void extract_mip_filter_external_heading_update_command(microstrain_serializer* serializer, mip_filter_external_heading_update_command* self) { microstrain_extract_float(serializer, &self->heading); @@ -323,9 +323,9 @@ void extract_mip_filter_external_heading_update_command(mip_serializer* serializ mip_cmd_result mip_filter_external_heading_update(struct mip_interface* device, float heading, float heading_uncertainty, uint8_t type) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_float(&serializer, heading); @@ -338,7 +338,7 @@ mip_cmd_result mip_filter_external_heading_update(struct mip_interface* device, return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_external_heading_update_with_time_command(mip_serializer* serializer, const mip_filter_external_heading_update_with_time_command* self) +void insert_mip_filter_external_heading_update_with_time_command(microstrain_serializer* serializer, const mip_filter_external_heading_update_with_time_command* self) { microstrain_insert_double(serializer, self->gps_time); @@ -351,7 +351,7 @@ void insert_mip_filter_external_heading_update_with_time_command(mip_serializer* microstrain_insert_u8(serializer, self->type); } -void extract_mip_filter_external_heading_update_with_time_command(mip_serializer* serializer, mip_filter_external_heading_update_with_time_command* self) +void extract_mip_filter_external_heading_update_with_time_command(microstrain_serializer* serializer, mip_filter_external_heading_update_with_time_command* self) { microstrain_extract_double(serializer, &self->gps_time); @@ -367,9 +367,9 @@ void extract_mip_filter_external_heading_update_with_time_command(mip_serializer mip_cmd_result mip_filter_external_heading_update_with_time(struct mip_interface* device, double gps_time, uint16_t gps_week, float heading, float heading_uncertainty, uint8_t type) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_double(&serializer, gps_time); @@ -386,7 +386,7 @@ mip_cmd_result mip_filter_external_heading_update_with_time(struct mip_interface return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_tare_orientation_command(mip_serializer* serializer, const mip_filter_tare_orientation_command* self) +void insert_mip_filter_tare_orientation_command(microstrain_serializer* serializer, const mip_filter_tare_orientation_command* self) { insert_mip_function_selector(serializer, self->function); @@ -396,7 +396,7 @@ void insert_mip_filter_tare_orientation_command(mip_serializer* serializer, cons } } -void extract_mip_filter_tare_orientation_command(mip_serializer* serializer, mip_filter_tare_orientation_command* self) +void extract_mip_filter_tare_orientation_command(microstrain_serializer* serializer, mip_filter_tare_orientation_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -407,22 +407,22 @@ void extract_mip_filter_tare_orientation_command(mip_serializer* serializer, mip } } -void insert_mip_filter_tare_orientation_response(mip_serializer* serializer, const mip_filter_tare_orientation_response* self) +void insert_mip_filter_tare_orientation_response(microstrain_serializer* serializer, const mip_filter_tare_orientation_response* self) { insert_mip_filter_tare_orientation_command_mip_tare_axes(serializer, self->axes); } -void extract_mip_filter_tare_orientation_response(mip_serializer* serializer, mip_filter_tare_orientation_response* self) +void extract_mip_filter_tare_orientation_response(microstrain_serializer* serializer, mip_filter_tare_orientation_response* self) { extract_mip_filter_tare_orientation_command_mip_tare_axes(serializer, &self->axes); } -void insert_mip_filter_tare_orientation_command_mip_tare_axes(struct mip_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self) +void insert_mip_filter_tare_orientation_command_mip_tare_axes(struct microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_tare_orientation_command_mip_tare_axes(struct mip_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self) +void extract_mip_filter_tare_orientation_command_mip_tare_axes(struct microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -431,9 +431,9 @@ void extract_mip_filter_tare_orientation_command_mip_tare_axes(struct mip_serial mip_cmd_result mip_filter_write_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes axes) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -446,9 +446,9 @@ mip_cmd_result mip_filter_write_tare_orientation(struct mip_interface* device, m } mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes* axes_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -460,8 +460,8 @@ mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mi if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(axes_out); extract_mip_filter_tare_orientation_command_mip_tare_axes(&deserializer, axes_out); @@ -473,9 +473,9 @@ mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mi } mip_cmd_result mip_filter_save_tare_orientation(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -486,9 +486,9 @@ mip_cmd_result mip_filter_save_tare_orientation(struct mip_interface* device) } mip_cmd_result mip_filter_load_tare_orientation(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -499,9 +499,9 @@ mip_cmd_result mip_filter_load_tare_orientation(struct mip_interface* device) } mip_cmd_result mip_filter_default_tare_orientation(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -510,7 +510,7 @@ mip_cmd_result mip_filter_default_tare_orientation(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_vehicle_dynamics_mode_command(mip_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self) +void insert_mip_filter_vehicle_dynamics_mode_command(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self) { insert_mip_function_selector(serializer, self->function); @@ -520,7 +520,7 @@ void insert_mip_filter_vehicle_dynamics_mode_command(mip_serializer* serializer, } } -void extract_mip_filter_vehicle_dynamics_mode_command(mip_serializer* serializer, mip_filter_vehicle_dynamics_mode_command* self) +void extract_mip_filter_vehicle_dynamics_mode_command(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -531,22 +531,22 @@ void extract_mip_filter_vehicle_dynamics_mode_command(mip_serializer* serializer } } -void insert_mip_filter_vehicle_dynamics_mode_response(mip_serializer* serializer, const mip_filter_vehicle_dynamics_mode_response* self) +void insert_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_response* self) { insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(serializer, self->mode); } -void extract_mip_filter_vehicle_dynamics_mode_response(mip_serializer* serializer, mip_filter_vehicle_dynamics_mode_response* self) +void extract_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_response* self) { extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(serializer, &self->mode); } -void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct mip_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self) +void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct mip_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self) +void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -555,9 +555,9 @@ void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct mip_s mip_cmd_result mip_filter_write_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -570,9 +570,9 @@ mip_cmd_result mip_filter_write_vehicle_dynamics_mode(struct mip_interface* devi } mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* mode_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -584,8 +584,8 @@ mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* devic if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(mode_out); extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(&deserializer, mode_out); @@ -597,9 +597,9 @@ mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* devic } mip_cmd_result mip_filter_save_vehicle_dynamics_mode(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -610,9 +610,9 @@ mip_cmd_result mip_filter_save_vehicle_dynamics_mode(struct mip_interface* devic } mip_cmd_result mip_filter_load_vehicle_dynamics_mode(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -623,9 +623,9 @@ mip_cmd_result mip_filter_load_vehicle_dynamics_mode(struct mip_interface* devic } mip_cmd_result mip_filter_default_vehicle_dynamics_mode(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -634,7 +634,7 @@ mip_cmd_result mip_filter_default_vehicle_dynamics_mode(struct mip_interface* de return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self) +void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self) { insert_mip_function_selector(serializer, self->function); @@ -648,7 +648,7 @@ void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(mip_serializer* } } -void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_command* self) +void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -663,7 +663,7 @@ void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(mip_serializer* } } -void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self) +void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self) { microstrain_insert_float(serializer, self->roll); @@ -672,7 +672,7 @@ void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(mip_serializer* microstrain_insert_float(serializer, self->yaw); } -void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self) +void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self) { microstrain_extract_float(serializer, &self->roll); @@ -684,9 +684,9 @@ void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(mip_serializer mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float roll, float pitch, float yaw) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -703,9 +703,9 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(struct mip_inte } mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -717,8 +717,8 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_inter if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(roll_out); microstrain_extract_float(&deserializer, roll_out); @@ -736,9 +736,9 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_inter } mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_euler(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -749,9 +749,9 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_euler(struct mip_inter } mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_euler(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -762,9 +762,9 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_euler(struct mip_inter } mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -773,7 +773,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(struct mip_in return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_command* self) +void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_command* self) { insert_mip_function_selector(serializer, self->function); @@ -784,7 +784,7 @@ void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(mip_serializer* se } } -void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_command* self) +void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -796,13 +796,13 @@ void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(mip_serializer* s } } -void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self) +void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->dcm[i]); } -void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self) +void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->dcm[i]); @@ -811,9 +811,9 @@ void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(mip_serializer* mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, const float* dcm) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -828,9 +828,9 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(struct mip_interf } mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, float* dcm_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -842,8 +842,8 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interfa if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(dcm_out || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -856,9 +856,9 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interfa } mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_dcm(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -869,9 +869,9 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_dcm(struct mip_interfa } mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_dcm(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -882,9 +882,9 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_dcm(struct mip_interfa } mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -893,7 +893,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(struct mip_inte return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_command* self) +void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_command* self) { insert_mip_function_selector(serializer, self->function); @@ -904,7 +904,7 @@ void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(mip_seriali } } -void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_command* self) +void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -916,13 +916,13 @@ void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(mip_serial } } -void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) +void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) { for(unsigned int i=0; i < 4; i++) microstrain_insert_float(serializer, self->quat[i]); } -void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) +void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) { for(unsigned int i=0; i < 4; i++) microstrain_extract_float(serializer, &self->quat[i]); @@ -931,9 +931,9 @@ void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(mip_seria mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, const float* quat) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -948,9 +948,9 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(struct mip } mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, float* quat_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -962,8 +962,8 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_ if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(quat_out || (4 == 0)); for(unsigned int i=0; i < 4; i++) @@ -976,9 +976,9 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_ } mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -989,9 +989,9 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_quaternion(struct mip_ } mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1002,9 +1002,9 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_quaternion(struct mip_ } mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1013,7 +1013,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(struct m return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_sensor_to_vehicle_offset_command(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_command* self) +void insert_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1024,7 +1024,7 @@ void insert_mip_filter_sensor_to_vehicle_offset_command(mip_serializer* serializ } } -void extract_mip_filter_sensor_to_vehicle_offset_command(mip_serializer* serializer, mip_filter_sensor_to_vehicle_offset_command* self) +void extract_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1036,13 +1036,13 @@ void extract_mip_filter_sensor_to_vehicle_offset_command(mip_serializer* seriali } } -void insert_mip_filter_sensor_to_vehicle_offset_response(mip_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self) +void insert_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->offset[i]); } -void extract_mip_filter_sensor_to_vehicle_offset_response(mip_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self) +void extract_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->offset[i]); @@ -1051,9 +1051,9 @@ void extract_mip_filter_sensor_to_vehicle_offset_response(mip_serializer* serial mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(struct mip_interface* device, const float* offset) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1068,9 +1068,9 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(struct mip_interface* d } mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* device, float* offset_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1082,8 +1082,8 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* de if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(offset_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1096,9 +1096,9 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* de } mip_cmd_result mip_filter_save_sensor_to_vehicle_offset(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1109,9 +1109,9 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_offset(struct mip_interface* de } mip_cmd_result mip_filter_load_sensor_to_vehicle_offset(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1122,9 +1122,9 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_offset(struct mip_interface* de } mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1133,7 +1133,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(struct mip_interface* return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_antenna_offset_command(mip_serializer* serializer, const mip_filter_antenna_offset_command* self) +void insert_mip_filter_antenna_offset_command(microstrain_serializer* serializer, const mip_filter_antenna_offset_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1144,7 +1144,7 @@ void insert_mip_filter_antenna_offset_command(mip_serializer* serializer, const } } -void extract_mip_filter_antenna_offset_command(mip_serializer* serializer, mip_filter_antenna_offset_command* self) +void extract_mip_filter_antenna_offset_command(microstrain_serializer* serializer, mip_filter_antenna_offset_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1156,13 +1156,13 @@ void extract_mip_filter_antenna_offset_command(mip_serializer* serializer, mip_f } } -void insert_mip_filter_antenna_offset_response(mip_serializer* serializer, const mip_filter_antenna_offset_response* self) +void insert_mip_filter_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_antenna_offset_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->offset[i]); } -void extract_mip_filter_antenna_offset_response(mip_serializer* serializer, mip_filter_antenna_offset_response* self) +void extract_mip_filter_antenna_offset_response(microstrain_serializer* serializer, mip_filter_antenna_offset_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->offset[i]); @@ -1171,9 +1171,9 @@ void extract_mip_filter_antenna_offset_response(mip_serializer* serializer, mip_ mip_cmd_result mip_filter_write_antenna_offset(struct mip_interface* device, const float* offset) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1188,9 +1188,9 @@ mip_cmd_result mip_filter_write_antenna_offset(struct mip_interface* device, con } mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, float* offset_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1202,8 +1202,8 @@ mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, floa if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(offset_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1216,9 +1216,9 @@ mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, floa } mip_cmd_result mip_filter_save_antenna_offset(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1229,9 +1229,9 @@ mip_cmd_result mip_filter_save_antenna_offset(struct mip_interface* device) } mip_cmd_result mip_filter_load_antenna_offset(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1242,9 +1242,9 @@ mip_cmd_result mip_filter_load_antenna_offset(struct mip_interface* device) } mip_cmd_result mip_filter_default_antenna_offset(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1253,7 +1253,7 @@ mip_cmd_result mip_filter_default_antenna_offset(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_gnss_source_command(mip_serializer* serializer, const mip_filter_gnss_source_command* self) +void insert_mip_filter_gnss_source_command(microstrain_serializer* serializer, const mip_filter_gnss_source_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1263,7 +1263,7 @@ void insert_mip_filter_gnss_source_command(mip_serializer* serializer, const mip } } -void extract_mip_filter_gnss_source_command(mip_serializer* serializer, mip_filter_gnss_source_command* self) +void extract_mip_filter_gnss_source_command(microstrain_serializer* serializer, mip_filter_gnss_source_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1274,22 +1274,22 @@ void extract_mip_filter_gnss_source_command(mip_serializer* serializer, mip_filt } } -void insert_mip_filter_gnss_source_response(mip_serializer* serializer, const mip_filter_gnss_source_response* self) +void insert_mip_filter_gnss_source_response(microstrain_serializer* serializer, const mip_filter_gnss_source_response* self) { insert_mip_filter_gnss_source_command_source(serializer, self->source); } -void extract_mip_filter_gnss_source_response(mip_serializer* serializer, mip_filter_gnss_source_response* self) +void extract_mip_filter_gnss_source_response(microstrain_serializer* serializer, mip_filter_gnss_source_response* self) { extract_mip_filter_gnss_source_command_source(serializer, &self->source); } -void insert_mip_filter_gnss_source_command_source(struct mip_serializer* serializer, const mip_filter_gnss_source_command_source self) +void insert_mip_filter_gnss_source_command_source(struct microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_gnss_source_command_source(struct mip_serializer* serializer, mip_filter_gnss_source_command_source* self) +void extract_mip_filter_gnss_source_command_source(struct microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1298,9 +1298,9 @@ void extract_mip_filter_gnss_source_command_source(struct mip_serializer* serial mip_cmd_result mip_filter_write_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1313,9 +1313,9 @@ mip_cmd_result mip_filter_write_gnss_source(struct mip_interface* device, mip_fi } mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source* source_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1327,8 +1327,8 @@ mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_fil if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(source_out); extract_mip_filter_gnss_source_command_source(&deserializer, source_out); @@ -1340,9 +1340,9 @@ mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_fil } mip_cmd_result mip_filter_save_gnss_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1353,9 +1353,9 @@ mip_cmd_result mip_filter_save_gnss_source(struct mip_interface* device) } mip_cmd_result mip_filter_load_gnss_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1366,9 +1366,9 @@ mip_cmd_result mip_filter_load_gnss_source(struct mip_interface* device) } mip_cmd_result mip_filter_default_gnss_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1377,7 +1377,7 @@ mip_cmd_result mip_filter_default_gnss_source(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_heading_source_command(mip_serializer* serializer, const mip_filter_heading_source_command* self) +void insert_mip_filter_heading_source_command(microstrain_serializer* serializer, const mip_filter_heading_source_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1387,7 +1387,7 @@ void insert_mip_filter_heading_source_command(mip_serializer* serializer, const } } -void extract_mip_filter_heading_source_command(mip_serializer* serializer, mip_filter_heading_source_command* self) +void extract_mip_filter_heading_source_command(microstrain_serializer* serializer, mip_filter_heading_source_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1398,22 +1398,22 @@ void extract_mip_filter_heading_source_command(mip_serializer* serializer, mip_f } } -void insert_mip_filter_heading_source_response(mip_serializer* serializer, const mip_filter_heading_source_response* self) +void insert_mip_filter_heading_source_response(microstrain_serializer* serializer, const mip_filter_heading_source_response* self) { insert_mip_filter_heading_source_command_source(serializer, self->source); } -void extract_mip_filter_heading_source_response(mip_serializer* serializer, mip_filter_heading_source_response* self) +void extract_mip_filter_heading_source_response(microstrain_serializer* serializer, mip_filter_heading_source_response* self) { extract_mip_filter_heading_source_command_source(serializer, &self->source); } -void insert_mip_filter_heading_source_command_source(struct mip_serializer* serializer, const mip_filter_heading_source_command_source self) +void insert_mip_filter_heading_source_command_source(struct microstrain_serializer* serializer, const mip_filter_heading_source_command_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_heading_source_command_source(struct mip_serializer* serializer, mip_filter_heading_source_command_source* self) +void extract_mip_filter_heading_source_command_source(struct microstrain_serializer* serializer, mip_filter_heading_source_command_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1422,9 +1422,9 @@ void extract_mip_filter_heading_source_command_source(struct mip_serializer* ser mip_cmd_result mip_filter_write_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1437,9 +1437,9 @@ mip_cmd_result mip_filter_write_heading_source(struct mip_interface* device, mip } mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source* source_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1451,8 +1451,8 @@ mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_ if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(source_out); extract_mip_filter_heading_source_command_source(&deserializer, source_out); @@ -1464,9 +1464,9 @@ mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_ } mip_cmd_result mip_filter_save_heading_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1477,9 +1477,9 @@ mip_cmd_result mip_filter_save_heading_source(struct mip_interface* device) } mip_cmd_result mip_filter_load_heading_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1490,9 +1490,9 @@ mip_cmd_result mip_filter_load_heading_source(struct mip_interface* device) } mip_cmd_result mip_filter_default_heading_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1501,7 +1501,7 @@ mip_cmd_result mip_filter_default_heading_source(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_auto_init_control_command(mip_serializer* serializer, const mip_filter_auto_init_control_command* self) +void insert_mip_filter_auto_init_control_command(microstrain_serializer* serializer, const mip_filter_auto_init_control_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1511,7 +1511,7 @@ void insert_mip_filter_auto_init_control_command(mip_serializer* serializer, con } } -void extract_mip_filter_auto_init_control_command(mip_serializer* serializer, mip_filter_auto_init_control_command* self) +void extract_mip_filter_auto_init_control_command(microstrain_serializer* serializer, mip_filter_auto_init_control_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1522,12 +1522,12 @@ void extract_mip_filter_auto_init_control_command(mip_serializer* serializer, mi } } -void insert_mip_filter_auto_init_control_response(mip_serializer* serializer, const mip_filter_auto_init_control_response* self) +void insert_mip_filter_auto_init_control_response(microstrain_serializer* serializer, const mip_filter_auto_init_control_response* self) { microstrain_insert_u8(serializer, self->enable); } -void extract_mip_filter_auto_init_control_response(mip_serializer* serializer, mip_filter_auto_init_control_response* self) +void extract_mip_filter_auto_init_control_response(microstrain_serializer* serializer, mip_filter_auto_init_control_response* self) { microstrain_extract_u8(serializer, &self->enable); @@ -1535,9 +1535,9 @@ void extract_mip_filter_auto_init_control_response(mip_serializer* serializer, m mip_cmd_result mip_filter_write_auto_init_control(struct mip_interface* device, uint8_t enable) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1550,9 +1550,9 @@ mip_cmd_result mip_filter_write_auto_init_control(struct mip_interface* device, } mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, uint8_t* enable_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1564,8 +1564,8 @@ mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, u if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); @@ -1577,9 +1577,9 @@ mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, u } mip_cmd_result mip_filter_save_auto_init_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1590,9 +1590,9 @@ mip_cmd_result mip_filter_save_auto_init_control(struct mip_interface* device) } mip_cmd_result mip_filter_load_auto_init_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1603,9 +1603,9 @@ mip_cmd_result mip_filter_load_auto_init_control(struct mip_interface* device) } mip_cmd_result mip_filter_default_auto_init_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1614,7 +1614,7 @@ mip_cmd_result mip_filter_default_auto_init_control(struct mip_interface* device return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_accel_noise_command(mip_serializer* serializer, const mip_filter_accel_noise_command* self) +void insert_mip_filter_accel_noise_command(microstrain_serializer* serializer, const mip_filter_accel_noise_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1625,7 +1625,7 @@ void insert_mip_filter_accel_noise_command(mip_serializer* serializer, const mip } } -void extract_mip_filter_accel_noise_command(mip_serializer* serializer, mip_filter_accel_noise_command* self) +void extract_mip_filter_accel_noise_command(microstrain_serializer* serializer, mip_filter_accel_noise_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1637,13 +1637,13 @@ void extract_mip_filter_accel_noise_command(mip_serializer* serializer, mip_filt } } -void insert_mip_filter_accel_noise_response(mip_serializer* serializer, const mip_filter_accel_noise_response* self) +void insert_mip_filter_accel_noise_response(microstrain_serializer* serializer, const mip_filter_accel_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->noise[i]); } -void extract_mip_filter_accel_noise_response(mip_serializer* serializer, mip_filter_accel_noise_response* self) +void extract_mip_filter_accel_noise_response(microstrain_serializer* serializer, mip_filter_accel_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->noise[i]); @@ -1652,9 +1652,9 @@ void extract_mip_filter_accel_noise_response(mip_serializer* serializer, mip_fil mip_cmd_result mip_filter_write_accel_noise(struct mip_interface* device, const float* noise) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1669,9 +1669,9 @@ mip_cmd_result mip_filter_write_accel_noise(struct mip_interface* device, const } mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* noise_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1683,8 +1683,8 @@ mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1697,9 +1697,9 @@ mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* } mip_cmd_result mip_filter_save_accel_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1710,9 +1710,9 @@ mip_cmd_result mip_filter_save_accel_noise(struct mip_interface* device) } mip_cmd_result mip_filter_load_accel_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1723,9 +1723,9 @@ mip_cmd_result mip_filter_load_accel_noise(struct mip_interface* device) } mip_cmd_result mip_filter_default_accel_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1734,7 +1734,7 @@ mip_cmd_result mip_filter_default_accel_noise(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_gyro_noise_command(mip_serializer* serializer, const mip_filter_gyro_noise_command* self) +void insert_mip_filter_gyro_noise_command(microstrain_serializer* serializer, const mip_filter_gyro_noise_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1745,7 +1745,7 @@ void insert_mip_filter_gyro_noise_command(mip_serializer* serializer, const mip_ } } -void extract_mip_filter_gyro_noise_command(mip_serializer* serializer, mip_filter_gyro_noise_command* self) +void extract_mip_filter_gyro_noise_command(microstrain_serializer* serializer, mip_filter_gyro_noise_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1757,13 +1757,13 @@ void extract_mip_filter_gyro_noise_command(mip_serializer* serializer, mip_filte } } -void insert_mip_filter_gyro_noise_response(mip_serializer* serializer, const mip_filter_gyro_noise_response* self) +void insert_mip_filter_gyro_noise_response(microstrain_serializer* serializer, const mip_filter_gyro_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->noise[i]); } -void extract_mip_filter_gyro_noise_response(mip_serializer* serializer, mip_filter_gyro_noise_response* self) +void extract_mip_filter_gyro_noise_response(microstrain_serializer* serializer, mip_filter_gyro_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->noise[i]); @@ -1772,9 +1772,9 @@ void extract_mip_filter_gyro_noise_response(mip_serializer* serializer, mip_filt mip_cmd_result mip_filter_write_gyro_noise(struct mip_interface* device, const float* noise) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1789,9 +1789,9 @@ mip_cmd_result mip_filter_write_gyro_noise(struct mip_interface* device, const f } mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* noise_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1803,8 +1803,8 @@ mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* n if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1817,9 +1817,9 @@ mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* n } mip_cmd_result mip_filter_save_gyro_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1830,9 +1830,9 @@ mip_cmd_result mip_filter_save_gyro_noise(struct mip_interface* device) } mip_cmd_result mip_filter_load_gyro_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1843,9 +1843,9 @@ mip_cmd_result mip_filter_load_gyro_noise(struct mip_interface* device) } mip_cmd_result mip_filter_default_gyro_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1854,7 +1854,7 @@ mip_cmd_result mip_filter_default_gyro_noise(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_accel_bias_model_command(mip_serializer* serializer, const mip_filter_accel_bias_model_command* self) +void insert_mip_filter_accel_bias_model_command(microstrain_serializer* serializer, const mip_filter_accel_bias_model_command* self) { insert_mip_function_selector(serializer, self->function); @@ -1868,7 +1868,7 @@ void insert_mip_filter_accel_bias_model_command(mip_serializer* serializer, cons } } -void extract_mip_filter_accel_bias_model_command(mip_serializer* serializer, mip_filter_accel_bias_model_command* self) +void extract_mip_filter_accel_bias_model_command(microstrain_serializer* serializer, mip_filter_accel_bias_model_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -1883,7 +1883,7 @@ void extract_mip_filter_accel_bias_model_command(mip_serializer* serializer, mip } } -void insert_mip_filter_accel_bias_model_response(mip_serializer* serializer, const mip_filter_accel_bias_model_response* self) +void insert_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, const mip_filter_accel_bias_model_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->beta[i]); @@ -1892,7 +1892,7 @@ void insert_mip_filter_accel_bias_model_response(mip_serializer* serializer, con microstrain_insert_float(serializer, self->noise[i]); } -void extract_mip_filter_accel_bias_model_response(mip_serializer* serializer, mip_filter_accel_bias_model_response* self) +void extract_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, mip_filter_accel_bias_model_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->beta[i]); @@ -1904,9 +1904,9 @@ void extract_mip_filter_accel_bias_model_response(mip_serializer* serializer, mi mip_cmd_result mip_filter_write_accel_bias_model(struct mip_interface* device, const float* beta, const float* noise) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -1925,9 +1925,9 @@ mip_cmd_result mip_filter_write_accel_bias_model(struct mip_interface* device, c } mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, float* beta_out, float* noise_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -1939,8 +1939,8 @@ mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, fl if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(beta_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1957,9 +1957,9 @@ mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, fl } mip_cmd_result mip_filter_save_accel_bias_model(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -1970,9 +1970,9 @@ mip_cmd_result mip_filter_save_accel_bias_model(struct mip_interface* device) } mip_cmd_result mip_filter_load_accel_bias_model(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -1983,9 +1983,9 @@ mip_cmd_result mip_filter_load_accel_bias_model(struct mip_interface* device) } mip_cmd_result mip_filter_default_accel_bias_model(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -1994,7 +1994,7 @@ mip_cmd_result mip_filter_default_accel_bias_model(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_gyro_bias_model_command(mip_serializer* serializer, const mip_filter_gyro_bias_model_command* self) +void insert_mip_filter_gyro_bias_model_command(microstrain_serializer* serializer, const mip_filter_gyro_bias_model_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2008,7 +2008,7 @@ void insert_mip_filter_gyro_bias_model_command(mip_serializer* serializer, const } } -void extract_mip_filter_gyro_bias_model_command(mip_serializer* serializer, mip_filter_gyro_bias_model_command* self) +void extract_mip_filter_gyro_bias_model_command(microstrain_serializer* serializer, mip_filter_gyro_bias_model_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2023,7 +2023,7 @@ void extract_mip_filter_gyro_bias_model_command(mip_serializer* serializer, mip_ } } -void insert_mip_filter_gyro_bias_model_response(mip_serializer* serializer, const mip_filter_gyro_bias_model_response* self) +void insert_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, const mip_filter_gyro_bias_model_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->beta[i]); @@ -2032,7 +2032,7 @@ void insert_mip_filter_gyro_bias_model_response(mip_serializer* serializer, cons microstrain_insert_float(serializer, self->noise[i]); } -void extract_mip_filter_gyro_bias_model_response(mip_serializer* serializer, mip_filter_gyro_bias_model_response* self) +void extract_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, mip_filter_gyro_bias_model_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->beta[i]); @@ -2044,9 +2044,9 @@ void extract_mip_filter_gyro_bias_model_response(mip_serializer* serializer, mip mip_cmd_result mip_filter_write_gyro_bias_model(struct mip_interface* device, const float* beta, const float* noise) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2065,9 +2065,9 @@ mip_cmd_result mip_filter_write_gyro_bias_model(struct mip_interface* device, co } mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, float* beta_out, float* noise_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2079,8 +2079,8 @@ mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, flo if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(beta_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2097,9 +2097,9 @@ mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, flo } mip_cmd_result mip_filter_save_gyro_bias_model(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2110,9 +2110,9 @@ mip_cmd_result mip_filter_save_gyro_bias_model(struct mip_interface* device) } mip_cmd_result mip_filter_load_gyro_bias_model(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2123,9 +2123,9 @@ mip_cmd_result mip_filter_load_gyro_bias_model(struct mip_interface* device) } mip_cmd_result mip_filter_default_gyro_bias_model(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2134,7 +2134,7 @@ mip_cmd_result mip_filter_default_gyro_bias_model(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_altitude_aiding_command(mip_serializer* serializer, const mip_filter_altitude_aiding_command* self) +void insert_mip_filter_altitude_aiding_command(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2144,7 +2144,7 @@ void insert_mip_filter_altitude_aiding_command(mip_serializer* serializer, const } } -void extract_mip_filter_altitude_aiding_command(mip_serializer* serializer, mip_filter_altitude_aiding_command* self) +void extract_mip_filter_altitude_aiding_command(microstrain_serializer* serializer, mip_filter_altitude_aiding_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2155,22 +2155,22 @@ void extract_mip_filter_altitude_aiding_command(mip_serializer* serializer, mip_ } } -void insert_mip_filter_altitude_aiding_response(mip_serializer* serializer, const mip_filter_altitude_aiding_response* self) +void insert_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, const mip_filter_altitude_aiding_response* self) { insert_mip_filter_altitude_aiding_command_aiding_selector(serializer, self->selector); } -void extract_mip_filter_altitude_aiding_response(mip_serializer* serializer, mip_filter_altitude_aiding_response* self) +void extract_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, mip_filter_altitude_aiding_response* self) { extract_mip_filter_altitude_aiding_command_aiding_selector(serializer, &self->selector); } -void insert_mip_filter_altitude_aiding_command_aiding_selector(struct mip_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self) +void insert_mip_filter_altitude_aiding_command_aiding_selector(struct microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_altitude_aiding_command_aiding_selector(struct mip_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self) +void extract_mip_filter_altitude_aiding_command_aiding_selector(struct microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2179,9 +2179,9 @@ void extract_mip_filter_altitude_aiding_command_aiding_selector(struct mip_seria mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector selector) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2194,9 +2194,9 @@ mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, mi } mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector* selector_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2208,8 +2208,8 @@ mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(selector_out); extract_mip_filter_altitude_aiding_command_aiding_selector(&deserializer, selector_out); @@ -2221,9 +2221,9 @@ mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip } mip_cmd_result mip_filter_save_altitude_aiding(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2234,9 +2234,9 @@ mip_cmd_result mip_filter_save_altitude_aiding(struct mip_interface* device) } mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2247,9 +2247,9 @@ mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device) } mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2258,7 +2258,7 @@ mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_pitch_roll_aiding_command(mip_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self) +void insert_mip_filter_pitch_roll_aiding_command(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2268,7 +2268,7 @@ void insert_mip_filter_pitch_roll_aiding_command(mip_serializer* serializer, con } } -void extract_mip_filter_pitch_roll_aiding_command(mip_serializer* serializer, mip_filter_pitch_roll_aiding_command* self) +void extract_mip_filter_pitch_roll_aiding_command(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2279,22 +2279,22 @@ void extract_mip_filter_pitch_roll_aiding_command(mip_serializer* serializer, mi } } -void insert_mip_filter_pitch_roll_aiding_response(mip_serializer* serializer, const mip_filter_pitch_roll_aiding_response* self) +void insert_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_response* self) { insert_mip_filter_pitch_roll_aiding_command_aiding_source(serializer, self->source); } -void extract_mip_filter_pitch_roll_aiding_response(mip_serializer* serializer, mip_filter_pitch_roll_aiding_response* self) +void extract_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_response* self) { extract_mip_filter_pitch_roll_aiding_command_aiding_source(serializer, &self->source); } -void insert_mip_filter_pitch_roll_aiding_command_aiding_source(struct mip_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self) +void insert_mip_filter_pitch_roll_aiding_command_aiding_source(struct microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_pitch_roll_aiding_command_aiding_source(struct mip_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self) +void extract_mip_filter_pitch_roll_aiding_command_aiding_source(struct microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2303,9 +2303,9 @@ void extract_mip_filter_pitch_roll_aiding_command_aiding_source(struct mip_seria mip_cmd_result mip_filter_write_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2318,9 +2318,9 @@ mip_cmd_result mip_filter_write_pitch_roll_aiding(struct mip_interface* device, } mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source* source_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2332,8 +2332,8 @@ mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, m if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(source_out); extract_mip_filter_pitch_roll_aiding_command_aiding_source(&deserializer, source_out); @@ -2345,9 +2345,9 @@ mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, m } mip_cmd_result mip_filter_save_pitch_roll_aiding(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2358,9 +2358,9 @@ mip_cmd_result mip_filter_save_pitch_roll_aiding(struct mip_interface* device) } mip_cmd_result mip_filter_load_pitch_roll_aiding(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2371,9 +2371,9 @@ mip_cmd_result mip_filter_load_pitch_roll_aiding(struct mip_interface* device) } mip_cmd_result mip_filter_default_pitch_roll_aiding(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2382,7 +2382,7 @@ mip_cmd_result mip_filter_default_pitch_roll_aiding(struct mip_interface* device return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_auto_zupt_command(mip_serializer* serializer, const mip_filter_auto_zupt_command* self) +void insert_mip_filter_auto_zupt_command(microstrain_serializer* serializer, const mip_filter_auto_zupt_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2394,7 +2394,7 @@ void insert_mip_filter_auto_zupt_command(mip_serializer* serializer, const mip_f } } -void extract_mip_filter_auto_zupt_command(mip_serializer* serializer, mip_filter_auto_zupt_command* self) +void extract_mip_filter_auto_zupt_command(microstrain_serializer* serializer, mip_filter_auto_zupt_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2407,14 +2407,14 @@ void extract_mip_filter_auto_zupt_command(mip_serializer* serializer, mip_filter } } -void insert_mip_filter_auto_zupt_response(mip_serializer* serializer, const mip_filter_auto_zupt_response* self) +void insert_mip_filter_auto_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_zupt_response* self) { microstrain_insert_u8(serializer, self->enable); microstrain_insert_float(serializer, self->threshold); } -void extract_mip_filter_auto_zupt_response(mip_serializer* serializer, mip_filter_auto_zupt_response* self) +void extract_mip_filter_auto_zupt_response(microstrain_serializer* serializer, mip_filter_auto_zupt_response* self) { microstrain_extract_u8(serializer, &self->enable); @@ -2424,9 +2424,9 @@ void extract_mip_filter_auto_zupt_response(mip_serializer* serializer, mip_filte mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t enable, float threshold) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2441,9 +2441,9 @@ mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t } mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2455,8 +2455,8 @@ mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); @@ -2471,9 +2471,9 @@ mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* } mip_cmd_result mip_filter_save_auto_zupt(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2484,9 +2484,9 @@ mip_cmd_result mip_filter_save_auto_zupt(struct mip_interface* device) } mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2497,9 +2497,9 @@ mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device) } mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2508,7 +2508,7 @@ mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, const mip_filter_auto_angular_zupt_command* self) +void insert_mip_filter_auto_angular_zupt_command(microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2520,7 +2520,7 @@ void insert_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, con } } -void extract_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, mip_filter_auto_angular_zupt_command* self) +void extract_mip_filter_auto_angular_zupt_command(microstrain_serializer* serializer, mip_filter_auto_angular_zupt_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2533,14 +2533,14 @@ void extract_mip_filter_auto_angular_zupt_command(mip_serializer* serializer, mi } } -void insert_mip_filter_auto_angular_zupt_response(mip_serializer* serializer, const mip_filter_auto_angular_zupt_response* self) +void insert_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_response* self) { microstrain_insert_u8(serializer, self->enable); microstrain_insert_float(serializer, self->threshold); } -void extract_mip_filter_auto_angular_zupt_response(mip_serializer* serializer, mip_filter_auto_angular_zupt_response* self) +void extract_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, mip_filter_auto_angular_zupt_response* self) { microstrain_extract_u8(serializer, &self->enable); @@ -2550,9 +2550,9 @@ void extract_mip_filter_auto_angular_zupt_response(mip_serializer* serializer, m mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, uint8_t enable, float threshold) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2567,9 +2567,9 @@ mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, } mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2581,8 +2581,8 @@ mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, u if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); @@ -2597,9 +2597,9 @@ mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, u } mip_cmd_result mip_filter_save_auto_angular_zupt(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2610,9 +2610,9 @@ mip_cmd_result mip_filter_save_auto_angular_zupt(struct mip_interface* device) } mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2623,9 +2623,9 @@ mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device) } mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2642,12 +2642,12 @@ mip_cmd_result mip_filter_commanded_angular_zupt(struct mip_interface* device) { return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_COMMANDED_ANGULAR_ZUPT, NULL, 0); } -void insert_mip_filter_mag_capture_auto_cal_command(mip_serializer* serializer, const mip_filter_mag_capture_auto_cal_command* self) +void insert_mip_filter_mag_capture_auto_cal_command(microstrain_serializer* serializer, const mip_filter_mag_capture_auto_cal_command* self) { insert_mip_function_selector(serializer, self->function); } -void extract_mip_filter_mag_capture_auto_cal_command(mip_serializer* serializer, mip_filter_mag_capture_auto_cal_command* self) +void extract_mip_filter_mag_capture_auto_cal_command(microstrain_serializer* serializer, mip_filter_mag_capture_auto_cal_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2655,9 +2655,9 @@ void extract_mip_filter_mag_capture_auto_cal_command(mip_serializer* serializer, mip_cmd_result mip_filter_write_mag_capture_auto_cal(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2668,9 +2668,9 @@ mip_cmd_result mip_filter_write_mag_capture_auto_cal(struct mip_interface* devic } mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2679,7 +2679,7 @@ mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_gravity_noise_command(mip_serializer* serializer, const mip_filter_gravity_noise_command* self) +void insert_mip_filter_gravity_noise_command(microstrain_serializer* serializer, const mip_filter_gravity_noise_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2690,7 +2690,7 @@ void insert_mip_filter_gravity_noise_command(mip_serializer* serializer, const m } } -void extract_mip_filter_gravity_noise_command(mip_serializer* serializer, mip_filter_gravity_noise_command* self) +void extract_mip_filter_gravity_noise_command(microstrain_serializer* serializer, mip_filter_gravity_noise_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2702,13 +2702,13 @@ void extract_mip_filter_gravity_noise_command(mip_serializer* serializer, mip_fi } } -void insert_mip_filter_gravity_noise_response(mip_serializer* serializer, const mip_filter_gravity_noise_response* self) +void insert_mip_filter_gravity_noise_response(microstrain_serializer* serializer, const mip_filter_gravity_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->noise[i]); } -void extract_mip_filter_gravity_noise_response(mip_serializer* serializer, mip_filter_gravity_noise_response* self) +void extract_mip_filter_gravity_noise_response(microstrain_serializer* serializer, mip_filter_gravity_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->noise[i]); @@ -2717,9 +2717,9 @@ void extract_mip_filter_gravity_noise_response(mip_serializer* serializer, mip_f mip_cmd_result mip_filter_write_gravity_noise(struct mip_interface* device, const float* noise) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2734,9 +2734,9 @@ mip_cmd_result mip_filter_write_gravity_noise(struct mip_interface* device, cons } mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float* noise_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2748,8 +2748,8 @@ mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2762,9 +2762,9 @@ mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float } mip_cmd_result mip_filter_save_gravity_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2775,9 +2775,9 @@ mip_cmd_result mip_filter_save_gravity_noise(struct mip_interface* device) } mip_cmd_result mip_filter_load_gravity_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2788,9 +2788,9 @@ mip_cmd_result mip_filter_load_gravity_noise(struct mip_interface* device) } mip_cmd_result mip_filter_default_gravity_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2799,7 +2799,7 @@ mip_cmd_result mip_filter_default_gravity_noise(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_pressure_altitude_noise_command(mip_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self) +void insert_mip_filter_pressure_altitude_noise_command(microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2809,7 +2809,7 @@ void insert_mip_filter_pressure_altitude_noise_command(mip_serializer* serialize } } -void extract_mip_filter_pressure_altitude_noise_command(mip_serializer* serializer, mip_filter_pressure_altitude_noise_command* self) +void extract_mip_filter_pressure_altitude_noise_command(microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2820,12 +2820,12 @@ void extract_mip_filter_pressure_altitude_noise_command(mip_serializer* serializ } } -void insert_mip_filter_pressure_altitude_noise_response(mip_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self) +void insert_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self) { microstrain_insert_float(serializer, self->noise); } -void extract_mip_filter_pressure_altitude_noise_response(mip_serializer* serializer, mip_filter_pressure_altitude_noise_response* self) +void extract_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_response* self) { microstrain_extract_float(serializer, &self->noise); @@ -2833,9 +2833,9 @@ void extract_mip_filter_pressure_altitude_noise_response(mip_serializer* seriali mip_cmd_result mip_filter_write_pressure_altitude_noise(struct mip_interface* device, float noise) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2848,9 +2848,9 @@ mip_cmd_result mip_filter_write_pressure_altitude_noise(struct mip_interface* de } mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* device, float* noise_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2862,8 +2862,8 @@ mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* dev if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(noise_out); microstrain_extract_float(&deserializer, noise_out); @@ -2875,9 +2875,9 @@ mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* dev } mip_cmd_result mip_filter_save_pressure_altitude_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -2888,9 +2888,9 @@ mip_cmd_result mip_filter_save_pressure_altitude_noise(struct mip_interface* dev } mip_cmd_result mip_filter_load_pressure_altitude_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -2901,9 +2901,9 @@ mip_cmd_result mip_filter_load_pressure_altitude_noise(struct mip_interface* dev } mip_cmd_result mip_filter_default_pressure_altitude_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -2912,7 +2912,7 @@ mip_cmd_result mip_filter_default_pressure_altitude_noise(struct mip_interface* return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_hard_iron_offset_noise_command(mip_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self) +void insert_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2923,7 +2923,7 @@ void insert_mip_filter_hard_iron_offset_noise_command(mip_serializer* serializer } } -void extract_mip_filter_hard_iron_offset_noise_command(mip_serializer* serializer, mip_filter_hard_iron_offset_noise_command* self) +void extract_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -2935,13 +2935,13 @@ void extract_mip_filter_hard_iron_offset_noise_command(mip_serializer* serialize } } -void insert_mip_filter_hard_iron_offset_noise_response(mip_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self) +void insert_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->noise[i]); } -void extract_mip_filter_hard_iron_offset_noise_response(mip_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self) +void extract_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->noise[i]); @@ -2950,9 +2950,9 @@ void extract_mip_filter_hard_iron_offset_noise_response(mip_serializer* serializ mip_cmd_result mip_filter_write_hard_iron_offset_noise(struct mip_interface* device, const float* noise) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -2967,9 +2967,9 @@ mip_cmd_result mip_filter_write_hard_iron_offset_noise(struct mip_interface* dev } mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* device, float* noise_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -2981,8 +2981,8 @@ mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* devi if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2995,9 +2995,9 @@ mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* devi } mip_cmd_result mip_filter_save_hard_iron_offset_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3008,9 +3008,9 @@ mip_cmd_result mip_filter_save_hard_iron_offset_noise(struct mip_interface* devi } mip_cmd_result mip_filter_load_hard_iron_offset_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3021,9 +3021,9 @@ mip_cmd_result mip_filter_load_hard_iron_offset_noise(struct mip_interface* devi } mip_cmd_result mip_filter_default_hard_iron_offset_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3032,7 +3032,7 @@ mip_cmd_result mip_filter_default_hard_iron_offset_noise(struct mip_interface* d return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self) +void insert_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3043,7 +3043,7 @@ void insert_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serializer } } -void extract_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serializer, mip_filter_soft_iron_matrix_noise_command* self) +void extract_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3055,13 +3055,13 @@ void extract_mip_filter_soft_iron_matrix_noise_command(mip_serializer* serialize } } -void insert_mip_filter_soft_iron_matrix_noise_response(mip_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self) +void insert_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->noise[i]); } -void extract_mip_filter_soft_iron_matrix_noise_response(mip_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self) +void extract_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->noise[i]); @@ -3070,9 +3070,9 @@ void extract_mip_filter_soft_iron_matrix_noise_response(mip_serializer* serializ mip_cmd_result mip_filter_write_soft_iron_matrix_noise(struct mip_interface* device, const float* noise) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3087,9 +3087,9 @@ mip_cmd_result mip_filter_write_soft_iron_matrix_noise(struct mip_interface* dev } mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* device, float* noise_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3101,8 +3101,8 @@ mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* devi if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(noise_out || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -3115,9 +3115,9 @@ mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* devi } mip_cmd_result mip_filter_save_soft_iron_matrix_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3128,9 +3128,9 @@ mip_cmd_result mip_filter_save_soft_iron_matrix_noise(struct mip_interface* devi } mip_cmd_result mip_filter_load_soft_iron_matrix_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3141,9 +3141,9 @@ mip_cmd_result mip_filter_load_soft_iron_matrix_noise(struct mip_interface* devi } mip_cmd_result mip_filter_default_soft_iron_matrix_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3152,7 +3152,7 @@ mip_cmd_result mip_filter_default_soft_iron_matrix_noise(struct mip_interface* d return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_mag_noise_command(mip_serializer* serializer, const mip_filter_mag_noise_command* self) +void insert_mip_filter_mag_noise_command(microstrain_serializer* serializer, const mip_filter_mag_noise_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3163,7 +3163,7 @@ void insert_mip_filter_mag_noise_command(mip_serializer* serializer, const mip_f } } -void extract_mip_filter_mag_noise_command(mip_serializer* serializer, mip_filter_mag_noise_command* self) +void extract_mip_filter_mag_noise_command(microstrain_serializer* serializer, mip_filter_mag_noise_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3175,13 +3175,13 @@ void extract_mip_filter_mag_noise_command(mip_serializer* serializer, mip_filter } } -void insert_mip_filter_mag_noise_response(mip_serializer* serializer, const mip_filter_mag_noise_response* self) +void insert_mip_filter_mag_noise_response(microstrain_serializer* serializer, const mip_filter_mag_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->noise[i]); } -void extract_mip_filter_mag_noise_response(mip_serializer* serializer, mip_filter_mag_noise_response* self) +void extract_mip_filter_mag_noise_response(microstrain_serializer* serializer, mip_filter_mag_noise_response* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->noise[i]); @@ -3190,9 +3190,9 @@ void extract_mip_filter_mag_noise_response(mip_serializer* serializer, mip_filte mip_cmd_result mip_filter_write_mag_noise(struct mip_interface* device, const float* noise) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3207,9 +3207,9 @@ mip_cmd_result mip_filter_write_mag_noise(struct mip_interface* device, const fl } mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* noise_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3221,8 +3221,8 @@ mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* no if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(noise_out || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3235,9 +3235,9 @@ mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* no } mip_cmd_result mip_filter_save_mag_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3248,9 +3248,9 @@ mip_cmd_result mip_filter_save_mag_noise(struct mip_interface* device) } mip_cmd_result mip_filter_load_mag_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3261,9 +3261,9 @@ mip_cmd_result mip_filter_load_mag_noise(struct mip_interface* device) } mip_cmd_result mip_filter_default_mag_noise(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3272,7 +3272,7 @@ mip_cmd_result mip_filter_default_mag_noise(struct mip_interface* device) return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_inclination_source_command(mip_serializer* serializer, const mip_filter_inclination_source_command* self) +void insert_mip_filter_inclination_source_command(microstrain_serializer* serializer, const mip_filter_inclination_source_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3284,7 +3284,7 @@ void insert_mip_filter_inclination_source_command(mip_serializer* serializer, co } } -void extract_mip_filter_inclination_source_command(mip_serializer* serializer, mip_filter_inclination_source_command* self) +void extract_mip_filter_inclination_source_command(microstrain_serializer* serializer, mip_filter_inclination_source_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3297,14 +3297,14 @@ void extract_mip_filter_inclination_source_command(mip_serializer* serializer, m } } -void insert_mip_filter_inclination_source_response(mip_serializer* serializer, const mip_filter_inclination_source_response* self) +void insert_mip_filter_inclination_source_response(microstrain_serializer* serializer, const mip_filter_inclination_source_response* self) { insert_mip_filter_mag_param_source(serializer, self->source); microstrain_insert_float(serializer, self->inclination); } -void extract_mip_filter_inclination_source_response(mip_serializer* serializer, mip_filter_inclination_source_response* self) +void extract_mip_filter_inclination_source_response(microstrain_serializer* serializer, mip_filter_inclination_source_response* self) { extract_mip_filter_mag_param_source(serializer, &self->source); @@ -3314,9 +3314,9 @@ void extract_mip_filter_inclination_source_response(mip_serializer* serializer, mip_cmd_result mip_filter_write_inclination_source(struct mip_interface* device, mip_filter_mag_param_source source, float inclination) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3331,9 +3331,9 @@ mip_cmd_result mip_filter_write_inclination_source(struct mip_interface* device, } mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* inclination_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3345,8 +3345,8 @@ mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(source_out); extract_mip_filter_mag_param_source(&deserializer, source_out); @@ -3361,9 +3361,9 @@ mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, } mip_cmd_result mip_filter_save_inclination_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3374,9 +3374,9 @@ mip_cmd_result mip_filter_save_inclination_source(struct mip_interface* device) } mip_cmd_result mip_filter_load_inclination_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3387,9 +3387,9 @@ mip_cmd_result mip_filter_load_inclination_source(struct mip_interface* device) } mip_cmd_result mip_filter_default_inclination_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3398,7 +3398,7 @@ mip_cmd_result mip_filter_default_inclination_source(struct mip_interface* devic return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_magnetic_declination_source_command(mip_serializer* serializer, const mip_filter_magnetic_declination_source_command* self) +void insert_mip_filter_magnetic_declination_source_command(microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3410,7 +3410,7 @@ void insert_mip_filter_magnetic_declination_source_command(mip_serializer* seria } } -void extract_mip_filter_magnetic_declination_source_command(mip_serializer* serializer, mip_filter_magnetic_declination_source_command* self) +void extract_mip_filter_magnetic_declination_source_command(microstrain_serializer* serializer, mip_filter_magnetic_declination_source_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3423,14 +3423,14 @@ void extract_mip_filter_magnetic_declination_source_command(mip_serializer* seri } } -void insert_mip_filter_magnetic_declination_source_response(mip_serializer* serializer, const mip_filter_magnetic_declination_source_response* self) +void insert_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_response* self) { insert_mip_filter_mag_param_source(serializer, self->source); microstrain_insert_float(serializer, self->declination); } -void extract_mip_filter_magnetic_declination_source_response(mip_serializer* serializer, mip_filter_magnetic_declination_source_response* self) +void extract_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, mip_filter_magnetic_declination_source_response* self) { extract_mip_filter_mag_param_source(serializer, &self->source); @@ -3440,9 +3440,9 @@ void extract_mip_filter_magnetic_declination_source_response(mip_serializer* ser mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source source, float declination) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3457,9 +3457,9 @@ mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface } mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* declination_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3471,8 +3471,8 @@ mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(source_out); extract_mip_filter_mag_param_source(&deserializer, source_out); @@ -3487,9 +3487,9 @@ mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* } mip_cmd_result mip_filter_save_magnetic_declination_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3500,9 +3500,9 @@ mip_cmd_result mip_filter_save_magnetic_declination_source(struct mip_interface* } mip_cmd_result mip_filter_load_magnetic_declination_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3513,9 +3513,9 @@ mip_cmd_result mip_filter_load_magnetic_declination_source(struct mip_interface* } mip_cmd_result mip_filter_default_magnetic_declination_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3524,7 +3524,7 @@ mip_cmd_result mip_filter_default_magnetic_declination_source(struct mip_interfa return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_mag_field_magnitude_source_command(mip_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self) +void insert_mip_filter_mag_field_magnitude_source_command(microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3536,7 +3536,7 @@ void insert_mip_filter_mag_field_magnitude_source_command(mip_serializer* serial } } -void extract_mip_filter_mag_field_magnitude_source_command(mip_serializer* serializer, mip_filter_mag_field_magnitude_source_command* self) +void extract_mip_filter_mag_field_magnitude_source_command(microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3549,14 +3549,14 @@ void extract_mip_filter_mag_field_magnitude_source_command(mip_serializer* seria } } -void insert_mip_filter_mag_field_magnitude_source_response(mip_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self) +void insert_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self) { insert_mip_filter_mag_param_source(serializer, self->source); microstrain_insert_float(serializer, self->magnitude); } -void extract_mip_filter_mag_field_magnitude_source_response(mip_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self) +void extract_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self) { extract_mip_filter_mag_param_source(serializer, &self->source); @@ -3566,9 +3566,9 @@ void extract_mip_filter_mag_field_magnitude_source_response(mip_serializer* seri mip_cmd_result mip_filter_write_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source source, float magnitude) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3583,9 +3583,9 @@ mip_cmd_result mip_filter_write_mag_field_magnitude_source(struct mip_interface* } mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* magnitude_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3597,8 +3597,8 @@ mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(source_out); extract_mip_filter_mag_param_source(&deserializer, source_out); @@ -3613,9 +3613,9 @@ mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* } mip_cmd_result mip_filter_save_mag_field_magnitude_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3626,9 +3626,9 @@ mip_cmd_result mip_filter_save_mag_field_magnitude_source(struct mip_interface* } mip_cmd_result mip_filter_load_mag_field_magnitude_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3639,9 +3639,9 @@ mip_cmd_result mip_filter_load_mag_field_magnitude_source(struct mip_interface* } mip_cmd_result mip_filter_default_mag_field_magnitude_source(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3650,7 +3650,7 @@ mip_cmd_result mip_filter_default_mag_field_magnitude_source(struct mip_interfac return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_reference_position_command(mip_serializer* serializer, const mip_filter_reference_position_command* self) +void insert_mip_filter_reference_position_command(microstrain_serializer* serializer, const mip_filter_reference_position_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3666,7 +3666,7 @@ void insert_mip_filter_reference_position_command(mip_serializer* serializer, co } } -void extract_mip_filter_reference_position_command(mip_serializer* serializer, mip_filter_reference_position_command* self) +void extract_mip_filter_reference_position_command(microstrain_serializer* serializer, mip_filter_reference_position_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3683,7 +3683,7 @@ void extract_mip_filter_reference_position_command(mip_serializer* serializer, m } } -void insert_mip_filter_reference_position_response(mip_serializer* serializer, const mip_filter_reference_position_response* self) +void insert_mip_filter_reference_position_response(microstrain_serializer* serializer, const mip_filter_reference_position_response* self) { microstrain_insert_bool(serializer, self->enable); @@ -3694,7 +3694,7 @@ void insert_mip_filter_reference_position_response(mip_serializer* serializer, c microstrain_insert_double(serializer, self->altitude); } -void extract_mip_filter_reference_position_response(mip_serializer* serializer, mip_filter_reference_position_response* self) +void extract_mip_filter_reference_position_response(microstrain_serializer* serializer, mip_filter_reference_position_response* self) { microstrain_extract_bool(serializer, &self->enable); @@ -3708,9 +3708,9 @@ void extract_mip_filter_reference_position_response(mip_serializer* serializer, mip_cmd_result mip_filter_write_reference_position(struct mip_interface* device, bool enable, double latitude, double longitude, double altitude) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3729,9 +3729,9 @@ mip_cmd_result mip_filter_write_reference_position(struct mip_interface* device, } mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, bool* enable_out, double* latitude_out, double* longitude_out, double* altitude_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3743,8 +3743,8 @@ mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_bool(&deserializer, enable_out); @@ -3765,9 +3765,9 @@ mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, } mip_cmd_result mip_filter_save_reference_position(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3778,9 +3778,9 @@ mip_cmd_result mip_filter_save_reference_position(struct mip_interface* device) } mip_cmd_result mip_filter_load_reference_position(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3791,9 +3791,9 @@ mip_cmd_result mip_filter_load_reference_position(struct mip_interface* device) } mip_cmd_result mip_filter_default_reference_position(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3802,7 +3802,7 @@ mip_cmd_result mip_filter_default_reference_position(struct mip_interface* devic return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self) +void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3824,7 +3824,7 @@ void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_se } } -void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_command* self) +void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -3847,7 +3847,7 @@ void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(mip_s } } -void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self) +void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self) { insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); @@ -3864,7 +3864,7 @@ void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(mip_s microstrain_insert_float(serializer, self->minimum_uncertainty); } -void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self) +void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self) { extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); @@ -3884,9 +3884,9 @@ void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(mip_ mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -3911,9 +3911,9 @@ mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(struc } mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -3925,8 +3925,8 @@ mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(adaptive_measurement_out); extract_mip_filter_adaptive_measurement(&deserializer, adaptive_measurement_out); @@ -3956,9 +3956,9 @@ mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct } mip_cmd_result mip_filter_save_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -3969,9 +3969,9 @@ mip_cmd_result mip_filter_save_accel_magnitude_error_adaptive_measurement(struct } mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -3982,9 +3982,9 @@ mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(struct } mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -3993,7 +3993,7 @@ mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(str return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self) +void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4015,7 +4015,7 @@ void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_seri } } -void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_command* self) +void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4038,7 +4038,7 @@ void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(mip_ser } } -void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self) +void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self) { insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); @@ -4055,7 +4055,7 @@ void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(mip_ser microstrain_insert_float(serializer, self->minimum_uncertainty); } -void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(mip_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self) +void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self) { extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); @@ -4075,9 +4075,9 @@ void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(mip_se mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4102,9 +4102,9 @@ mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(struct } mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4116,8 +4116,8 @@ mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct m if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(adaptive_measurement_out); extract_mip_filter_adaptive_measurement(&deserializer, adaptive_measurement_out); @@ -4147,9 +4147,9 @@ mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct m } mip_cmd_result mip_filter_save_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4160,9 +4160,9 @@ mip_cmd_result mip_filter_save_mag_magnitude_error_adaptive_measurement(struct m } mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4173,9 +4173,9 @@ mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(struct m } mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4184,7 +4184,7 @@ mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(struc return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(mip_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self) +void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4202,7 +4202,7 @@ void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(mip_seri } } -void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(mip_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_command* self) +void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4221,7 +4221,7 @@ void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(mip_ser } } -void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(mip_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) +void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) { microstrain_insert_bool(serializer, self->enable); @@ -4234,7 +4234,7 @@ void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(mip_ser microstrain_insert_float(serializer, self->minimum_uncertainty); } -void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(mip_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) +void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) { microstrain_extract_bool(serializer, &self->enable); @@ -4250,9 +4250,9 @@ void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(mip_se mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool enable, float frequency, float high_limit, float high_limit_uncertainty, float minimum_uncertainty) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4273,9 +4273,9 @@ mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(struct } mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool* enable_out, float* frequency_out, float* high_limit_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4287,8 +4287,8 @@ mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct m if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_bool(&deserializer, enable_out); @@ -4312,9 +4312,9 @@ mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct m } mip_cmd_result mip_filter_save_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4325,9 +4325,9 @@ mip_cmd_result mip_filter_save_mag_dip_angle_error_adaptive_measurement(struct m } mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4338,9 +4338,9 @@ mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(struct m } mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4349,7 +4349,7 @@ mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(struc return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_aiding_measurement_enable_command(mip_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self) +void insert_mip_filter_aiding_measurement_enable_command(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4361,7 +4361,7 @@ void insert_mip_filter_aiding_measurement_enable_command(mip_serializer* seriali } } -void extract_mip_filter_aiding_measurement_enable_command(mip_serializer* serializer, mip_filter_aiding_measurement_enable_command* self) +void extract_mip_filter_aiding_measurement_enable_command(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4374,14 +4374,14 @@ void extract_mip_filter_aiding_measurement_enable_command(mip_serializer* serial } } -void insert_mip_filter_aiding_measurement_enable_response(mip_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self) +void insert_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self) { insert_mip_filter_aiding_measurement_enable_command_aiding_source(serializer, self->aiding_source); microstrain_insert_bool(serializer, self->enable); } -void extract_mip_filter_aiding_measurement_enable_response(mip_serializer* serializer, mip_filter_aiding_measurement_enable_response* self) +void extract_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_response* self) { extract_mip_filter_aiding_measurement_enable_command_aiding_source(serializer, &self->aiding_source); @@ -4389,11 +4389,11 @@ void extract_mip_filter_aiding_measurement_enable_response(mip_serializer* seria } -void insert_mip_filter_aiding_measurement_enable_command_aiding_source(struct mip_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self) +void insert_mip_filter_aiding_measurement_enable_command_aiding_source(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_aiding_measurement_enable_command_aiding_source(struct mip_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self) +void extract_mip_filter_aiding_measurement_enable_command_aiding_source(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -4402,9 +4402,9 @@ void extract_mip_filter_aiding_measurement_enable_command_aiding_source(struct m mip_cmd_result mip_filter_write_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool enable) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4419,9 +4419,9 @@ mip_cmd_result mip_filter_write_aiding_measurement_enable(struct mip_interface* } mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool* enable_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4435,8 +4435,8 @@ mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* d if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); extract_mip_filter_aiding_measurement_enable_command_aiding_source(&deserializer, &aiding_source); @@ -4450,9 +4450,9 @@ mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* d } mip_cmd_result mip_filter_save_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4465,9 +4465,9 @@ mip_cmd_result mip_filter_save_aiding_measurement_enable(struct mip_interface* d } mip_cmd_result mip_filter_load_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4480,9 +4480,9 @@ mip_cmd_result mip_filter_load_aiding_measurement_enable(struct mip_interface* d } mip_cmd_result mip_filter_default_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4497,7 +4497,7 @@ mip_cmd_result mip_filter_run(struct mip_interface* device) { return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_RUN, NULL, 0); } -void insert_mip_filter_kinematic_constraint_command(mip_serializer* serializer, const mip_filter_kinematic_constraint_command* self) +void insert_mip_filter_kinematic_constraint_command(microstrain_serializer* serializer, const mip_filter_kinematic_constraint_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4511,7 +4511,7 @@ void insert_mip_filter_kinematic_constraint_command(mip_serializer* serializer, } } -void extract_mip_filter_kinematic_constraint_command(mip_serializer* serializer, mip_filter_kinematic_constraint_command* self) +void extract_mip_filter_kinematic_constraint_command(microstrain_serializer* serializer, mip_filter_kinematic_constraint_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4526,7 +4526,7 @@ void extract_mip_filter_kinematic_constraint_command(mip_serializer* serializer, } } -void insert_mip_filter_kinematic_constraint_response(mip_serializer* serializer, const mip_filter_kinematic_constraint_response* self) +void insert_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, const mip_filter_kinematic_constraint_response* self) { microstrain_insert_u8(serializer, self->acceleration_constraint_selection); @@ -4535,7 +4535,7 @@ void insert_mip_filter_kinematic_constraint_response(mip_serializer* serializer, microstrain_insert_u8(serializer, self->angular_constraint_selection); } -void extract_mip_filter_kinematic_constraint_response(mip_serializer* serializer, mip_filter_kinematic_constraint_response* self) +void extract_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, mip_filter_kinematic_constraint_response* self) { microstrain_extract_u8(serializer, &self->acceleration_constraint_selection); @@ -4547,9 +4547,9 @@ void extract_mip_filter_kinematic_constraint_response(mip_serializer* serializer mip_cmd_result mip_filter_write_kinematic_constraint(struct mip_interface* device, uint8_t acceleration_constraint_selection, uint8_t velocity_constraint_selection, uint8_t angular_constraint_selection) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4566,9 +4566,9 @@ mip_cmd_result mip_filter_write_kinematic_constraint(struct mip_interface* devic } mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device, uint8_t* acceleration_constraint_selection_out, uint8_t* velocity_constraint_selection_out, uint8_t* angular_constraint_selection_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4580,8 +4580,8 @@ mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(acceleration_constraint_selection_out); microstrain_extract_u8(&deserializer, acceleration_constraint_selection_out); @@ -4599,9 +4599,9 @@ mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device } mip_cmd_result mip_filter_save_kinematic_constraint(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4612,9 +4612,9 @@ mip_cmd_result mip_filter_save_kinematic_constraint(struct mip_interface* device } mip_cmd_result mip_filter_load_kinematic_constraint(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4625,9 +4625,9 @@ mip_cmd_result mip_filter_load_kinematic_constraint(struct mip_interface* device } mip_cmd_result mip_filter_default_kinematic_constraint(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4636,7 +4636,7 @@ mip_cmd_result mip_filter_default_kinematic_constraint(struct mip_interface* dev return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_initialization_configuration_command(mip_serializer* serializer, const mip_filter_initialization_configuration_command* self) +void insert_mip_filter_initialization_configuration_command(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4664,7 +4664,7 @@ void insert_mip_filter_initialization_configuration_command(mip_serializer* seri } } -void extract_mip_filter_initialization_configuration_command(mip_serializer* serializer, mip_filter_initialization_configuration_command* self) +void extract_mip_filter_initialization_configuration_command(microstrain_serializer* serializer, mip_filter_initialization_configuration_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4693,7 +4693,7 @@ void extract_mip_filter_initialization_configuration_command(mip_serializer* ser } } -void insert_mip_filter_initialization_configuration_response(mip_serializer* serializer, const mip_filter_initialization_configuration_response* self) +void insert_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, const mip_filter_initialization_configuration_response* self) { microstrain_insert_u8(serializer, self->wait_for_run_command); @@ -4716,7 +4716,7 @@ void insert_mip_filter_initialization_configuration_response(mip_serializer* ser insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); } -void extract_mip_filter_initialization_configuration_response(mip_serializer* serializer, mip_filter_initialization_configuration_response* self) +void extract_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, mip_filter_initialization_configuration_response* self) { microstrain_extract_u8(serializer, &self->wait_for_run_command); @@ -4740,22 +4740,22 @@ void extract_mip_filter_initialization_configuration_response(mip_serializer* se } -void insert_mip_filter_initialization_configuration_command_alignment_selector(struct mip_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self) +void insert_mip_filter_initialization_configuration_command_alignment_selector(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_initialization_configuration_command_alignment_selector(struct mip_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self) +void extract_mip_filter_initialization_configuration_command_alignment_selector(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_initialization_configuration_command_initial_condition_source(struct mip_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self) +void insert_mip_filter_initialization_configuration_command_initial_condition_source(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_initialization_configuration_command_initial_condition_source(struct mip_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self) +void extract_mip_filter_initialization_configuration_command_initial_condition_source(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -4764,9 +4764,9 @@ void extract_mip_filter_initialization_configuration_command_initial_condition_s mip_cmd_result mip_filter_write_initialization_configuration(struct mip_interface* device, uint8_t wait_for_run_command, mip_filter_initialization_configuration_command_initial_condition_source initial_cond_src, mip_filter_initialization_configuration_command_alignment_selector auto_heading_alignment_selector, float initial_heading, float initial_pitch, float initial_roll, const float* initial_position, const float* initial_velocity, mip_filter_reference_frame reference_frame_selector) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4799,9 +4799,9 @@ mip_cmd_result mip_filter_write_initialization_configuration(struct mip_interfac } mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface* device, uint8_t* wait_for_run_command_out, mip_filter_initialization_configuration_command_initial_condition_source* initial_cond_src_out, mip_filter_initialization_configuration_command_alignment_selector* auto_heading_alignment_selector_out, float* initial_heading_out, float* initial_pitch_out, float* initial_roll_out, float* initial_position_out, float* initial_velocity_out, mip_filter_reference_frame* reference_frame_selector_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4813,8 +4813,8 @@ mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(wait_for_run_command_out); microstrain_extract_u8(&deserializer, wait_for_run_command_out); @@ -4852,9 +4852,9 @@ mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface } mip_cmd_result mip_filter_save_initialization_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4865,9 +4865,9 @@ mip_cmd_result mip_filter_save_initialization_configuration(struct mip_interface } mip_cmd_result mip_filter_load_initialization_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -4878,9 +4878,9 @@ mip_cmd_result mip_filter_load_initialization_configuration(struct mip_interface } mip_cmd_result mip_filter_default_initialization_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -4889,7 +4889,7 @@ mip_cmd_result mip_filter_default_initialization_configuration(struct mip_interf return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_adaptive_filter_options_command(mip_serializer* serializer, const mip_filter_adaptive_filter_options_command* self) +void insert_mip_filter_adaptive_filter_options_command(microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_command* self) { insert_mip_function_selector(serializer, self->function); @@ -4901,7 +4901,7 @@ void insert_mip_filter_adaptive_filter_options_command(mip_serializer* serialize } } -void extract_mip_filter_adaptive_filter_options_command(mip_serializer* serializer, mip_filter_adaptive_filter_options_command* self) +void extract_mip_filter_adaptive_filter_options_command(microstrain_serializer* serializer, mip_filter_adaptive_filter_options_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -4914,14 +4914,14 @@ void extract_mip_filter_adaptive_filter_options_command(mip_serializer* serializ } } -void insert_mip_filter_adaptive_filter_options_response(mip_serializer* serializer, const mip_filter_adaptive_filter_options_response* self) +void insert_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_response* self) { microstrain_insert_u8(serializer, self->level); microstrain_insert_u16(serializer, self->time_limit); } -void extract_mip_filter_adaptive_filter_options_response(mip_serializer* serializer, mip_filter_adaptive_filter_options_response* self) +void extract_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, mip_filter_adaptive_filter_options_response* self) { microstrain_extract_u8(serializer, &self->level); @@ -4931,9 +4931,9 @@ void extract_mip_filter_adaptive_filter_options_response(mip_serializer* seriali mip_cmd_result mip_filter_write_adaptive_filter_options(struct mip_interface* device, uint8_t level, uint16_t time_limit) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -4948,9 +4948,9 @@ mip_cmd_result mip_filter_write_adaptive_filter_options(struct mip_interface* de } mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* device, uint8_t* level_out, uint16_t* time_limit_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -4962,8 +4962,8 @@ mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* dev if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(level_out); microstrain_extract_u8(&deserializer, level_out); @@ -4978,9 +4978,9 @@ mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* dev } mip_cmd_result mip_filter_save_adaptive_filter_options(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -4991,9 +4991,9 @@ mip_cmd_result mip_filter_save_adaptive_filter_options(struct mip_interface* dev } mip_cmd_result mip_filter_load_adaptive_filter_options(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5004,9 +5004,9 @@ mip_cmd_result mip_filter_load_adaptive_filter_options(struct mip_interface* dev } mip_cmd_result mip_filter_default_adaptive_filter_options(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5015,7 +5015,7 @@ mip_cmd_result mip_filter_default_adaptive_filter_options(struct mip_interface* return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_multi_antenna_offset_command(mip_serializer* serializer, const mip_filter_multi_antenna_offset_command* self) +void insert_mip_filter_multi_antenna_offset_command(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_command* self) { insert_mip_function_selector(serializer, self->function); @@ -5028,7 +5028,7 @@ void insert_mip_filter_multi_antenna_offset_command(mip_serializer* serializer, } } -void extract_mip_filter_multi_antenna_offset_command(mip_serializer* serializer, mip_filter_multi_antenna_offset_command* self) +void extract_mip_filter_multi_antenna_offset_command(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -5042,7 +5042,7 @@ void extract_mip_filter_multi_antenna_offset_command(mip_serializer* serializer, } } -void insert_mip_filter_multi_antenna_offset_response(mip_serializer* serializer, const mip_filter_multi_antenna_offset_response* self) +void insert_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_response* self) { microstrain_insert_u8(serializer, self->receiver_id); @@ -5050,7 +5050,7 @@ void insert_mip_filter_multi_antenna_offset_response(mip_serializer* serializer, microstrain_insert_float(serializer, self->antenna_offset[i]); } -void extract_mip_filter_multi_antenna_offset_response(mip_serializer* serializer, mip_filter_multi_antenna_offset_response* self) +void extract_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_response* self) { microstrain_extract_u8(serializer, &self->receiver_id); @@ -5061,9 +5061,9 @@ void extract_mip_filter_multi_antenna_offset_response(mip_serializer* serializer mip_cmd_result mip_filter_write_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, const float* antenna_offset) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -5080,9 +5080,9 @@ mip_cmd_result mip_filter_write_multi_antenna_offset(struct mip_interface* devic } mip_cmd_result mip_filter_read_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, float* antenna_offset_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -5096,8 +5096,8 @@ mip_cmd_result mip_filter_read_multi_antenna_offset(struct mip_interface* device if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &receiver_id); @@ -5112,9 +5112,9 @@ mip_cmd_result mip_filter_read_multi_antenna_offset(struct mip_interface* device } mip_cmd_result mip_filter_save_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5127,9 +5127,9 @@ mip_cmd_result mip_filter_save_multi_antenna_offset(struct mip_interface* device } mip_cmd_result mip_filter_load_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5142,9 +5142,9 @@ mip_cmd_result mip_filter_load_multi_antenna_offset(struct mip_interface* device } mip_cmd_result mip_filter_default_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5155,7 +5155,7 @@ mip_cmd_result mip_filter_default_multi_antenna_offset(struct mip_interface* dev return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_rel_pos_configuration_command(mip_serializer* serializer, const mip_filter_rel_pos_configuration_command* self) +void insert_mip_filter_rel_pos_configuration_command(microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_command* self) { insert_mip_function_selector(serializer, self->function); @@ -5170,7 +5170,7 @@ void insert_mip_filter_rel_pos_configuration_command(mip_serializer* serializer, } } -void extract_mip_filter_rel_pos_configuration_command(mip_serializer* serializer, mip_filter_rel_pos_configuration_command* self) +void extract_mip_filter_rel_pos_configuration_command(microstrain_serializer* serializer, mip_filter_rel_pos_configuration_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -5186,7 +5186,7 @@ void extract_mip_filter_rel_pos_configuration_command(mip_serializer* serializer } } -void insert_mip_filter_rel_pos_configuration_response(mip_serializer* serializer, const mip_filter_rel_pos_configuration_response* self) +void insert_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_response* self) { microstrain_insert_u8(serializer, self->source); @@ -5196,7 +5196,7 @@ void insert_mip_filter_rel_pos_configuration_response(mip_serializer* serializer microstrain_insert_double(serializer, self->reference_coordinates[i]); } -void extract_mip_filter_rel_pos_configuration_response(mip_serializer* serializer, mip_filter_rel_pos_configuration_response* self) +void extract_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, mip_filter_rel_pos_configuration_response* self) { microstrain_extract_u8(serializer, &self->source); @@ -5209,9 +5209,9 @@ void extract_mip_filter_rel_pos_configuration_response(mip_serializer* serialize mip_cmd_result mip_filter_write_rel_pos_configuration(struct mip_interface* device, uint8_t source, mip_filter_reference_frame reference_frame_selector, const double* reference_coordinates) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -5230,9 +5230,9 @@ mip_cmd_result mip_filter_write_rel_pos_configuration(struct mip_interface* devi } mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* device, uint8_t* source_out, mip_filter_reference_frame* reference_frame_selector_out, double* reference_coordinates_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -5244,8 +5244,8 @@ mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* devic if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(source_out); microstrain_extract_u8(&deserializer, source_out); @@ -5264,9 +5264,9 @@ mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* devic } mip_cmd_result mip_filter_save_rel_pos_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5277,9 +5277,9 @@ mip_cmd_result mip_filter_save_rel_pos_configuration(struct mip_interface* devic } mip_cmd_result mip_filter_load_rel_pos_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5290,9 +5290,9 @@ mip_cmd_result mip_filter_load_rel_pos_configuration(struct mip_interface* devic } mip_cmd_result mip_filter_default_rel_pos_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5301,7 +5301,7 @@ mip_cmd_result mip_filter_default_rel_pos_configuration(struct mip_interface* de return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_ref_point_lever_arm_command(mip_serializer* serializer, const mip_filter_ref_point_lever_arm_command* self) +void insert_mip_filter_ref_point_lever_arm_command(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command* self) { insert_mip_function_selector(serializer, self->function); @@ -5314,7 +5314,7 @@ void insert_mip_filter_ref_point_lever_arm_command(mip_serializer* serializer, c } } -void extract_mip_filter_ref_point_lever_arm_command(mip_serializer* serializer, mip_filter_ref_point_lever_arm_command* self) +void extract_mip_filter_ref_point_lever_arm_command(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -5328,7 +5328,7 @@ void extract_mip_filter_ref_point_lever_arm_command(mip_serializer* serializer, } } -void insert_mip_filter_ref_point_lever_arm_response(mip_serializer* serializer, const mip_filter_ref_point_lever_arm_response* self) +void insert_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_response* self) { insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, self->ref_point_sel); @@ -5336,7 +5336,7 @@ void insert_mip_filter_ref_point_lever_arm_response(mip_serializer* serializer, microstrain_insert_float(serializer, self->lever_arm_offset[i]); } -void extract_mip_filter_ref_point_lever_arm_response(mip_serializer* serializer, mip_filter_ref_point_lever_arm_response* self) +void extract_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_response* self) { extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, &self->ref_point_sel); @@ -5345,11 +5345,11 @@ void extract_mip_filter_ref_point_lever_arm_response(mip_serializer* serializer, } -void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct mip_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self) +void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct mip_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self) +void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -5358,9 +5358,9 @@ void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(str mip_cmd_result mip_filter_write_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel, const float* lever_arm_offset) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -5377,9 +5377,9 @@ mip_cmd_result mip_filter_write_ref_point_lever_arm(struct mip_interface* device } mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector* ref_point_sel_out, float* lever_arm_offset_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -5391,8 +5391,8 @@ mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(ref_point_sel_out); extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(&deserializer, ref_point_sel_out); @@ -5408,9 +5408,9 @@ mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, } mip_cmd_result mip_filter_save_ref_point_lever_arm(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5421,9 +5421,9 @@ mip_cmd_result mip_filter_save_ref_point_lever_arm(struct mip_interface* device) } mip_cmd_result mip_filter_load_ref_point_lever_arm(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5434,9 +5434,9 @@ mip_cmd_result mip_filter_load_ref_point_lever_arm(struct mip_interface* device) } mip_cmd_result mip_filter_default_ref_point_lever_arm(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5445,7 +5445,7 @@ mip_cmd_result mip_filter_default_ref_point_lever_arm(struct mip_interface* devi return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_speed_measurement_command(mip_serializer* serializer, const mip_filter_speed_measurement_command* self) +void insert_mip_filter_speed_measurement_command(microstrain_serializer* serializer, const mip_filter_speed_measurement_command* self) { microstrain_insert_u8(serializer, self->source); @@ -5456,7 +5456,7 @@ void insert_mip_filter_speed_measurement_command(mip_serializer* serializer, con microstrain_insert_float(serializer, self->speed_uncertainty); } -void extract_mip_filter_speed_measurement_command(mip_serializer* serializer, mip_filter_speed_measurement_command* self) +void extract_mip_filter_speed_measurement_command(microstrain_serializer* serializer, mip_filter_speed_measurement_command* self) { microstrain_extract_u8(serializer, &self->source); @@ -5470,9 +5470,9 @@ void extract_mip_filter_speed_measurement_command(mip_serializer* serializer, mi mip_cmd_result mip_filter_speed_measurement(struct mip_interface* device, uint8_t source, float time_of_week, float speed, float speed_uncertainty) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_u8(&serializer, source); @@ -5487,7 +5487,7 @@ mip_cmd_result mip_filter_speed_measurement(struct mip_interface* device, uint8_ return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_MEASUREMENT, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_speed_lever_arm_command(mip_serializer* serializer, const mip_filter_speed_lever_arm_command* self) +void insert_mip_filter_speed_lever_arm_command(microstrain_serializer* serializer, const mip_filter_speed_lever_arm_command* self) { insert_mip_function_selector(serializer, self->function); @@ -5500,7 +5500,7 @@ void insert_mip_filter_speed_lever_arm_command(mip_serializer* serializer, const } } -void extract_mip_filter_speed_lever_arm_command(mip_serializer* serializer, mip_filter_speed_lever_arm_command* self) +void extract_mip_filter_speed_lever_arm_command(microstrain_serializer* serializer, mip_filter_speed_lever_arm_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -5514,7 +5514,7 @@ void extract_mip_filter_speed_lever_arm_command(mip_serializer* serializer, mip_ } } -void insert_mip_filter_speed_lever_arm_response(mip_serializer* serializer, const mip_filter_speed_lever_arm_response* self) +void insert_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, const mip_filter_speed_lever_arm_response* self) { microstrain_insert_u8(serializer, self->source); @@ -5522,7 +5522,7 @@ void insert_mip_filter_speed_lever_arm_response(mip_serializer* serializer, cons microstrain_insert_float(serializer, self->lever_arm_offset[i]); } -void extract_mip_filter_speed_lever_arm_response(mip_serializer* serializer, mip_filter_speed_lever_arm_response* self) +void extract_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, mip_filter_speed_lever_arm_response* self) { microstrain_extract_u8(serializer, &self->source); @@ -5533,9 +5533,9 @@ void extract_mip_filter_speed_lever_arm_response(mip_serializer* serializer, mip mip_cmd_result mip_filter_write_speed_lever_arm(struct mip_interface* device, uint8_t source, const float* lever_arm_offset) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -5552,9 +5552,9 @@ mip_cmd_result mip_filter_write_speed_lever_arm(struct mip_interface* device, ui } mip_cmd_result mip_filter_read_speed_lever_arm(struct mip_interface* device, uint8_t source, float* lever_arm_offset_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -5568,8 +5568,8 @@ mip_cmd_result mip_filter_read_speed_lever_arm(struct mip_interface* device, uin if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); microstrain_extract_u8(&deserializer, &source); @@ -5584,9 +5584,9 @@ mip_cmd_result mip_filter_read_speed_lever_arm(struct mip_interface* device, uin } mip_cmd_result mip_filter_save_speed_lever_arm(struct mip_interface* device, uint8_t source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5599,9 +5599,9 @@ mip_cmd_result mip_filter_save_speed_lever_arm(struct mip_interface* device, uin } mip_cmd_result mip_filter_load_speed_lever_arm(struct mip_interface* device, uint8_t source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5614,9 +5614,9 @@ mip_cmd_result mip_filter_load_speed_lever_arm(struct mip_interface* device, uin } mip_cmd_result mip_filter_default_speed_lever_arm(struct mip_interface* device, uint8_t source) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5627,7 +5627,7 @@ mip_cmd_result mip_filter_default_speed_lever_arm(struct mip_interface* device, return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_wheeled_vehicle_constraint_control_command(mip_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_command* self) +void insert_mip_filter_wheeled_vehicle_constraint_control_command(microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_command* self) { insert_mip_function_selector(serializer, self->function); @@ -5637,7 +5637,7 @@ void insert_mip_filter_wheeled_vehicle_constraint_control_command(mip_serializer } } -void extract_mip_filter_wheeled_vehicle_constraint_control_command(mip_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_command* self) +void extract_mip_filter_wheeled_vehicle_constraint_control_command(microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -5648,12 +5648,12 @@ void extract_mip_filter_wheeled_vehicle_constraint_control_command(mip_serialize } } -void insert_mip_filter_wheeled_vehicle_constraint_control_response(mip_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self) +void insert_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self) { microstrain_insert_u8(serializer, self->enable); } -void extract_mip_filter_wheeled_vehicle_constraint_control_response(mip_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self) +void extract_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self) { microstrain_extract_u8(serializer, &self->enable); @@ -5661,9 +5661,9 @@ void extract_mip_filter_wheeled_vehicle_constraint_control_response(mip_serializ mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t enable) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -5676,9 +5676,9 @@ mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(struct mip_in } mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t* enable_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -5690,8 +5690,8 @@ mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_int if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); @@ -5703,9 +5703,9 @@ mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_int } mip_cmd_result mip_filter_save_wheeled_vehicle_constraint_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5716,9 +5716,9 @@ mip_cmd_result mip_filter_save_wheeled_vehicle_constraint_control(struct mip_int } mip_cmd_result mip_filter_load_wheeled_vehicle_constraint_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5729,9 +5729,9 @@ mip_cmd_result mip_filter_load_wheeled_vehicle_constraint_control(struct mip_int } mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5740,7 +5740,7 @@ mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(struct mip_ return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_vertical_gyro_constraint_control_command(mip_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_command* self) +void insert_mip_filter_vertical_gyro_constraint_control_command(microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_command* self) { insert_mip_function_selector(serializer, self->function); @@ -5750,7 +5750,7 @@ void insert_mip_filter_vertical_gyro_constraint_control_command(mip_serializer* } } -void extract_mip_filter_vertical_gyro_constraint_control_command(mip_serializer* serializer, mip_filter_vertical_gyro_constraint_control_command* self) +void extract_mip_filter_vertical_gyro_constraint_control_command(microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -5761,12 +5761,12 @@ void extract_mip_filter_vertical_gyro_constraint_control_command(mip_serializer* } } -void insert_mip_filter_vertical_gyro_constraint_control_response(mip_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self) +void insert_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self) { microstrain_insert_u8(serializer, self->enable); } -void extract_mip_filter_vertical_gyro_constraint_control_response(mip_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self) +void extract_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self) { microstrain_extract_u8(serializer, &self->enable); @@ -5774,9 +5774,9 @@ void extract_mip_filter_vertical_gyro_constraint_control_response(mip_serializer mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t enable) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -5789,9 +5789,9 @@ mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(struct mip_inte } mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t* enable_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -5803,8 +5803,8 @@ mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_inter if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); @@ -5816,9 +5816,9 @@ mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_inter } mip_cmd_result mip_filter_save_vertical_gyro_constraint_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5829,9 +5829,9 @@ mip_cmd_result mip_filter_save_vertical_gyro_constraint_control(struct mip_inter } mip_cmd_result mip_filter_load_vertical_gyro_constraint_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5842,9 +5842,9 @@ mip_cmd_result mip_filter_load_vertical_gyro_constraint_control(struct mip_inter } mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5853,7 +5853,7 @@ mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(struct mip_in return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_gnss_antenna_cal_control_command(mip_serializer* serializer, const mip_filter_gnss_antenna_cal_control_command* self) +void insert_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_command* self) { insert_mip_function_selector(serializer, self->function); @@ -5865,7 +5865,7 @@ void insert_mip_filter_gnss_antenna_cal_control_command(mip_serializer* serializ } } -void extract_mip_filter_gnss_antenna_cal_control_command(mip_serializer* serializer, mip_filter_gnss_antenna_cal_control_command* self) +void extract_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -5878,14 +5878,14 @@ void extract_mip_filter_gnss_antenna_cal_control_command(mip_serializer* seriali } } -void insert_mip_filter_gnss_antenna_cal_control_response(mip_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self) +void insert_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self) { microstrain_insert_u8(serializer, self->enable); microstrain_insert_float(serializer, self->max_offset); } -void extract_mip_filter_gnss_antenna_cal_control_response(mip_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self) +void extract_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self) { microstrain_extract_u8(serializer, &self->enable); @@ -5895,9 +5895,9 @@ void extract_mip_filter_gnss_antenna_cal_control_response(mip_serializer* serial mip_cmd_result mip_filter_write_gnss_antenna_cal_control(struct mip_interface* device, uint8_t enable, float max_offset) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -5912,9 +5912,9 @@ mip_cmd_result mip_filter_write_gnss_antenna_cal_control(struct mip_interface* d } mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* device, uint8_t* enable_out, float* max_offset_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -5926,8 +5926,8 @@ mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* de if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); @@ -5942,9 +5942,9 @@ mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* de } mip_cmd_result mip_filter_save_gnss_antenna_cal_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -5955,9 +5955,9 @@ mip_cmd_result mip_filter_save_gnss_antenna_cal_control(struct mip_interface* de } mip_cmd_result mip_filter_load_gnss_antenna_cal_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -5968,9 +5968,9 @@ mip_cmd_result mip_filter_load_gnss_antenna_cal_control(struct mip_interface* de } mip_cmd_result mip_filter_default_gnss_antenna_cal_control(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -5979,12 +5979,12 @@ mip_cmd_result mip_filter_default_gnss_antenna_cal_control(struct mip_interface* return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_filter_set_initial_heading_command(mip_serializer* serializer, const mip_filter_set_initial_heading_command* self) +void insert_mip_filter_set_initial_heading_command(microstrain_serializer* serializer, const mip_filter_set_initial_heading_command* self) { microstrain_insert_float(serializer, self->heading); } -void extract_mip_filter_set_initial_heading_command(mip_serializer* serializer, mip_filter_set_initial_heading_command* self) +void extract_mip_filter_set_initial_heading_command(microstrain_serializer* serializer, mip_filter_set_initial_heading_command* self) { microstrain_extract_float(serializer, &self->heading); @@ -5992,9 +5992,9 @@ void extract_mip_filter_set_initial_heading_command(mip_serializer* serializer, mip_cmd_result mip_filter_set_initial_heading(struct mip_interface* device, float heading) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_float(&serializer, heading); diff --git a/src/mip/definitions/commands_filter.cpp b/src/mip/definitions/commands_filter.cpp index 527c23787..a838cee97 100644 --- a/src/mip/definitions/commands_filter.cpp +++ b/src/mip/definitions/commands_filter.cpp @@ -76,7 +76,7 @@ TypedResult setInitialAttitude(C::mip_interface& device, flo assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_ATTITUDE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_ATTITUDE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const EstimationControl& self) { @@ -120,7 +120,7 @@ TypedResult writeEstimationControl(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut) { @@ -131,7 +131,7 @@ TypedResult readEstimationControl(C::mip_interface& device, E assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -153,7 +153,7 @@ TypedResult saveEstimationControl(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadEstimationControl(C::mip_interface& device) { @@ -163,7 +163,7 @@ TypedResult loadEstimationControl(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultEstimationControl(C::mip_interface& device) { @@ -173,7 +173,7 @@ TypedResult defaultEstimationControl(C::mip_interface& device insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ExternalGnssUpdate& self) { @@ -249,7 +249,7 @@ TypedResult externalGnssUpdate(C::mip_interface& device, dou assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ExternalHeadingUpdate& self) { @@ -283,7 +283,7 @@ TypedResult externalHeadingUpdate(C::mip_interface& devic assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ExternalHeadingUpdateWithTime& self) { @@ -329,7 +329,7 @@ TypedResult externalHeadingUpdateWithTime(C::mip_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const TareOrientation& self) { @@ -373,7 +373,7 @@ TypedResult writeTareOrientation(C::mip_interface& device, Tare assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut) { @@ -384,7 +384,7 @@ TypedResult readTareOrientation(C::mip_interface& device, TareO assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_TARE_ORIENTATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_TARE_ORIENTATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -406,7 +406,7 @@ TypedResult saveTareOrientation(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadTareOrientation(C::mip_interface& device) { @@ -416,7 +416,7 @@ TypedResult loadTareOrientation(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultTareOrientation(C::mip_interface& device) { @@ -426,7 +426,7 @@ TypedResult defaultTareOrientation(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const VehicleDynamicsMode& self) { @@ -470,7 +470,7 @@ TypedResult writeVehicleDynamicsMode(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut) { @@ -481,7 +481,7 @@ TypedResult readVehicleDynamicsMode(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -503,7 +503,7 @@ TypedResult saveVehicleDynamicsMode(C::mip_interface& devic insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadVehicleDynamicsMode(C::mip_interface& device) { @@ -513,7 +513,7 @@ TypedResult loadVehicleDynamicsMode(C::mip_interface& devic insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultVehicleDynamicsMode(C::mip_interface& device) { @@ -523,7 +523,7 @@ TypedResult defaultVehicleDynamicsMode(C::mip_interface& de insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SensorToVehicleRotationEuler& self) { @@ -587,7 +587,7 @@ TypedResult writeSensorToVehicleRotationEuler(C::m assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { @@ -598,7 +598,7 @@ TypedResult readSensorToVehicleRotationEuler(C::mi assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -626,7 +626,7 @@ TypedResult saveSensorToVehicleRotationEuler(C::mi insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSensorToVehicleRotationEuler(C::mip_interface& device) { @@ -636,7 +636,7 @@ TypedResult loadSensorToVehicleRotationEuler(C::mi insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSensorToVehicleRotationEuler(C::mip_interface& device) { @@ -646,7 +646,7 @@ TypedResult defaultSensorToVehicleRotationEuler(C: insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SensorToVehicleRotationDcm& self) { @@ -696,7 +696,7 @@ TypedResult writeSensorToVehicleRotationDcm(C::mip_i assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut) { @@ -707,7 +707,7 @@ TypedResult readSensorToVehicleRotationDcm(C::mip_in assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -730,7 +730,7 @@ TypedResult saveSensorToVehicleRotationDcm(C::mip_in insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSensorToVehicleRotationDcm(C::mip_interface& device) { @@ -740,7 +740,7 @@ TypedResult loadSensorToVehicleRotationDcm(C::mip_in insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSensorToVehicleRotationDcm(C::mip_interface& device) { @@ -750,7 +750,7 @@ TypedResult defaultSensorToVehicleRotationDcm(C::mip insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SensorToVehicleRotationQuaternion& self) { @@ -800,7 +800,7 @@ TypedResult writeSensorToVehicleRotationQuate assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut) { @@ -811,7 +811,7 @@ TypedResult readSensorToVehicleRotationQuater assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -834,7 +834,7 @@ TypedResult saveSensorToVehicleRotationQuater insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) { @@ -844,7 +844,7 @@ TypedResult loadSensorToVehicleRotationQuater insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device) { @@ -854,7 +854,7 @@ TypedResult defaultSensorToVehicleRotationQua insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SensorToVehicleOffset& self) { @@ -904,7 +904,7 @@ TypedResult writeSensorToVehicleOffset(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) { @@ -915,7 +915,7 @@ TypedResult readSensorToVehicleOffset(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -938,7 +938,7 @@ TypedResult saveSensorToVehicleOffset(C::mip_interface& d insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSensorToVehicleOffset(C::mip_interface& device) { @@ -948,7 +948,7 @@ TypedResult loadSensorToVehicleOffset(C::mip_interface& d insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSensorToVehicleOffset(C::mip_interface& device) { @@ -958,7 +958,7 @@ TypedResult defaultSensorToVehicleOffset(C::mip_interface insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AntennaOffset& self) { @@ -1008,7 +1008,7 @@ TypedResult writeAntennaOffset(C::mip_interface& device, const fl assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut) { @@ -1019,7 +1019,7 @@ TypedResult readAntennaOffset(C::mip_interface& device, float* of assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ANTENNA_OFFSET, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1042,7 +1042,7 @@ TypedResult saveAntennaOffset(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAntennaOffset(C::mip_interface& device) { @@ -1052,7 +1052,7 @@ TypedResult loadAntennaOffset(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAntennaOffset(C::mip_interface& device) { @@ -1062,7 +1062,7 @@ TypedResult defaultAntennaOffset(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GnssSource& self) { @@ -1106,7 +1106,7 @@ TypedResult writeGnssSource(C::mip_interface& device, GnssSource::So assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut) { @@ -1117,7 +1117,7 @@ TypedResult readGnssSource(C::mip_interface& device, GnssSource::Sou assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GNSS_SOURCE_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_SOURCE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1139,7 +1139,7 @@ TypedResult saveGnssSource(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGnssSource(C::mip_interface& device) { @@ -1149,7 +1149,7 @@ TypedResult loadGnssSource(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGnssSource(C::mip_interface& device) { @@ -1159,7 +1159,7 @@ TypedResult defaultGnssSource(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const HeadingSource& self) { @@ -1203,7 +1203,7 @@ TypedResult writeHeadingSource(C::mip_interface& device, HeadingS assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut) { @@ -1214,7 +1214,7 @@ TypedResult readHeadingSource(C::mip_interface& device, HeadingSo assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_HEADING_UPDATE_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_HEADING_UPDATE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1236,7 +1236,7 @@ TypedResult saveHeadingSource(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadHeadingSource(C::mip_interface& device) { @@ -1246,7 +1246,7 @@ TypedResult loadHeadingSource(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultHeadingSource(C::mip_interface& device) { @@ -1256,7 +1256,7 @@ TypedResult defaultHeadingSource(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AutoInitControl& self) { @@ -1300,7 +1300,7 @@ TypedResult writeAutoInitControl(C::mip_interface& device, uint assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) { @@ -1311,7 +1311,7 @@ TypedResult readAutoInitControl(C::mip_interface& device, uint8 assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_AUTOINIT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_AUTOINIT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1333,7 +1333,7 @@ TypedResult saveAutoInitControl(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAutoInitControl(C::mip_interface& device) { @@ -1343,7 +1343,7 @@ TypedResult loadAutoInitControl(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAutoInitControl(C::mip_interface& device) { @@ -1353,7 +1353,7 @@ TypedResult defaultAutoInitControl(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AccelNoise& self) { @@ -1403,7 +1403,7 @@ TypedResult writeAccelNoise(C::mip_interface& device, const float* n assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut) { @@ -1414,7 +1414,7 @@ TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ACCEL_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ACCEL_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1437,7 +1437,7 @@ TypedResult saveAccelNoise(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAccelNoise(C::mip_interface& device) { @@ -1447,7 +1447,7 @@ TypedResult loadAccelNoise(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAccelNoise(C::mip_interface& device) { @@ -1457,7 +1457,7 @@ TypedResult defaultAccelNoise(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GyroNoise& self) { @@ -1507,7 +1507,7 @@ TypedResult writeGyroNoise(C::mip_interface& device, const float* noi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) { @@ -1518,7 +1518,7 @@ TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GYRO_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1541,7 +1541,7 @@ TypedResult saveGyroNoise(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGyroNoise(C::mip_interface& device) { @@ -1551,7 +1551,7 @@ TypedResult loadGyroNoise(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGyroNoise(C::mip_interface& device) { @@ -1561,7 +1561,7 @@ TypedResult defaultGyroNoise(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AccelBiasModel& self) { @@ -1627,7 +1627,7 @@ TypedResult writeAccelBiasModel(C::mip_interface& device, const assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { @@ -1638,7 +1638,7 @@ TypedResult readAccelBiasModel(C::mip_interface& device, float* assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ACCEL_BIAS_MODEL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ACCEL_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1665,7 +1665,7 @@ TypedResult saveAccelBiasModel(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAccelBiasModel(C::mip_interface& device) { @@ -1675,7 +1675,7 @@ TypedResult loadAccelBiasModel(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAccelBiasModel(C::mip_interface& device) { @@ -1685,7 +1685,7 @@ TypedResult defaultAccelBiasModel(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GyroBiasModel& self) { @@ -1751,7 +1751,7 @@ TypedResult writeGyroBiasModel(C::mip_interface& device, const fl assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { @@ -1762,7 +1762,7 @@ TypedResult readGyroBiasModel(C::mip_interface& device, float* be assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GYRO_BIAS_MODEL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1789,7 +1789,7 @@ TypedResult saveGyroBiasModel(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGyroBiasModel(C::mip_interface& device) { @@ -1799,7 +1799,7 @@ TypedResult loadGyroBiasModel(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGyroBiasModel(C::mip_interface& device) { @@ -1809,7 +1809,7 @@ TypedResult defaultGyroBiasModel(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AltitudeAiding& self) { @@ -1853,7 +1853,7 @@ TypedResult writeAltitudeAiding(C::mip_interface& device, Altitu assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut) { @@ -1864,7 +1864,7 @@ TypedResult readAltitudeAiding(C::mip_interface& device, Altitud assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1886,7 +1886,7 @@ TypedResult saveAltitudeAiding(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAltitudeAiding(C::mip_interface& device) { @@ -1896,7 +1896,7 @@ TypedResult loadAltitudeAiding(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAltitudeAiding(C::mip_interface& device) { @@ -1906,7 +1906,7 @@ TypedResult defaultAltitudeAiding(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const PitchRollAiding& self) { @@ -1950,7 +1950,7 @@ TypedResult writePitchRollAiding(C::mip_interface& device, Pitc assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut) { @@ -1961,7 +1961,7 @@ TypedResult readPitchRollAiding(C::mip_interface& device, Pitch assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1983,7 +1983,7 @@ TypedResult savePitchRollAiding(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadPitchRollAiding(C::mip_interface& device) { @@ -1993,7 +1993,7 @@ TypedResult loadPitchRollAiding(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultPitchRollAiding(C::mip_interface& device) { @@ -2003,7 +2003,7 @@ TypedResult defaultPitchRollAiding(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AutoZupt& self) { @@ -2057,7 +2057,7 @@ TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, fl assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { @@ -2068,7 +2068,7 @@ TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ZUPT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2093,7 +2093,7 @@ TypedResult saveAutoZupt(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAutoZupt(C::mip_interface& device) { @@ -2103,7 +2103,7 @@ TypedResult loadAutoZupt(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAutoZupt(C::mip_interface& device) { @@ -2113,7 +2113,7 @@ TypedResult defaultAutoZupt(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AutoAngularZupt& self) { @@ -2167,7 +2167,7 @@ TypedResult writeAutoAngularZupt(C::mip_interface& device, uint assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { @@ -2178,7 +2178,7 @@ TypedResult readAutoAngularZupt(C::mip_interface& device, uint8 assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2203,7 +2203,7 @@ TypedResult saveAutoAngularZupt(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAutoAngularZupt(C::mip_interface& device) { @@ -2213,7 +2213,7 @@ TypedResult loadAutoAngularZupt(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAutoAngularZupt(C::mip_interface& device) { @@ -2223,7 +2223,7 @@ TypedResult defaultAutoAngularZupt(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const CommandedZupt& self) { @@ -2274,7 +2274,7 @@ TypedResult writeMagCaptureAutoCal(C::mip_interface& device) insert(serializer, FunctionSelector::WRITE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult saveMagCaptureAutoCal(C::mip_interface& device) { @@ -2284,7 +2284,7 @@ TypedResult saveMagCaptureAutoCal(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GravityNoise& self) { @@ -2334,7 +2334,7 @@ TypedResult writeGravityNoise(C::mip_interface& device, const floa assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut) { @@ -2345,7 +2345,7 @@ TypedResult readGravityNoise(C::mip_interface& device, float* nois assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GRAVITY_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GRAVITY_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2368,7 +2368,7 @@ TypedResult saveGravityNoise(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGravityNoise(C::mip_interface& device) { @@ -2378,7 +2378,7 @@ TypedResult loadGravityNoise(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGravityNoise(C::mip_interface& device) { @@ -2388,7 +2388,7 @@ TypedResult defaultGravityNoise(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const PressureAltitudeNoise& self) { @@ -2432,7 +2432,7 @@ TypedResult writePressureAltitudeNoise(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut) { @@ -2443,7 +2443,7 @@ TypedResult readPressureAltitudeNoise(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_PRESSURE_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_PRESSURE_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2465,7 +2465,7 @@ TypedResult savePressureAltitudeNoise(C::mip_interface& d insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadPressureAltitudeNoise(C::mip_interface& device) { @@ -2475,7 +2475,7 @@ TypedResult loadPressureAltitudeNoise(C::mip_interface& d insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultPressureAltitudeNoise(C::mip_interface& device) { @@ -2485,7 +2485,7 @@ TypedResult defaultPressureAltitudeNoise(C::mip_interface insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const HardIronOffsetNoise& self) { @@ -2535,7 +2535,7 @@ TypedResult writeHardIronOffsetNoise(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut) { @@ -2546,7 +2546,7 @@ TypedResult readHardIronOffsetNoise(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2569,7 +2569,7 @@ TypedResult saveHardIronOffsetNoise(C::mip_interface& devic insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadHardIronOffsetNoise(C::mip_interface& device) { @@ -2579,7 +2579,7 @@ TypedResult loadHardIronOffsetNoise(C::mip_interface& devic insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultHardIronOffsetNoise(C::mip_interface& device) { @@ -2589,7 +2589,7 @@ TypedResult defaultHardIronOffsetNoise(C::mip_interface& de insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SoftIronMatrixNoise& self) { @@ -2639,7 +2639,7 @@ TypedResult writeSoftIronMatrixNoise(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut) { @@ -2650,7 +2650,7 @@ TypedResult readSoftIronMatrixNoise(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2673,7 +2673,7 @@ TypedResult saveSoftIronMatrixNoise(C::mip_interface& devic insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSoftIronMatrixNoise(C::mip_interface& device) { @@ -2683,7 +2683,7 @@ TypedResult loadSoftIronMatrixNoise(C::mip_interface& devic insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSoftIronMatrixNoise(C::mip_interface& device) { @@ -2693,7 +2693,7 @@ TypedResult defaultSoftIronMatrixNoise(C::mip_interface& de insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const MagNoise& self) { @@ -2743,7 +2743,7 @@ TypedResult writeMagNoise(C::mip_interface& device, const float* noise assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) { @@ -2754,7 +2754,7 @@ TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_MAG_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MAG_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2777,7 +2777,7 @@ TypedResult saveMagNoise(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadMagNoise(C::mip_interface& device) { @@ -2787,7 +2787,7 @@ TypedResult loadMagNoise(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultMagNoise(C::mip_interface& device) { @@ -2797,7 +2797,7 @@ TypedResult defaultMagNoise(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const InclinationSource& self) { @@ -2851,7 +2851,7 @@ TypedResult writeInclinationSource(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut) { @@ -2862,7 +2862,7 @@ TypedResult readInclinationSource(C::mip_interface& device, F assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_INCLINATION_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_INCLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2887,7 +2887,7 @@ TypedResult saveInclinationSource(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadInclinationSource(C::mip_interface& device) { @@ -2897,7 +2897,7 @@ TypedResult loadInclinationSource(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultInclinationSource(C::mip_interface& device) { @@ -2907,7 +2907,7 @@ TypedResult defaultInclinationSource(C::mip_interface& device insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const MagneticDeclinationSource& self) { @@ -2961,7 +2961,7 @@ TypedResult writeMagneticDeclinationSource(C::mip_int assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut) { @@ -2972,7 +2972,7 @@ TypedResult readMagneticDeclinationSource(C::mip_inte assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_DECLINATION_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_DECLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2997,7 +2997,7 @@ TypedResult saveMagneticDeclinationSource(C::mip_inte insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadMagneticDeclinationSource(C::mip_interface& device) { @@ -3007,7 +3007,7 @@ TypedResult loadMagneticDeclinationSource(C::mip_inte insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultMagneticDeclinationSource(C::mip_interface& device) { @@ -3017,7 +3017,7 @@ TypedResult defaultMagneticDeclinationSource(C::mip_i insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const MagFieldMagnitudeSource& self) { @@ -3071,7 +3071,7 @@ TypedResult writeMagFieldMagnitudeSource(C::mip_interfa assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut) { @@ -3082,7 +3082,7 @@ TypedResult readMagFieldMagnitudeSource(C::mip_interfac assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3107,7 +3107,7 @@ TypedResult saveMagFieldMagnitudeSource(C::mip_interfac insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadMagFieldMagnitudeSource(C::mip_interface& device) { @@ -3117,7 +3117,7 @@ TypedResult loadMagFieldMagnitudeSource(C::mip_interfac insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultMagFieldMagnitudeSource(C::mip_interface& device) { @@ -3127,7 +3127,7 @@ TypedResult defaultMagFieldMagnitudeSource(C::mip_inter insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ReferencePosition& self) { @@ -3201,7 +3201,7 @@ TypedResult writeReferencePosition(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut) { @@ -3212,7 +3212,7 @@ TypedResult readReferencePosition(C::mip_interface& device, b assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_REFERENCE_POSITION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_REFERENCE_POSITION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3243,7 +3243,7 @@ TypedResult saveReferencePosition(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadReferencePosition(C::mip_interface& device) { @@ -3253,7 +3253,7 @@ TypedResult loadReferencePosition(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultReferencePosition(C::mip_interface& device) { @@ -3263,7 +3263,7 @@ TypedResult defaultReferencePosition(C::mip_interface& device insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self) { @@ -3367,7 +3367,7 @@ TypedResult writeAccelMagnitudeErrorAdap assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { @@ -3378,7 +3378,7 @@ TypedResult readAccelMagnitudeErrorAdapt assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3418,7 +3418,7 @@ TypedResult saveAccelMagnitudeErrorAdapt insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3428,7 +3428,7 @@ TypedResult loadAccelMagnitudeErrorAdapt insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3438,7 +3438,7 @@ TypedResult defaultAccelMagnitudeErrorAd insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self) { @@ -3542,7 +3542,7 @@ TypedResult writeMagMagnitudeErrorAdaptive assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { @@ -3553,7 +3553,7 @@ TypedResult readMagMagnitudeErrorAdaptiveM assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3593,7 +3593,7 @@ TypedResult saveMagMagnitudeErrorAdaptiveM insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3603,7 +3603,7 @@ TypedResult loadMagMagnitudeErrorAdaptiveM insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3613,7 +3613,7 @@ TypedResult defaultMagMagnitudeErrorAdapti insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self) { @@ -3697,7 +3697,7 @@ TypedResult writeMagDipAngleErrorAdaptiveMe assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { @@ -3708,7 +3708,7 @@ TypedResult readMagDipAngleErrorAdaptiveMea assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3742,7 +3742,7 @@ TypedResult saveMagDipAngleErrorAdaptiveMea insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3752,7 +3752,7 @@ TypedResult loadMagDipAngleErrorAdaptiveMea insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3762,7 +3762,7 @@ TypedResult defaultMagDipAngleErrorAdaptive insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AidingMeasurementEnable& self) { @@ -3816,7 +3816,7 @@ TypedResult writeAidingMeasurementEnable(C::mip_interfa assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut) { @@ -3829,7 +3829,7 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3855,7 +3855,7 @@ TypedResult saveAidingMeasurementEnable(C::mip_interfac assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { @@ -3867,7 +3867,7 @@ TypedResult loadAidingMeasurementEnable(C::mip_interfac assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { @@ -3879,7 +3879,7 @@ TypedResult defaultAidingMeasurementEnable(C::mip_inter assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const Run& self) { @@ -3958,7 +3958,7 @@ TypedResult writeKinematicConstraint(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut) { @@ -3969,7 +3969,7 @@ TypedResult readKinematicConstraint(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_KINEMATIC_CONSTRAINT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_KINEMATIC_CONSTRAINT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3997,7 +3997,7 @@ TypedResult saveKinematicConstraint(C::mip_interface& devic insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadKinematicConstraint(C::mip_interface& device) { @@ -4007,7 +4007,7 @@ TypedResult loadKinematicConstraint(C::mip_interface& devic insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultKinematicConstraint(C::mip_interface& device) { @@ -4017,7 +4017,7 @@ TypedResult defaultKinematicConstraint(C::mip_interface& de insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const InitializationConfiguration& self) { @@ -4153,7 +4153,7 @@ TypedResult writeInitializationConfiguration(C::mip assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut) { @@ -4164,7 +4164,7 @@ TypedResult readInitializationConfiguration(C::mip_ assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_INITIALIZATION_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_INITIALIZATION_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4212,7 +4212,7 @@ TypedResult saveInitializationConfiguration(C::mip_ insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadInitializationConfiguration(C::mip_interface& device) { @@ -4222,7 +4222,7 @@ TypedResult loadInitializationConfiguration(C::mip_ insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultInitializationConfiguration(C::mip_interface& device) { @@ -4232,7 +4232,7 @@ TypedResult defaultInitializationConfiguration(C::m insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const AdaptiveFilterOptions& self) { @@ -4286,7 +4286,7 @@ TypedResult writeAdaptiveFilterOptions(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut) { @@ -4297,7 +4297,7 @@ TypedResult readAdaptiveFilterOptions(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4322,7 +4322,7 @@ TypedResult saveAdaptiveFilterOptions(C::mip_interface& d insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadAdaptiveFilterOptions(C::mip_interface& device) { @@ -4332,7 +4332,7 @@ TypedResult loadAdaptiveFilterOptions(C::mip_interface& d insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultAdaptiveFilterOptions(C::mip_interface& device) { @@ -4342,7 +4342,7 @@ TypedResult defaultAdaptiveFilterOptions(C::mip_interface insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const MultiAntennaOffset& self) { @@ -4402,7 +4402,7 @@ TypedResult writeMultiAntennaOffset(C::mip_interface& device assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut) { @@ -4415,7 +4415,7 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_MULTI_ANTENNA_OFFSET, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MULTI_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4442,7 +4442,7 @@ TypedResult saveMultiAntennaOffset(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { @@ -4454,7 +4454,7 @@ TypedResult loadMultiAntennaOffset(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { @@ -4466,7 +4466,7 @@ TypedResult defaultMultiAntennaOffset(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const RelPosConfiguration& self) { @@ -4536,7 +4536,7 @@ TypedResult writeRelPosConfiguration(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut) { @@ -4547,7 +4547,7 @@ TypedResult readRelPosConfiguration(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_REL_POS_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_REL_POS_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4576,7 +4576,7 @@ TypedResult saveRelPosConfiguration(C::mip_interface& devic insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadRelPosConfiguration(C::mip_interface& device) { @@ -4586,7 +4586,7 @@ TypedResult loadRelPosConfiguration(C::mip_interface& devic insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultRelPosConfiguration(C::mip_interface& device) { @@ -4596,7 +4596,7 @@ TypedResult defaultRelPosConfiguration(C::mip_interface& de insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const RefPointLeverArm& self) { @@ -4656,7 +4656,7 @@ TypedResult writeRefPointLeverArm(C::mip_interface& device, Re assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut) { @@ -4667,7 +4667,7 @@ TypedResult readRefPointLeverArm(C::mip_interface& device, Ref assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_REF_POINT_LEVER_ARM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_REF_POINT_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4693,7 +4693,7 @@ TypedResult saveRefPointLeverArm(C::mip_interface& device) insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadRefPointLeverArm(C::mip_interface& device) { @@ -4703,7 +4703,7 @@ TypedResult loadRefPointLeverArm(C::mip_interface& device) insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultRefPointLeverArm(C::mip_interface& device) { @@ -4713,7 +4713,7 @@ TypedResult defaultRefPointLeverArm(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SpeedMeasurement& self) { @@ -4753,7 +4753,7 @@ TypedResult speedMeasurement(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_MEASUREMENT, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_MEASUREMENT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SpeedLeverArm& self) { @@ -4813,7 +4813,7 @@ TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut) { @@ -4826,7 +4826,7 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SPEED_LEVER_ARM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SPEED_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4853,7 +4853,7 @@ TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t s assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) { @@ -4865,7 +4865,7 @@ TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t s assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source) { @@ -4877,7 +4877,7 @@ TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const WheeledVehicleConstraintControl& self) { @@ -4921,7 +4921,7 @@ TypedResult writeWheeledVehicleConstraintContro assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut) { @@ -4932,7 +4932,7 @@ TypedResult readWheeledVehicleConstraintControl assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4954,7 +4954,7 @@ TypedResult saveWheeledVehicleConstraintControl insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadWheeledVehicleConstraintControl(C::mip_interface& device) { @@ -4964,7 +4964,7 @@ TypedResult loadWheeledVehicleConstraintControl insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultWheeledVehicleConstraintControl(C::mip_interface& device) { @@ -4974,7 +4974,7 @@ TypedResult defaultWheeledVehicleConstraintCont insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const VerticalGyroConstraintControl& self) { @@ -5018,7 +5018,7 @@ TypedResult writeVerticalGyroConstraintControl(C: assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut) { @@ -5029,7 +5029,7 @@ TypedResult readVerticalGyroConstraintControl(C:: assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5051,7 +5051,7 @@ TypedResult saveVerticalGyroConstraintControl(C:: insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadVerticalGyroConstraintControl(C::mip_interface& device) { @@ -5061,7 +5061,7 @@ TypedResult loadVerticalGyroConstraintControl(C:: insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultVerticalGyroConstraintControl(C::mip_interface& device) { @@ -5071,7 +5071,7 @@ TypedResult defaultVerticalGyroConstraintControl( insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GnssAntennaCalControl& self) { @@ -5125,7 +5125,7 @@ TypedResult writeGnssAntennaCalControl(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut) { @@ -5136,7 +5136,7 @@ TypedResult readGnssAntennaCalControl(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5161,7 +5161,7 @@ TypedResult saveGnssAntennaCalControl(C::mip_interface& d insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadGnssAntennaCalControl(C::mip_interface& device) { @@ -5171,7 +5171,7 @@ TypedResult loadGnssAntennaCalControl(C::mip_interface& d insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultGnssAntennaCalControl(C::mip_interface& device) { @@ -5181,7 +5181,7 @@ TypedResult defaultGnssAntennaCalControl(C::mip_interface insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const SetInitialHeading& self) { @@ -5203,7 +5203,7 @@ TypedResult setInitialHeading(C::mip_interface& device, float assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_HEADING, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_HEADING, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } } // namespace commands_filter diff --git a/src/mip/definitions/commands_filter.h b/src/mip/definitions/commands_filter.h index 8fddf4cd7..57eda7e63 100644 --- a/src/mip/definitions/commands_filter.h +++ b/src/mip/definitions/commands_filter.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -160,24 +160,24 @@ typedef uint8_t mip_filter_reference_frame; static const mip_filter_reference_frame MIP_FILTER_REFERENCE_FRAME_ECEF = 1; ///< WGS84 Earth-fixed, earth centered coordinates static const mip_filter_reference_frame MIP_FILTER_REFERENCE_FRAME_LLH = 2; ///< WGS84 Latitude, longitude, and height above ellipsoid -void insert_mip_filter_reference_frame(struct mip_serializer* serializer, const mip_filter_reference_frame self); -void extract_mip_filter_reference_frame(struct mip_serializer* serializer, mip_filter_reference_frame* self); +void insert_mip_filter_reference_frame(struct microstrain_serializer* serializer, const mip_filter_reference_frame self); +void extract_mip_filter_reference_frame(struct microstrain_serializer* serializer, mip_filter_reference_frame* self); typedef uint8_t mip_filter_mag_param_source; static const mip_filter_mag_param_source MIP_FILTER_MAG_PARAM_SOURCE_NONE = 1; ///< No source. See command documentation for default behavior static const mip_filter_mag_param_source MIP_FILTER_MAG_PARAM_SOURCE_WMM = 2; ///< Magnetic field is assumed to conform to the World Magnetic Model, calculated using current location estimate as an input to the model. static const mip_filter_mag_param_source MIP_FILTER_MAG_PARAM_SOURCE_MANUAL = 3; ///< Magnetic field is assumed to have the parameter specified by the user. -void insert_mip_filter_mag_param_source(struct mip_serializer* serializer, const mip_filter_mag_param_source self); -void extract_mip_filter_mag_param_source(struct mip_serializer* serializer, mip_filter_mag_param_source* self); +void insert_mip_filter_mag_param_source(struct microstrain_serializer* serializer, const mip_filter_mag_param_source self); +void extract_mip_filter_mag_param_source(struct microstrain_serializer* serializer, mip_filter_mag_param_source* self); typedef uint8_t mip_filter_adaptive_measurement; static const mip_filter_adaptive_measurement MIP_FILTER_ADAPTIVE_MEASUREMENT_DISABLED = 0; ///< No adaptive measurement static const mip_filter_adaptive_measurement MIP_FILTER_ADAPTIVE_MEASUREMENT_FIXED = 1; ///< Enable fixed adaptive measurement (use specified limits) static const mip_filter_adaptive_measurement MIP_FILTER_ADAPTIVE_MEASUREMENT_AUTO = 2; ///< Enable auto adaptive measurement -void insert_mip_filter_adaptive_measurement(struct mip_serializer* serializer, const mip_filter_adaptive_measurement self); -void extract_mip_filter_adaptive_measurement(struct mip_serializer* serializer, mip_filter_adaptive_measurement* self); +void insert_mip_filter_adaptive_measurement(struct microstrain_serializer* serializer, const mip_filter_adaptive_measurement self); +void extract_mip_filter_adaptive_measurement(struct microstrain_serializer* serializer, mip_filter_adaptive_measurement* self); //////////////////////////////////////////////////////////////////////////////// @@ -222,8 +222,8 @@ struct mip_filter_set_initial_attitude_command }; typedef struct mip_filter_set_initial_attitude_command mip_filter_set_initial_attitude_command; -void insert_mip_filter_set_initial_attitude_command(struct mip_serializer* serializer, const mip_filter_set_initial_attitude_command* self); -void extract_mip_filter_set_initial_attitude_command(struct mip_serializer* serializer, mip_filter_set_initial_attitude_command* self); +void insert_mip_filter_set_initial_attitude_command(struct microstrain_serializer* serializer, const mip_filter_set_initial_attitude_command* self); +void extract_mip_filter_set_initial_attitude_command(struct microstrain_serializer* serializer, mip_filter_set_initial_attitude_command* self); mip_cmd_result mip_filter_set_initial_attitude(struct mip_interface* device, float roll, float pitch, float heading); @@ -263,11 +263,11 @@ struct mip_filter_estimation_control_command }; typedef struct mip_filter_estimation_control_command mip_filter_estimation_control_command; -void insert_mip_filter_estimation_control_command(struct mip_serializer* serializer, const mip_filter_estimation_control_command* self); -void extract_mip_filter_estimation_control_command(struct mip_serializer* serializer, mip_filter_estimation_control_command* self); +void insert_mip_filter_estimation_control_command(struct microstrain_serializer* serializer, const mip_filter_estimation_control_command* self); +void extract_mip_filter_estimation_control_command(struct microstrain_serializer* serializer, mip_filter_estimation_control_command* self); -void insert_mip_filter_estimation_control_command_enable_flags(struct mip_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self); -void extract_mip_filter_estimation_control_command_enable_flags(struct mip_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self); +void insert_mip_filter_estimation_control_command_enable_flags(struct microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self); +void extract_mip_filter_estimation_control_command_enable_flags(struct microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self); struct mip_filter_estimation_control_response { @@ -275,8 +275,8 @@ struct mip_filter_estimation_control_response }; typedef struct mip_filter_estimation_control_response mip_filter_estimation_control_response; -void insert_mip_filter_estimation_control_response(struct mip_serializer* serializer, const mip_filter_estimation_control_response* self); -void extract_mip_filter_estimation_control_response(struct mip_serializer* serializer, mip_filter_estimation_control_response* self); +void insert_mip_filter_estimation_control_response(struct microstrain_serializer* serializer, const mip_filter_estimation_control_response* self); +void extract_mip_filter_estimation_control_response(struct microstrain_serializer* serializer, mip_filter_estimation_control_response* self); mip_cmd_result mip_filter_write_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags enable); mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags* enable_out); @@ -309,8 +309,8 @@ struct mip_filter_external_gnss_update_command }; typedef struct mip_filter_external_gnss_update_command mip_filter_external_gnss_update_command; -void insert_mip_filter_external_gnss_update_command(struct mip_serializer* serializer, const mip_filter_external_gnss_update_command* self); -void extract_mip_filter_external_gnss_update_command(struct mip_serializer* serializer, mip_filter_external_gnss_update_command* self); +void insert_mip_filter_external_gnss_update_command(struct microstrain_serializer* serializer, const mip_filter_external_gnss_update_command* self); +void extract_mip_filter_external_gnss_update_command(struct microstrain_serializer* serializer, mip_filter_external_gnss_update_command* self); mip_cmd_result mip_filter_external_gnss_update(struct mip_interface* device, double gps_time, uint16_t gps_week, double latitude, double longitude, double height, const float* velocity, const float* pos_uncertainty, const float* vel_uncertainty); @@ -342,8 +342,8 @@ struct mip_filter_external_heading_update_command }; typedef struct mip_filter_external_heading_update_command mip_filter_external_heading_update_command; -void insert_mip_filter_external_heading_update_command(struct mip_serializer* serializer, const mip_filter_external_heading_update_command* self); -void extract_mip_filter_external_heading_update_command(struct mip_serializer* serializer, mip_filter_external_heading_update_command* self); +void insert_mip_filter_external_heading_update_command(struct microstrain_serializer* serializer, const mip_filter_external_heading_update_command* self); +void extract_mip_filter_external_heading_update_command(struct microstrain_serializer* serializer, mip_filter_external_heading_update_command* self); mip_cmd_result mip_filter_external_heading_update(struct mip_interface* device, float heading, float heading_uncertainty, uint8_t type); @@ -381,8 +381,8 @@ struct mip_filter_external_heading_update_with_time_command }; typedef struct mip_filter_external_heading_update_with_time_command mip_filter_external_heading_update_with_time_command; -void insert_mip_filter_external_heading_update_with_time_command(struct mip_serializer* serializer, const mip_filter_external_heading_update_with_time_command* self); -void extract_mip_filter_external_heading_update_with_time_command(struct mip_serializer* serializer, mip_filter_external_heading_update_with_time_command* self); +void insert_mip_filter_external_heading_update_with_time_command(struct microstrain_serializer* serializer, const mip_filter_external_heading_update_with_time_command* self); +void extract_mip_filter_external_heading_update_with_time_command(struct microstrain_serializer* serializer, mip_filter_external_heading_update_with_time_command* self); mip_cmd_result mip_filter_external_heading_update_with_time(struct mip_interface* device, double gps_time, uint16_t gps_week, float heading, float heading_uncertainty, uint8_t type); @@ -412,11 +412,11 @@ struct mip_filter_tare_orientation_command }; typedef struct mip_filter_tare_orientation_command mip_filter_tare_orientation_command; -void insert_mip_filter_tare_orientation_command(struct mip_serializer* serializer, const mip_filter_tare_orientation_command* self); -void extract_mip_filter_tare_orientation_command(struct mip_serializer* serializer, mip_filter_tare_orientation_command* self); +void insert_mip_filter_tare_orientation_command(struct microstrain_serializer* serializer, const mip_filter_tare_orientation_command* self); +void extract_mip_filter_tare_orientation_command(struct microstrain_serializer* serializer, mip_filter_tare_orientation_command* self); -void insert_mip_filter_tare_orientation_command_mip_tare_axes(struct mip_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self); -void extract_mip_filter_tare_orientation_command_mip_tare_axes(struct mip_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self); +void insert_mip_filter_tare_orientation_command_mip_tare_axes(struct microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self); +void extract_mip_filter_tare_orientation_command_mip_tare_axes(struct microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self); struct mip_filter_tare_orientation_response { @@ -424,8 +424,8 @@ struct mip_filter_tare_orientation_response }; typedef struct mip_filter_tare_orientation_response mip_filter_tare_orientation_response; -void insert_mip_filter_tare_orientation_response(struct mip_serializer* serializer, const mip_filter_tare_orientation_response* self); -void extract_mip_filter_tare_orientation_response(struct mip_serializer* serializer, mip_filter_tare_orientation_response* self); +void insert_mip_filter_tare_orientation_response(struct microstrain_serializer* serializer, const mip_filter_tare_orientation_response* self); +void extract_mip_filter_tare_orientation_response(struct microstrain_serializer* serializer, mip_filter_tare_orientation_response* self); mip_cmd_result mip_filter_write_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes axes); mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes* axes_out); @@ -454,11 +454,11 @@ struct mip_filter_vehicle_dynamics_mode_command }; typedef struct mip_filter_vehicle_dynamics_mode_command mip_filter_vehicle_dynamics_mode_command; -void insert_mip_filter_vehicle_dynamics_mode_command(struct mip_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self); -void extract_mip_filter_vehicle_dynamics_mode_command(struct mip_serializer* serializer, mip_filter_vehicle_dynamics_mode_command* self); +void insert_mip_filter_vehicle_dynamics_mode_command(struct microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self); +void extract_mip_filter_vehicle_dynamics_mode_command(struct microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command* self); -void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct mip_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self); -void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct mip_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self); +void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self); +void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self); struct mip_filter_vehicle_dynamics_mode_response { @@ -466,8 +466,8 @@ struct mip_filter_vehicle_dynamics_mode_response }; typedef struct mip_filter_vehicle_dynamics_mode_response mip_filter_vehicle_dynamics_mode_response; -void insert_mip_filter_vehicle_dynamics_mode_response(struct mip_serializer* serializer, const mip_filter_vehicle_dynamics_mode_response* self); -void extract_mip_filter_vehicle_dynamics_mode_response(struct mip_serializer* serializer, mip_filter_vehicle_dynamics_mode_response* self); +void insert_mip_filter_vehicle_dynamics_mode_response(struct microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_response* self); +void extract_mip_filter_vehicle_dynamics_mode_response(struct microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_response* self); mip_cmd_result mip_filter_write_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode); mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* mode_out); @@ -514,8 +514,8 @@ struct mip_filter_sensor_to_vehicle_rotation_euler_command }; typedef struct mip_filter_sensor_to_vehicle_rotation_euler_command mip_filter_sensor_to_vehicle_rotation_euler_command; -void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(struct mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self); -void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(struct mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_command* self); +void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self); +void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_command* self); struct mip_filter_sensor_to_vehicle_rotation_euler_response { @@ -525,8 +525,8 @@ struct mip_filter_sensor_to_vehicle_rotation_euler_response }; typedef struct mip_filter_sensor_to_vehicle_rotation_euler_response mip_filter_sensor_to_vehicle_rotation_euler_response; -void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(struct mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self); -void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(struct mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self); +void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self); +void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self); mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float roll, float pitch, float yaw); mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out); @@ -577,8 +577,8 @@ struct mip_filter_sensor_to_vehicle_rotation_dcm_command }; typedef struct mip_filter_sensor_to_vehicle_rotation_dcm_command mip_filter_sensor_to_vehicle_rotation_dcm_command; -void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(struct mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_command* self); -void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(struct mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_command* self); +void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_command* self); +void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_command* self); struct mip_filter_sensor_to_vehicle_rotation_dcm_response { @@ -586,8 +586,8 @@ struct mip_filter_sensor_to_vehicle_rotation_dcm_response }; typedef struct mip_filter_sensor_to_vehicle_rotation_dcm_response mip_filter_sensor_to_vehicle_rotation_dcm_response; -void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(struct mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self); -void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(struct mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self); +void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self); +void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self); mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, const float* dcm); mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, float* dcm_out); @@ -637,8 +637,8 @@ struct mip_filter_sensor_to_vehicle_rotation_quaternion_command }; typedef struct mip_filter_sensor_to_vehicle_rotation_quaternion_command mip_filter_sensor_to_vehicle_rotation_quaternion_command; -void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(struct mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); -void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(struct mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); +void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); +void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); struct mip_filter_sensor_to_vehicle_rotation_quaternion_response { @@ -646,8 +646,8 @@ struct mip_filter_sensor_to_vehicle_rotation_quaternion_response }; typedef struct mip_filter_sensor_to_vehicle_rotation_quaternion_response mip_filter_sensor_to_vehicle_rotation_quaternion_response; -void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(struct mip_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); -void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(struct mip_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); +void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); +void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, const float* quat); mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, float* quat_out); @@ -678,8 +678,8 @@ struct mip_filter_sensor_to_vehicle_offset_command }; typedef struct mip_filter_sensor_to_vehicle_offset_command mip_filter_sensor_to_vehicle_offset_command; -void insert_mip_filter_sensor_to_vehicle_offset_command(struct mip_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_command* self); -void extract_mip_filter_sensor_to_vehicle_offset_command(struct mip_serializer* serializer, mip_filter_sensor_to_vehicle_offset_command* self); +void insert_mip_filter_sensor_to_vehicle_offset_command(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_command* self); +void extract_mip_filter_sensor_to_vehicle_offset_command(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_command* self); struct mip_filter_sensor_to_vehicle_offset_response { @@ -687,8 +687,8 @@ struct mip_filter_sensor_to_vehicle_offset_response }; typedef struct mip_filter_sensor_to_vehicle_offset_response mip_filter_sensor_to_vehicle_offset_response; -void insert_mip_filter_sensor_to_vehicle_offset_response(struct mip_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self); -void extract_mip_filter_sensor_to_vehicle_offset_response(struct mip_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self); +void insert_mip_filter_sensor_to_vehicle_offset_response(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self); +void extract_mip_filter_sensor_to_vehicle_offset_response(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self); mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(struct mip_interface* device, const float* offset); mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* device, float* offset_out); @@ -716,8 +716,8 @@ struct mip_filter_antenna_offset_command }; typedef struct mip_filter_antenna_offset_command mip_filter_antenna_offset_command; -void insert_mip_filter_antenna_offset_command(struct mip_serializer* serializer, const mip_filter_antenna_offset_command* self); -void extract_mip_filter_antenna_offset_command(struct mip_serializer* serializer, mip_filter_antenna_offset_command* self); +void insert_mip_filter_antenna_offset_command(struct microstrain_serializer* serializer, const mip_filter_antenna_offset_command* self); +void extract_mip_filter_antenna_offset_command(struct microstrain_serializer* serializer, mip_filter_antenna_offset_command* self); struct mip_filter_antenna_offset_response { @@ -725,8 +725,8 @@ struct mip_filter_antenna_offset_response }; typedef struct mip_filter_antenna_offset_response mip_filter_antenna_offset_response; -void insert_mip_filter_antenna_offset_response(struct mip_serializer* serializer, const mip_filter_antenna_offset_response* self); -void extract_mip_filter_antenna_offset_response(struct mip_serializer* serializer, mip_filter_antenna_offset_response* self); +void insert_mip_filter_antenna_offset_response(struct microstrain_serializer* serializer, const mip_filter_antenna_offset_response* self); +void extract_mip_filter_antenna_offset_response(struct microstrain_serializer* serializer, mip_filter_antenna_offset_response* self); mip_cmd_result mip_filter_write_antenna_offset(struct mip_interface* device, const float* offset); mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, float* offset_out); @@ -759,11 +759,11 @@ struct mip_filter_gnss_source_command }; typedef struct mip_filter_gnss_source_command mip_filter_gnss_source_command; -void insert_mip_filter_gnss_source_command(struct mip_serializer* serializer, const mip_filter_gnss_source_command* self); -void extract_mip_filter_gnss_source_command(struct mip_serializer* serializer, mip_filter_gnss_source_command* self); +void insert_mip_filter_gnss_source_command(struct microstrain_serializer* serializer, const mip_filter_gnss_source_command* self); +void extract_mip_filter_gnss_source_command(struct microstrain_serializer* serializer, mip_filter_gnss_source_command* self); -void insert_mip_filter_gnss_source_command_source(struct mip_serializer* serializer, const mip_filter_gnss_source_command_source self); -void extract_mip_filter_gnss_source_command_source(struct mip_serializer* serializer, mip_filter_gnss_source_command_source* self); +void insert_mip_filter_gnss_source_command_source(struct microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self); +void extract_mip_filter_gnss_source_command_source(struct microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self); struct mip_filter_gnss_source_response { @@ -771,8 +771,8 @@ struct mip_filter_gnss_source_response }; typedef struct mip_filter_gnss_source_response mip_filter_gnss_source_response; -void insert_mip_filter_gnss_source_response(struct mip_serializer* serializer, const mip_filter_gnss_source_response* self); -void extract_mip_filter_gnss_source_response(struct mip_serializer* serializer, mip_filter_gnss_source_response* self); +void insert_mip_filter_gnss_source_response(struct microstrain_serializer* serializer, const mip_filter_gnss_source_response* self); +void extract_mip_filter_gnss_source_response(struct microstrain_serializer* serializer, mip_filter_gnss_source_response* self); mip_cmd_result mip_filter_write_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source source); mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source* source_out); @@ -816,11 +816,11 @@ struct mip_filter_heading_source_command }; typedef struct mip_filter_heading_source_command mip_filter_heading_source_command; -void insert_mip_filter_heading_source_command(struct mip_serializer* serializer, const mip_filter_heading_source_command* self); -void extract_mip_filter_heading_source_command(struct mip_serializer* serializer, mip_filter_heading_source_command* self); +void insert_mip_filter_heading_source_command(struct microstrain_serializer* serializer, const mip_filter_heading_source_command* self); +void extract_mip_filter_heading_source_command(struct microstrain_serializer* serializer, mip_filter_heading_source_command* self); -void insert_mip_filter_heading_source_command_source(struct mip_serializer* serializer, const mip_filter_heading_source_command_source self); -void extract_mip_filter_heading_source_command_source(struct mip_serializer* serializer, mip_filter_heading_source_command_source* self); +void insert_mip_filter_heading_source_command_source(struct microstrain_serializer* serializer, const mip_filter_heading_source_command_source self); +void extract_mip_filter_heading_source_command_source(struct microstrain_serializer* serializer, mip_filter_heading_source_command_source* self); struct mip_filter_heading_source_response { @@ -828,8 +828,8 @@ struct mip_filter_heading_source_response }; typedef struct mip_filter_heading_source_response mip_filter_heading_source_response; -void insert_mip_filter_heading_source_response(struct mip_serializer* serializer, const mip_filter_heading_source_response* self); -void extract_mip_filter_heading_source_response(struct mip_serializer* serializer, mip_filter_heading_source_response* self); +void insert_mip_filter_heading_source_response(struct microstrain_serializer* serializer, const mip_filter_heading_source_response* self); +void extract_mip_filter_heading_source_response(struct microstrain_serializer* serializer, mip_filter_heading_source_response* self); mip_cmd_result mip_filter_write_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source source); mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source* source_out); @@ -860,8 +860,8 @@ struct mip_filter_auto_init_control_command }; typedef struct mip_filter_auto_init_control_command mip_filter_auto_init_control_command; -void insert_mip_filter_auto_init_control_command(struct mip_serializer* serializer, const mip_filter_auto_init_control_command* self); -void extract_mip_filter_auto_init_control_command(struct mip_serializer* serializer, mip_filter_auto_init_control_command* self); +void insert_mip_filter_auto_init_control_command(struct microstrain_serializer* serializer, const mip_filter_auto_init_control_command* self); +void extract_mip_filter_auto_init_control_command(struct microstrain_serializer* serializer, mip_filter_auto_init_control_command* self); struct mip_filter_auto_init_control_response { @@ -869,8 +869,8 @@ struct mip_filter_auto_init_control_response }; typedef struct mip_filter_auto_init_control_response mip_filter_auto_init_control_response; -void insert_mip_filter_auto_init_control_response(struct mip_serializer* serializer, const mip_filter_auto_init_control_response* self); -void extract_mip_filter_auto_init_control_response(struct mip_serializer* serializer, mip_filter_auto_init_control_response* self); +void insert_mip_filter_auto_init_control_response(struct microstrain_serializer* serializer, const mip_filter_auto_init_control_response* self); +void extract_mip_filter_auto_init_control_response(struct microstrain_serializer* serializer, mip_filter_auto_init_control_response* self); mip_cmd_result mip_filter_write_auto_init_control(struct mip_interface* device, uint8_t enable); mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, uint8_t* enable_out); @@ -899,8 +899,8 @@ struct mip_filter_accel_noise_command }; typedef struct mip_filter_accel_noise_command mip_filter_accel_noise_command; -void insert_mip_filter_accel_noise_command(struct mip_serializer* serializer, const mip_filter_accel_noise_command* self); -void extract_mip_filter_accel_noise_command(struct mip_serializer* serializer, mip_filter_accel_noise_command* self); +void insert_mip_filter_accel_noise_command(struct microstrain_serializer* serializer, const mip_filter_accel_noise_command* self); +void extract_mip_filter_accel_noise_command(struct microstrain_serializer* serializer, mip_filter_accel_noise_command* self); struct mip_filter_accel_noise_response { @@ -908,8 +908,8 @@ struct mip_filter_accel_noise_response }; typedef struct mip_filter_accel_noise_response mip_filter_accel_noise_response; -void insert_mip_filter_accel_noise_response(struct mip_serializer* serializer, const mip_filter_accel_noise_response* self); -void extract_mip_filter_accel_noise_response(struct mip_serializer* serializer, mip_filter_accel_noise_response* self); +void insert_mip_filter_accel_noise_response(struct microstrain_serializer* serializer, const mip_filter_accel_noise_response* self); +void extract_mip_filter_accel_noise_response(struct microstrain_serializer* serializer, mip_filter_accel_noise_response* self); mip_cmd_result mip_filter_write_accel_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* noise_out); @@ -938,8 +938,8 @@ struct mip_filter_gyro_noise_command }; typedef struct mip_filter_gyro_noise_command mip_filter_gyro_noise_command; -void insert_mip_filter_gyro_noise_command(struct mip_serializer* serializer, const mip_filter_gyro_noise_command* self); -void extract_mip_filter_gyro_noise_command(struct mip_serializer* serializer, mip_filter_gyro_noise_command* self); +void insert_mip_filter_gyro_noise_command(struct microstrain_serializer* serializer, const mip_filter_gyro_noise_command* self); +void extract_mip_filter_gyro_noise_command(struct microstrain_serializer* serializer, mip_filter_gyro_noise_command* self); struct mip_filter_gyro_noise_response { @@ -947,8 +947,8 @@ struct mip_filter_gyro_noise_response }; typedef struct mip_filter_gyro_noise_response mip_filter_gyro_noise_response; -void insert_mip_filter_gyro_noise_response(struct mip_serializer* serializer, const mip_filter_gyro_noise_response* self); -void extract_mip_filter_gyro_noise_response(struct mip_serializer* serializer, mip_filter_gyro_noise_response* self); +void insert_mip_filter_gyro_noise_response(struct microstrain_serializer* serializer, const mip_filter_gyro_noise_response* self); +void extract_mip_filter_gyro_noise_response(struct microstrain_serializer* serializer, mip_filter_gyro_noise_response* self); mip_cmd_result mip_filter_write_gyro_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* noise_out); @@ -975,8 +975,8 @@ struct mip_filter_accel_bias_model_command }; typedef struct mip_filter_accel_bias_model_command mip_filter_accel_bias_model_command; -void insert_mip_filter_accel_bias_model_command(struct mip_serializer* serializer, const mip_filter_accel_bias_model_command* self); -void extract_mip_filter_accel_bias_model_command(struct mip_serializer* serializer, mip_filter_accel_bias_model_command* self); +void insert_mip_filter_accel_bias_model_command(struct microstrain_serializer* serializer, const mip_filter_accel_bias_model_command* self); +void extract_mip_filter_accel_bias_model_command(struct microstrain_serializer* serializer, mip_filter_accel_bias_model_command* self); struct mip_filter_accel_bias_model_response { @@ -985,8 +985,8 @@ struct mip_filter_accel_bias_model_response }; typedef struct mip_filter_accel_bias_model_response mip_filter_accel_bias_model_response; -void insert_mip_filter_accel_bias_model_response(struct mip_serializer* serializer, const mip_filter_accel_bias_model_response* self); -void extract_mip_filter_accel_bias_model_response(struct mip_serializer* serializer, mip_filter_accel_bias_model_response* self); +void insert_mip_filter_accel_bias_model_response(struct microstrain_serializer* serializer, const mip_filter_accel_bias_model_response* self); +void extract_mip_filter_accel_bias_model_response(struct microstrain_serializer* serializer, mip_filter_accel_bias_model_response* self); mip_cmd_result mip_filter_write_accel_bias_model(struct mip_interface* device, const float* beta, const float* noise); mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, float* beta_out, float* noise_out); @@ -1013,8 +1013,8 @@ struct mip_filter_gyro_bias_model_command }; typedef struct mip_filter_gyro_bias_model_command mip_filter_gyro_bias_model_command; -void insert_mip_filter_gyro_bias_model_command(struct mip_serializer* serializer, const mip_filter_gyro_bias_model_command* self); -void extract_mip_filter_gyro_bias_model_command(struct mip_serializer* serializer, mip_filter_gyro_bias_model_command* self); +void insert_mip_filter_gyro_bias_model_command(struct microstrain_serializer* serializer, const mip_filter_gyro_bias_model_command* self); +void extract_mip_filter_gyro_bias_model_command(struct microstrain_serializer* serializer, mip_filter_gyro_bias_model_command* self); struct mip_filter_gyro_bias_model_response { @@ -1023,8 +1023,8 @@ struct mip_filter_gyro_bias_model_response }; typedef struct mip_filter_gyro_bias_model_response mip_filter_gyro_bias_model_response; -void insert_mip_filter_gyro_bias_model_response(struct mip_serializer* serializer, const mip_filter_gyro_bias_model_response* self); -void extract_mip_filter_gyro_bias_model_response(struct mip_serializer* serializer, mip_filter_gyro_bias_model_response* self); +void insert_mip_filter_gyro_bias_model_response(struct microstrain_serializer* serializer, const mip_filter_gyro_bias_model_response* self); +void extract_mip_filter_gyro_bias_model_response(struct microstrain_serializer* serializer, mip_filter_gyro_bias_model_response* self); mip_cmd_result mip_filter_write_gyro_bias_model(struct mip_interface* device, const float* beta, const float* noise); mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, float* beta_out, float* noise_out); @@ -1055,11 +1055,11 @@ struct mip_filter_altitude_aiding_command }; typedef struct mip_filter_altitude_aiding_command mip_filter_altitude_aiding_command; -void insert_mip_filter_altitude_aiding_command(struct mip_serializer* serializer, const mip_filter_altitude_aiding_command* self); -void extract_mip_filter_altitude_aiding_command(struct mip_serializer* serializer, mip_filter_altitude_aiding_command* self); +void insert_mip_filter_altitude_aiding_command(struct microstrain_serializer* serializer, const mip_filter_altitude_aiding_command* self); +void extract_mip_filter_altitude_aiding_command(struct microstrain_serializer* serializer, mip_filter_altitude_aiding_command* self); -void insert_mip_filter_altitude_aiding_command_aiding_selector(struct mip_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self); -void extract_mip_filter_altitude_aiding_command_aiding_selector(struct mip_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self); +void insert_mip_filter_altitude_aiding_command_aiding_selector(struct microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self); +void extract_mip_filter_altitude_aiding_command_aiding_selector(struct microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self); struct mip_filter_altitude_aiding_response { @@ -1067,8 +1067,8 @@ struct mip_filter_altitude_aiding_response }; typedef struct mip_filter_altitude_aiding_response mip_filter_altitude_aiding_response; -void insert_mip_filter_altitude_aiding_response(struct mip_serializer* serializer, const mip_filter_altitude_aiding_response* self); -void extract_mip_filter_altitude_aiding_response(struct mip_serializer* serializer, mip_filter_altitude_aiding_response* self); +void insert_mip_filter_altitude_aiding_response(struct microstrain_serializer* serializer, const mip_filter_altitude_aiding_response* self); +void extract_mip_filter_altitude_aiding_response(struct microstrain_serializer* serializer, mip_filter_altitude_aiding_response* self); mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector selector); mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector* selector_out); @@ -1096,11 +1096,11 @@ struct mip_filter_pitch_roll_aiding_command }; typedef struct mip_filter_pitch_roll_aiding_command mip_filter_pitch_roll_aiding_command; -void insert_mip_filter_pitch_roll_aiding_command(struct mip_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self); -void extract_mip_filter_pitch_roll_aiding_command(struct mip_serializer* serializer, mip_filter_pitch_roll_aiding_command* self); +void insert_mip_filter_pitch_roll_aiding_command(struct microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self); +void extract_mip_filter_pitch_roll_aiding_command(struct microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command* self); -void insert_mip_filter_pitch_roll_aiding_command_aiding_source(struct mip_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self); -void extract_mip_filter_pitch_roll_aiding_command_aiding_source(struct mip_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self); +void insert_mip_filter_pitch_roll_aiding_command_aiding_source(struct microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self); +void extract_mip_filter_pitch_roll_aiding_command_aiding_source(struct microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self); struct mip_filter_pitch_roll_aiding_response { @@ -1108,8 +1108,8 @@ struct mip_filter_pitch_roll_aiding_response }; typedef struct mip_filter_pitch_roll_aiding_response mip_filter_pitch_roll_aiding_response; -void insert_mip_filter_pitch_roll_aiding_response(struct mip_serializer* serializer, const mip_filter_pitch_roll_aiding_response* self); -void extract_mip_filter_pitch_roll_aiding_response(struct mip_serializer* serializer, mip_filter_pitch_roll_aiding_response* self); +void insert_mip_filter_pitch_roll_aiding_response(struct microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_response* self); +void extract_mip_filter_pitch_roll_aiding_response(struct microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_response* self); mip_cmd_result mip_filter_write_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source source); mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source* source_out); @@ -1134,8 +1134,8 @@ struct mip_filter_auto_zupt_command }; typedef struct mip_filter_auto_zupt_command mip_filter_auto_zupt_command; -void insert_mip_filter_auto_zupt_command(struct mip_serializer* serializer, const mip_filter_auto_zupt_command* self); -void extract_mip_filter_auto_zupt_command(struct mip_serializer* serializer, mip_filter_auto_zupt_command* self); +void insert_mip_filter_auto_zupt_command(struct microstrain_serializer* serializer, const mip_filter_auto_zupt_command* self); +void extract_mip_filter_auto_zupt_command(struct microstrain_serializer* serializer, mip_filter_auto_zupt_command* self); struct mip_filter_auto_zupt_response { @@ -1144,8 +1144,8 @@ struct mip_filter_auto_zupt_response }; typedef struct mip_filter_auto_zupt_response mip_filter_auto_zupt_response; -void insert_mip_filter_auto_zupt_response(struct mip_serializer* serializer, const mip_filter_auto_zupt_response* self); -void extract_mip_filter_auto_zupt_response(struct mip_serializer* serializer, mip_filter_auto_zupt_response* self); +void insert_mip_filter_auto_zupt_response(struct microstrain_serializer* serializer, const mip_filter_auto_zupt_response* self); +void extract_mip_filter_auto_zupt_response(struct microstrain_serializer* serializer, mip_filter_auto_zupt_response* self); mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t enable, float threshold); mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out); @@ -1171,8 +1171,8 @@ struct mip_filter_auto_angular_zupt_command }; typedef struct mip_filter_auto_angular_zupt_command mip_filter_auto_angular_zupt_command; -void insert_mip_filter_auto_angular_zupt_command(struct mip_serializer* serializer, const mip_filter_auto_angular_zupt_command* self); -void extract_mip_filter_auto_angular_zupt_command(struct mip_serializer* serializer, mip_filter_auto_angular_zupt_command* self); +void insert_mip_filter_auto_angular_zupt_command(struct microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_command* self); +void extract_mip_filter_auto_angular_zupt_command(struct microstrain_serializer* serializer, mip_filter_auto_angular_zupt_command* self); struct mip_filter_auto_angular_zupt_response { @@ -1181,8 +1181,8 @@ struct mip_filter_auto_angular_zupt_response }; typedef struct mip_filter_auto_angular_zupt_response mip_filter_auto_angular_zupt_response; -void insert_mip_filter_auto_angular_zupt_response(struct mip_serializer* serializer, const mip_filter_auto_angular_zupt_response* self); -void extract_mip_filter_auto_angular_zupt_response(struct mip_serializer* serializer, mip_filter_auto_angular_zupt_response* self); +void insert_mip_filter_auto_angular_zupt_response(struct microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_response* self); +void extract_mip_filter_auto_angular_zupt_response(struct microstrain_serializer* serializer, mip_filter_auto_angular_zupt_response* self); mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, uint8_t enable, float threshold); mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out); @@ -1226,8 +1226,8 @@ struct mip_filter_mag_capture_auto_cal_command }; typedef struct mip_filter_mag_capture_auto_cal_command mip_filter_mag_capture_auto_cal_command; -void insert_mip_filter_mag_capture_auto_cal_command(struct mip_serializer* serializer, const mip_filter_mag_capture_auto_cal_command* self); -void extract_mip_filter_mag_capture_auto_cal_command(struct mip_serializer* serializer, mip_filter_mag_capture_auto_cal_command* self); +void insert_mip_filter_mag_capture_auto_cal_command(struct microstrain_serializer* serializer, const mip_filter_mag_capture_auto_cal_command* self); +void extract_mip_filter_mag_capture_auto_cal_command(struct microstrain_serializer* serializer, mip_filter_mag_capture_auto_cal_command* self); mip_cmd_result mip_filter_write_mag_capture_auto_cal(struct mip_interface* device); mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device); @@ -1252,8 +1252,8 @@ struct mip_filter_gravity_noise_command }; typedef struct mip_filter_gravity_noise_command mip_filter_gravity_noise_command; -void insert_mip_filter_gravity_noise_command(struct mip_serializer* serializer, const mip_filter_gravity_noise_command* self); -void extract_mip_filter_gravity_noise_command(struct mip_serializer* serializer, mip_filter_gravity_noise_command* self); +void insert_mip_filter_gravity_noise_command(struct microstrain_serializer* serializer, const mip_filter_gravity_noise_command* self); +void extract_mip_filter_gravity_noise_command(struct microstrain_serializer* serializer, mip_filter_gravity_noise_command* self); struct mip_filter_gravity_noise_response { @@ -1261,8 +1261,8 @@ struct mip_filter_gravity_noise_response }; typedef struct mip_filter_gravity_noise_response mip_filter_gravity_noise_response; -void insert_mip_filter_gravity_noise_response(struct mip_serializer* serializer, const mip_filter_gravity_noise_response* self); -void extract_mip_filter_gravity_noise_response(struct mip_serializer* serializer, mip_filter_gravity_noise_response* self); +void insert_mip_filter_gravity_noise_response(struct microstrain_serializer* serializer, const mip_filter_gravity_noise_response* self); +void extract_mip_filter_gravity_noise_response(struct microstrain_serializer* serializer, mip_filter_gravity_noise_response* self); mip_cmd_result mip_filter_write_gravity_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float* noise_out); @@ -1290,8 +1290,8 @@ struct mip_filter_pressure_altitude_noise_command }; typedef struct mip_filter_pressure_altitude_noise_command mip_filter_pressure_altitude_noise_command; -void insert_mip_filter_pressure_altitude_noise_command(struct mip_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self); -void extract_mip_filter_pressure_altitude_noise_command(struct mip_serializer* serializer, mip_filter_pressure_altitude_noise_command* self); +void insert_mip_filter_pressure_altitude_noise_command(struct microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self); +void extract_mip_filter_pressure_altitude_noise_command(struct microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_command* self); struct mip_filter_pressure_altitude_noise_response { @@ -1299,8 +1299,8 @@ struct mip_filter_pressure_altitude_noise_response }; typedef struct mip_filter_pressure_altitude_noise_response mip_filter_pressure_altitude_noise_response; -void insert_mip_filter_pressure_altitude_noise_response(struct mip_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self); -void extract_mip_filter_pressure_altitude_noise_response(struct mip_serializer* serializer, mip_filter_pressure_altitude_noise_response* self); +void insert_mip_filter_pressure_altitude_noise_response(struct microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self); +void extract_mip_filter_pressure_altitude_noise_response(struct microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_response* self); mip_cmd_result mip_filter_write_pressure_altitude_noise(struct mip_interface* device, float noise); mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* device, float* noise_out); @@ -1330,8 +1330,8 @@ struct mip_filter_hard_iron_offset_noise_command }; typedef struct mip_filter_hard_iron_offset_noise_command mip_filter_hard_iron_offset_noise_command; -void insert_mip_filter_hard_iron_offset_noise_command(struct mip_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self); -void extract_mip_filter_hard_iron_offset_noise_command(struct mip_serializer* serializer, mip_filter_hard_iron_offset_noise_command* self); +void insert_mip_filter_hard_iron_offset_noise_command(struct microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self); +void extract_mip_filter_hard_iron_offset_noise_command(struct microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_command* self); struct mip_filter_hard_iron_offset_noise_response { @@ -1339,8 +1339,8 @@ struct mip_filter_hard_iron_offset_noise_response }; typedef struct mip_filter_hard_iron_offset_noise_response mip_filter_hard_iron_offset_noise_response; -void insert_mip_filter_hard_iron_offset_noise_response(struct mip_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self); -void extract_mip_filter_hard_iron_offset_noise_response(struct mip_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self); +void insert_mip_filter_hard_iron_offset_noise_response(struct microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self); +void extract_mip_filter_hard_iron_offset_noise_response(struct microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self); mip_cmd_result mip_filter_write_hard_iron_offset_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* device, float* noise_out); @@ -1369,8 +1369,8 @@ struct mip_filter_soft_iron_matrix_noise_command }; typedef struct mip_filter_soft_iron_matrix_noise_command mip_filter_soft_iron_matrix_noise_command; -void insert_mip_filter_soft_iron_matrix_noise_command(struct mip_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self); -void extract_mip_filter_soft_iron_matrix_noise_command(struct mip_serializer* serializer, mip_filter_soft_iron_matrix_noise_command* self); +void insert_mip_filter_soft_iron_matrix_noise_command(struct microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self); +void extract_mip_filter_soft_iron_matrix_noise_command(struct microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_command* self); struct mip_filter_soft_iron_matrix_noise_response { @@ -1378,8 +1378,8 @@ struct mip_filter_soft_iron_matrix_noise_response }; typedef struct mip_filter_soft_iron_matrix_noise_response mip_filter_soft_iron_matrix_noise_response; -void insert_mip_filter_soft_iron_matrix_noise_response(struct mip_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self); -void extract_mip_filter_soft_iron_matrix_noise_response(struct mip_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self); +void insert_mip_filter_soft_iron_matrix_noise_response(struct microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self); +void extract_mip_filter_soft_iron_matrix_noise_response(struct microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self); mip_cmd_result mip_filter_write_soft_iron_matrix_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* device, float* noise_out); @@ -1408,8 +1408,8 @@ struct mip_filter_mag_noise_command }; typedef struct mip_filter_mag_noise_command mip_filter_mag_noise_command; -void insert_mip_filter_mag_noise_command(struct mip_serializer* serializer, const mip_filter_mag_noise_command* self); -void extract_mip_filter_mag_noise_command(struct mip_serializer* serializer, mip_filter_mag_noise_command* self); +void insert_mip_filter_mag_noise_command(struct microstrain_serializer* serializer, const mip_filter_mag_noise_command* self); +void extract_mip_filter_mag_noise_command(struct microstrain_serializer* serializer, mip_filter_mag_noise_command* self); struct mip_filter_mag_noise_response { @@ -1417,8 +1417,8 @@ struct mip_filter_mag_noise_response }; typedef struct mip_filter_mag_noise_response mip_filter_mag_noise_response; -void insert_mip_filter_mag_noise_response(struct mip_serializer* serializer, const mip_filter_mag_noise_response* self); -void extract_mip_filter_mag_noise_response(struct mip_serializer* serializer, mip_filter_mag_noise_response* self); +void insert_mip_filter_mag_noise_response(struct microstrain_serializer* serializer, const mip_filter_mag_noise_response* self); +void extract_mip_filter_mag_noise_response(struct microstrain_serializer* serializer, mip_filter_mag_noise_response* self); mip_cmd_result mip_filter_write_mag_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* noise_out); @@ -1446,8 +1446,8 @@ struct mip_filter_inclination_source_command }; typedef struct mip_filter_inclination_source_command mip_filter_inclination_source_command; -void insert_mip_filter_inclination_source_command(struct mip_serializer* serializer, const mip_filter_inclination_source_command* self); -void extract_mip_filter_inclination_source_command(struct mip_serializer* serializer, mip_filter_inclination_source_command* self); +void insert_mip_filter_inclination_source_command(struct microstrain_serializer* serializer, const mip_filter_inclination_source_command* self); +void extract_mip_filter_inclination_source_command(struct microstrain_serializer* serializer, mip_filter_inclination_source_command* self); struct mip_filter_inclination_source_response { @@ -1456,8 +1456,8 @@ struct mip_filter_inclination_source_response }; typedef struct mip_filter_inclination_source_response mip_filter_inclination_source_response; -void insert_mip_filter_inclination_source_response(struct mip_serializer* serializer, const mip_filter_inclination_source_response* self); -void extract_mip_filter_inclination_source_response(struct mip_serializer* serializer, mip_filter_inclination_source_response* self); +void insert_mip_filter_inclination_source_response(struct microstrain_serializer* serializer, const mip_filter_inclination_source_response* self); +void extract_mip_filter_inclination_source_response(struct microstrain_serializer* serializer, mip_filter_inclination_source_response* self); mip_cmd_result mip_filter_write_inclination_source(struct mip_interface* device, mip_filter_mag_param_source source, float inclination); mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* inclination_out); @@ -1485,8 +1485,8 @@ struct mip_filter_magnetic_declination_source_command }; typedef struct mip_filter_magnetic_declination_source_command mip_filter_magnetic_declination_source_command; -void insert_mip_filter_magnetic_declination_source_command(struct mip_serializer* serializer, const mip_filter_magnetic_declination_source_command* self); -void extract_mip_filter_magnetic_declination_source_command(struct mip_serializer* serializer, mip_filter_magnetic_declination_source_command* self); +void insert_mip_filter_magnetic_declination_source_command(struct microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_command* self); +void extract_mip_filter_magnetic_declination_source_command(struct microstrain_serializer* serializer, mip_filter_magnetic_declination_source_command* self); struct mip_filter_magnetic_declination_source_response { @@ -1495,8 +1495,8 @@ struct mip_filter_magnetic_declination_source_response }; typedef struct mip_filter_magnetic_declination_source_response mip_filter_magnetic_declination_source_response; -void insert_mip_filter_magnetic_declination_source_response(struct mip_serializer* serializer, const mip_filter_magnetic_declination_source_response* self); -void extract_mip_filter_magnetic_declination_source_response(struct mip_serializer* serializer, mip_filter_magnetic_declination_source_response* self); +void insert_mip_filter_magnetic_declination_source_response(struct microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_response* self); +void extract_mip_filter_magnetic_declination_source_response(struct microstrain_serializer* serializer, mip_filter_magnetic_declination_source_response* self); mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source source, float declination); mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* declination_out); @@ -1523,8 +1523,8 @@ struct mip_filter_mag_field_magnitude_source_command }; typedef struct mip_filter_mag_field_magnitude_source_command mip_filter_mag_field_magnitude_source_command; -void insert_mip_filter_mag_field_magnitude_source_command(struct mip_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self); -void extract_mip_filter_mag_field_magnitude_source_command(struct mip_serializer* serializer, mip_filter_mag_field_magnitude_source_command* self); +void insert_mip_filter_mag_field_magnitude_source_command(struct microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self); +void extract_mip_filter_mag_field_magnitude_source_command(struct microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_command* self); struct mip_filter_mag_field_magnitude_source_response { @@ -1533,8 +1533,8 @@ struct mip_filter_mag_field_magnitude_source_response }; typedef struct mip_filter_mag_field_magnitude_source_response mip_filter_mag_field_magnitude_source_response; -void insert_mip_filter_mag_field_magnitude_source_response(struct mip_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self); -void extract_mip_filter_mag_field_magnitude_source_response(struct mip_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self); +void insert_mip_filter_mag_field_magnitude_source_response(struct microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self); +void extract_mip_filter_mag_field_magnitude_source_response(struct microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self); mip_cmd_result mip_filter_write_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source source, float magnitude); mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* magnitude_out); @@ -1563,8 +1563,8 @@ struct mip_filter_reference_position_command }; typedef struct mip_filter_reference_position_command mip_filter_reference_position_command; -void insert_mip_filter_reference_position_command(struct mip_serializer* serializer, const mip_filter_reference_position_command* self); -void extract_mip_filter_reference_position_command(struct mip_serializer* serializer, mip_filter_reference_position_command* self); +void insert_mip_filter_reference_position_command(struct microstrain_serializer* serializer, const mip_filter_reference_position_command* self); +void extract_mip_filter_reference_position_command(struct microstrain_serializer* serializer, mip_filter_reference_position_command* self); struct mip_filter_reference_position_response { @@ -1575,8 +1575,8 @@ struct mip_filter_reference_position_response }; typedef struct mip_filter_reference_position_response mip_filter_reference_position_response; -void insert_mip_filter_reference_position_response(struct mip_serializer* serializer, const mip_filter_reference_position_response* self); -void extract_mip_filter_reference_position_response(struct mip_serializer* serializer, mip_filter_reference_position_response* self); +void insert_mip_filter_reference_position_response(struct microstrain_serializer* serializer, const mip_filter_reference_position_response* self); +void extract_mip_filter_reference_position_response(struct microstrain_serializer* serializer, mip_filter_reference_position_response* self); mip_cmd_result mip_filter_write_reference_position(struct mip_interface* device, bool enable, double latitude, double longitude, double altitude); mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, bool* enable_out, double* latitude_out, double* longitude_out, double* altitude_out); @@ -1618,8 +1618,8 @@ struct mip_filter_accel_magnitude_error_adaptive_measurement_command }; typedef struct mip_filter_accel_magnitude_error_adaptive_measurement_command mip_filter_accel_magnitude_error_adaptive_measurement_command; -void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(struct mip_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self); -void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(struct mip_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_command* self); +void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(struct microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self); +void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(struct microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_command* self); struct mip_filter_accel_magnitude_error_adaptive_measurement_response { @@ -1633,8 +1633,8 @@ struct mip_filter_accel_magnitude_error_adaptive_measurement_response }; typedef struct mip_filter_accel_magnitude_error_adaptive_measurement_response mip_filter_accel_magnitude_error_adaptive_measurement_response; -void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(struct mip_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self); -void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(struct mip_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self); +void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(struct microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self); +void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(struct microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self); mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty); mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); @@ -1671,8 +1671,8 @@ struct mip_filter_mag_magnitude_error_adaptive_measurement_command }; typedef struct mip_filter_mag_magnitude_error_adaptive_measurement_command mip_filter_mag_magnitude_error_adaptive_measurement_command; -void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(struct mip_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self); -void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(struct mip_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_command* self); +void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(struct microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self); +void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(struct microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_command* self); struct mip_filter_mag_magnitude_error_adaptive_measurement_response { @@ -1686,8 +1686,8 @@ struct mip_filter_mag_magnitude_error_adaptive_measurement_response }; typedef struct mip_filter_mag_magnitude_error_adaptive_measurement_response mip_filter_mag_magnitude_error_adaptive_measurement_response; -void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(struct mip_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self); -void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(struct mip_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self); +void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(struct microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self); +void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(struct microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self); mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty); mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); @@ -1724,8 +1724,8 @@ struct mip_filter_mag_dip_angle_error_adaptive_measurement_command }; typedef struct mip_filter_mag_dip_angle_error_adaptive_measurement_command mip_filter_mag_dip_angle_error_adaptive_measurement_command; -void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(struct mip_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); -void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(struct mip_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); +void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(struct microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); +void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(struct microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); struct mip_filter_mag_dip_angle_error_adaptive_measurement_response { @@ -1737,8 +1737,8 @@ struct mip_filter_mag_dip_angle_error_adaptive_measurement_response }; typedef struct mip_filter_mag_dip_angle_error_adaptive_measurement_response mip_filter_mag_dip_angle_error_adaptive_measurement_response; -void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(struct mip_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); -void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(struct mip_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); +void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(struct microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); +void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(struct microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool enable, float frequency, float high_limit, float high_limit_uncertainty, float minimum_uncertainty); mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool* enable_out, float* frequency_out, float* high_limit_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); @@ -1776,11 +1776,11 @@ struct mip_filter_aiding_measurement_enable_command }; typedef struct mip_filter_aiding_measurement_enable_command mip_filter_aiding_measurement_enable_command; -void insert_mip_filter_aiding_measurement_enable_command(struct mip_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self); -void extract_mip_filter_aiding_measurement_enable_command(struct mip_serializer* serializer, mip_filter_aiding_measurement_enable_command* self); +void insert_mip_filter_aiding_measurement_enable_command(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self); +void extract_mip_filter_aiding_measurement_enable_command(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command* self); -void insert_mip_filter_aiding_measurement_enable_command_aiding_source(struct mip_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self); -void extract_mip_filter_aiding_measurement_enable_command_aiding_source(struct mip_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self); +void insert_mip_filter_aiding_measurement_enable_command_aiding_source(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self); +void extract_mip_filter_aiding_measurement_enable_command_aiding_source(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self); struct mip_filter_aiding_measurement_enable_response { @@ -1789,8 +1789,8 @@ struct mip_filter_aiding_measurement_enable_response }; typedef struct mip_filter_aiding_measurement_enable_response mip_filter_aiding_measurement_enable_response; -void insert_mip_filter_aiding_measurement_enable_response(struct mip_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self); -void extract_mip_filter_aiding_measurement_enable_response(struct mip_serializer* serializer, mip_filter_aiding_measurement_enable_response* self); +void insert_mip_filter_aiding_measurement_enable_response(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self); +void extract_mip_filter_aiding_measurement_enable_response(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_response* self); mip_cmd_result mip_filter_write_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool enable); mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool* enable_out); @@ -1829,8 +1829,8 @@ struct mip_filter_kinematic_constraint_command }; typedef struct mip_filter_kinematic_constraint_command mip_filter_kinematic_constraint_command; -void insert_mip_filter_kinematic_constraint_command(struct mip_serializer* serializer, const mip_filter_kinematic_constraint_command* self); -void extract_mip_filter_kinematic_constraint_command(struct mip_serializer* serializer, mip_filter_kinematic_constraint_command* self); +void insert_mip_filter_kinematic_constraint_command(struct microstrain_serializer* serializer, const mip_filter_kinematic_constraint_command* self); +void extract_mip_filter_kinematic_constraint_command(struct microstrain_serializer* serializer, mip_filter_kinematic_constraint_command* self); struct mip_filter_kinematic_constraint_response { @@ -1840,8 +1840,8 @@ struct mip_filter_kinematic_constraint_response }; typedef struct mip_filter_kinematic_constraint_response mip_filter_kinematic_constraint_response; -void insert_mip_filter_kinematic_constraint_response(struct mip_serializer* serializer, const mip_filter_kinematic_constraint_response* self); -void extract_mip_filter_kinematic_constraint_response(struct mip_serializer* serializer, mip_filter_kinematic_constraint_response* self); +void insert_mip_filter_kinematic_constraint_response(struct microstrain_serializer* serializer, const mip_filter_kinematic_constraint_response* self); +void extract_mip_filter_kinematic_constraint_response(struct microstrain_serializer* serializer, mip_filter_kinematic_constraint_response* self); mip_cmd_result mip_filter_write_kinematic_constraint(struct mip_interface* device, uint8_t acceleration_constraint_selection, uint8_t velocity_constraint_selection, uint8_t angular_constraint_selection); mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device, uint8_t* acceleration_constraint_selection_out, uint8_t* velocity_constraint_selection_out, uint8_t* angular_constraint_selection_out); @@ -1890,14 +1890,14 @@ struct mip_filter_initialization_configuration_command }; typedef struct mip_filter_initialization_configuration_command mip_filter_initialization_configuration_command; -void insert_mip_filter_initialization_configuration_command(struct mip_serializer* serializer, const mip_filter_initialization_configuration_command* self); -void extract_mip_filter_initialization_configuration_command(struct mip_serializer* serializer, mip_filter_initialization_configuration_command* self); +void insert_mip_filter_initialization_configuration_command(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command* self); +void extract_mip_filter_initialization_configuration_command(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command* self); -void insert_mip_filter_initialization_configuration_command_alignment_selector(struct mip_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self); -void extract_mip_filter_initialization_configuration_command_alignment_selector(struct mip_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self); +void insert_mip_filter_initialization_configuration_command_alignment_selector(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self); +void extract_mip_filter_initialization_configuration_command_alignment_selector(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self); -void insert_mip_filter_initialization_configuration_command_initial_condition_source(struct mip_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self); -void extract_mip_filter_initialization_configuration_command_initial_condition_source(struct mip_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self); +void insert_mip_filter_initialization_configuration_command_initial_condition_source(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self); +void extract_mip_filter_initialization_configuration_command_initial_condition_source(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self); struct mip_filter_initialization_configuration_response { @@ -1913,8 +1913,8 @@ struct mip_filter_initialization_configuration_response }; typedef struct mip_filter_initialization_configuration_response mip_filter_initialization_configuration_response; -void insert_mip_filter_initialization_configuration_response(struct mip_serializer* serializer, const mip_filter_initialization_configuration_response* self); -void extract_mip_filter_initialization_configuration_response(struct mip_serializer* serializer, mip_filter_initialization_configuration_response* self); +void insert_mip_filter_initialization_configuration_response(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_response* self); +void extract_mip_filter_initialization_configuration_response(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_response* self); mip_cmd_result mip_filter_write_initialization_configuration(struct mip_interface* device, uint8_t wait_for_run_command, mip_filter_initialization_configuration_command_initial_condition_source initial_cond_src, mip_filter_initialization_configuration_command_alignment_selector auto_heading_alignment_selector, float initial_heading, float initial_pitch, float initial_roll, const float* initial_position, const float* initial_velocity, mip_filter_reference_frame reference_frame_selector); mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface* device, uint8_t* wait_for_run_command_out, mip_filter_initialization_configuration_command_initial_condition_source* initial_cond_src_out, mip_filter_initialization_configuration_command_alignment_selector* auto_heading_alignment_selector_out, float* initial_heading_out, float* initial_pitch_out, float* initial_roll_out, float* initial_position_out, float* initial_velocity_out, mip_filter_reference_frame* reference_frame_selector_out); @@ -1938,8 +1938,8 @@ struct mip_filter_adaptive_filter_options_command }; typedef struct mip_filter_adaptive_filter_options_command mip_filter_adaptive_filter_options_command; -void insert_mip_filter_adaptive_filter_options_command(struct mip_serializer* serializer, const mip_filter_adaptive_filter_options_command* self); -void extract_mip_filter_adaptive_filter_options_command(struct mip_serializer* serializer, mip_filter_adaptive_filter_options_command* self); +void insert_mip_filter_adaptive_filter_options_command(struct microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_command* self); +void extract_mip_filter_adaptive_filter_options_command(struct microstrain_serializer* serializer, mip_filter_adaptive_filter_options_command* self); struct mip_filter_adaptive_filter_options_response { @@ -1948,8 +1948,8 @@ struct mip_filter_adaptive_filter_options_response }; typedef struct mip_filter_adaptive_filter_options_response mip_filter_adaptive_filter_options_response; -void insert_mip_filter_adaptive_filter_options_response(struct mip_serializer* serializer, const mip_filter_adaptive_filter_options_response* self); -void extract_mip_filter_adaptive_filter_options_response(struct mip_serializer* serializer, mip_filter_adaptive_filter_options_response* self); +void insert_mip_filter_adaptive_filter_options_response(struct microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_response* self); +void extract_mip_filter_adaptive_filter_options_response(struct microstrain_serializer* serializer, mip_filter_adaptive_filter_options_response* self); mip_cmd_result mip_filter_write_adaptive_filter_options(struct mip_interface* device, uint8_t level, uint16_t time_limit); mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* device, uint8_t* level_out, uint16_t* time_limit_out); @@ -1976,8 +1976,8 @@ struct mip_filter_multi_antenna_offset_command }; typedef struct mip_filter_multi_antenna_offset_command mip_filter_multi_antenna_offset_command; -void insert_mip_filter_multi_antenna_offset_command(struct mip_serializer* serializer, const mip_filter_multi_antenna_offset_command* self); -void extract_mip_filter_multi_antenna_offset_command(struct mip_serializer* serializer, mip_filter_multi_antenna_offset_command* self); +void insert_mip_filter_multi_antenna_offset_command(struct microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_command* self); +void extract_mip_filter_multi_antenna_offset_command(struct microstrain_serializer* serializer, mip_filter_multi_antenna_offset_command* self); struct mip_filter_multi_antenna_offset_response { @@ -1986,8 +1986,8 @@ struct mip_filter_multi_antenna_offset_response }; typedef struct mip_filter_multi_antenna_offset_response mip_filter_multi_antenna_offset_response; -void insert_mip_filter_multi_antenna_offset_response(struct mip_serializer* serializer, const mip_filter_multi_antenna_offset_response* self); -void extract_mip_filter_multi_antenna_offset_response(struct mip_serializer* serializer, mip_filter_multi_antenna_offset_response* self); +void insert_mip_filter_multi_antenna_offset_response(struct microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_response* self); +void extract_mip_filter_multi_antenna_offset_response(struct microstrain_serializer* serializer, mip_filter_multi_antenna_offset_response* self); mip_cmd_result mip_filter_write_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, const float* antenna_offset); mip_cmd_result mip_filter_read_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, float* antenna_offset_out); @@ -2012,8 +2012,8 @@ struct mip_filter_rel_pos_configuration_command }; typedef struct mip_filter_rel_pos_configuration_command mip_filter_rel_pos_configuration_command; -void insert_mip_filter_rel_pos_configuration_command(struct mip_serializer* serializer, const mip_filter_rel_pos_configuration_command* self); -void extract_mip_filter_rel_pos_configuration_command(struct mip_serializer* serializer, mip_filter_rel_pos_configuration_command* self); +void insert_mip_filter_rel_pos_configuration_command(struct microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_command* self); +void extract_mip_filter_rel_pos_configuration_command(struct microstrain_serializer* serializer, mip_filter_rel_pos_configuration_command* self); struct mip_filter_rel_pos_configuration_response { @@ -2023,8 +2023,8 @@ struct mip_filter_rel_pos_configuration_response }; typedef struct mip_filter_rel_pos_configuration_response mip_filter_rel_pos_configuration_response; -void insert_mip_filter_rel_pos_configuration_response(struct mip_serializer* serializer, const mip_filter_rel_pos_configuration_response* self); -void extract_mip_filter_rel_pos_configuration_response(struct mip_serializer* serializer, mip_filter_rel_pos_configuration_response* self); +void insert_mip_filter_rel_pos_configuration_response(struct microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_response* self); +void extract_mip_filter_rel_pos_configuration_response(struct microstrain_serializer* serializer, mip_filter_rel_pos_configuration_response* self); mip_cmd_result mip_filter_write_rel_pos_configuration(struct mip_interface* device, uint8_t source, mip_filter_reference_frame reference_frame_selector, const double* reference_coordinates); mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* device, uint8_t* source_out, mip_filter_reference_frame* reference_frame_selector_out, double* reference_coordinates_out); @@ -2058,11 +2058,11 @@ struct mip_filter_ref_point_lever_arm_command }; typedef struct mip_filter_ref_point_lever_arm_command mip_filter_ref_point_lever_arm_command; -void insert_mip_filter_ref_point_lever_arm_command(struct mip_serializer* serializer, const mip_filter_ref_point_lever_arm_command* self); -void extract_mip_filter_ref_point_lever_arm_command(struct mip_serializer* serializer, mip_filter_ref_point_lever_arm_command* self); +void insert_mip_filter_ref_point_lever_arm_command(struct microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command* self); +void extract_mip_filter_ref_point_lever_arm_command(struct microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command* self); -void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct mip_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self); -void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct mip_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self); +void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self); +void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self); struct mip_filter_ref_point_lever_arm_response { @@ -2071,8 +2071,8 @@ struct mip_filter_ref_point_lever_arm_response }; typedef struct mip_filter_ref_point_lever_arm_response mip_filter_ref_point_lever_arm_response; -void insert_mip_filter_ref_point_lever_arm_response(struct mip_serializer* serializer, const mip_filter_ref_point_lever_arm_response* self); -void extract_mip_filter_ref_point_lever_arm_response(struct mip_serializer* serializer, mip_filter_ref_point_lever_arm_response* self); +void insert_mip_filter_ref_point_lever_arm_response(struct microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_response* self); +void extract_mip_filter_ref_point_lever_arm_response(struct microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_response* self); mip_cmd_result mip_filter_write_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel, const float* lever_arm_offset); mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector* ref_point_sel_out, float* lever_arm_offset_out); @@ -2099,8 +2099,8 @@ struct mip_filter_speed_measurement_command }; typedef struct mip_filter_speed_measurement_command mip_filter_speed_measurement_command; -void insert_mip_filter_speed_measurement_command(struct mip_serializer* serializer, const mip_filter_speed_measurement_command* self); -void extract_mip_filter_speed_measurement_command(struct mip_serializer* serializer, mip_filter_speed_measurement_command* self); +void insert_mip_filter_speed_measurement_command(struct microstrain_serializer* serializer, const mip_filter_speed_measurement_command* self); +void extract_mip_filter_speed_measurement_command(struct microstrain_serializer* serializer, mip_filter_speed_measurement_command* self); mip_cmd_result mip_filter_speed_measurement(struct mip_interface* device, uint8_t source, float time_of_week, float speed, float speed_uncertainty); @@ -2126,8 +2126,8 @@ struct mip_filter_speed_lever_arm_command }; typedef struct mip_filter_speed_lever_arm_command mip_filter_speed_lever_arm_command; -void insert_mip_filter_speed_lever_arm_command(struct mip_serializer* serializer, const mip_filter_speed_lever_arm_command* self); -void extract_mip_filter_speed_lever_arm_command(struct mip_serializer* serializer, mip_filter_speed_lever_arm_command* self); +void insert_mip_filter_speed_lever_arm_command(struct microstrain_serializer* serializer, const mip_filter_speed_lever_arm_command* self); +void extract_mip_filter_speed_lever_arm_command(struct microstrain_serializer* serializer, mip_filter_speed_lever_arm_command* self); struct mip_filter_speed_lever_arm_response { @@ -2136,8 +2136,8 @@ struct mip_filter_speed_lever_arm_response }; typedef struct mip_filter_speed_lever_arm_response mip_filter_speed_lever_arm_response; -void insert_mip_filter_speed_lever_arm_response(struct mip_serializer* serializer, const mip_filter_speed_lever_arm_response* self); -void extract_mip_filter_speed_lever_arm_response(struct mip_serializer* serializer, mip_filter_speed_lever_arm_response* self); +void insert_mip_filter_speed_lever_arm_response(struct microstrain_serializer* serializer, const mip_filter_speed_lever_arm_response* self); +void extract_mip_filter_speed_lever_arm_response(struct microstrain_serializer* serializer, mip_filter_speed_lever_arm_response* self); mip_cmd_result mip_filter_write_speed_lever_arm(struct mip_interface* device, uint8_t source, const float* lever_arm_offset); mip_cmd_result mip_filter_read_speed_lever_arm(struct mip_interface* device, uint8_t source, float* lever_arm_offset_out); @@ -2166,8 +2166,8 @@ struct mip_filter_wheeled_vehicle_constraint_control_command }; typedef struct mip_filter_wheeled_vehicle_constraint_control_command mip_filter_wheeled_vehicle_constraint_control_command; -void insert_mip_filter_wheeled_vehicle_constraint_control_command(struct mip_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_command* self); -void extract_mip_filter_wheeled_vehicle_constraint_control_command(struct mip_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_command* self); +void insert_mip_filter_wheeled_vehicle_constraint_control_command(struct microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_command* self); +void extract_mip_filter_wheeled_vehicle_constraint_control_command(struct microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_command* self); struct mip_filter_wheeled_vehicle_constraint_control_response { @@ -2175,8 +2175,8 @@ struct mip_filter_wheeled_vehicle_constraint_control_response }; typedef struct mip_filter_wheeled_vehicle_constraint_control_response mip_filter_wheeled_vehicle_constraint_control_response; -void insert_mip_filter_wheeled_vehicle_constraint_control_response(struct mip_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self); -void extract_mip_filter_wheeled_vehicle_constraint_control_response(struct mip_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self); +void insert_mip_filter_wheeled_vehicle_constraint_control_response(struct microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self); +void extract_mip_filter_wheeled_vehicle_constraint_control_response(struct microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self); mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t enable); mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t* enable_out); @@ -2203,8 +2203,8 @@ struct mip_filter_vertical_gyro_constraint_control_command }; typedef struct mip_filter_vertical_gyro_constraint_control_command mip_filter_vertical_gyro_constraint_control_command; -void insert_mip_filter_vertical_gyro_constraint_control_command(struct mip_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_command* self); -void extract_mip_filter_vertical_gyro_constraint_control_command(struct mip_serializer* serializer, mip_filter_vertical_gyro_constraint_control_command* self); +void insert_mip_filter_vertical_gyro_constraint_control_command(struct microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_command* self); +void extract_mip_filter_vertical_gyro_constraint_control_command(struct microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_command* self); struct mip_filter_vertical_gyro_constraint_control_response { @@ -2212,8 +2212,8 @@ struct mip_filter_vertical_gyro_constraint_control_response }; typedef struct mip_filter_vertical_gyro_constraint_control_response mip_filter_vertical_gyro_constraint_control_response; -void insert_mip_filter_vertical_gyro_constraint_control_response(struct mip_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self); -void extract_mip_filter_vertical_gyro_constraint_control_response(struct mip_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self); +void insert_mip_filter_vertical_gyro_constraint_control_response(struct microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self); +void extract_mip_filter_vertical_gyro_constraint_control_response(struct microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self); mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t enable); mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t* enable_out); @@ -2239,8 +2239,8 @@ struct mip_filter_gnss_antenna_cal_control_command }; typedef struct mip_filter_gnss_antenna_cal_control_command mip_filter_gnss_antenna_cal_control_command; -void insert_mip_filter_gnss_antenna_cal_control_command(struct mip_serializer* serializer, const mip_filter_gnss_antenna_cal_control_command* self); -void extract_mip_filter_gnss_antenna_cal_control_command(struct mip_serializer* serializer, mip_filter_gnss_antenna_cal_control_command* self); +void insert_mip_filter_gnss_antenna_cal_control_command(struct microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_command* self); +void extract_mip_filter_gnss_antenna_cal_control_command(struct microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_command* self); struct mip_filter_gnss_antenna_cal_control_response { @@ -2249,8 +2249,8 @@ struct mip_filter_gnss_antenna_cal_control_response }; typedef struct mip_filter_gnss_antenna_cal_control_response mip_filter_gnss_antenna_cal_control_response; -void insert_mip_filter_gnss_antenna_cal_control_response(struct mip_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self); -void extract_mip_filter_gnss_antenna_cal_control_response(struct mip_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self); +void insert_mip_filter_gnss_antenna_cal_control_response(struct microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self); +void extract_mip_filter_gnss_antenna_cal_control_response(struct microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self); mip_cmd_result mip_filter_write_gnss_antenna_cal_control(struct mip_interface* device, uint8_t enable, float max_offset); mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* device, uint8_t* enable_out, float* max_offset_out); @@ -2275,8 +2275,8 @@ struct mip_filter_set_initial_heading_command }; typedef struct mip_filter_set_initial_heading_command mip_filter_set_initial_heading_command; -void insert_mip_filter_set_initial_heading_command(struct mip_serializer* serializer, const mip_filter_set_initial_heading_command* self); -void extract_mip_filter_set_initial_heading_command(struct mip_serializer* serializer, mip_filter_set_initial_heading_command* self); +void insert_mip_filter_set_initial_heading_command(struct microstrain_serializer* serializer, const mip_filter_set_initial_heading_command* self); +void extract_mip_filter_set_initial_heading_command(struct microstrain_serializer* serializer, mip_filter_set_initial_heading_command* self); mip_cmd_result mip_filter_set_initial_heading(struct mip_interface* device, float heading); diff --git a/src/mip/definitions/commands_gnss.c b/src/mip/definitions/commands_gnss.c index 179c66f9b..fe574356f 100644 --- a/src/mip/definitions/commands_gnss.c +++ b/src/mip/definitions/commands_gnss.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -27,7 +27,7 @@ struct mip_field; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_gnss_receiver_info_command_info(mip_serializer* serializer, const mip_gnss_receiver_info_command_info* self) +void insert_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, const mip_gnss_receiver_info_command_info* self) { microstrain_insert_u8(serializer, self->receiver_id); @@ -37,7 +37,7 @@ void insert_mip_gnss_receiver_info_command_info(mip_serializer* serializer, cons microstrain_insert_char(serializer, self->description[i]); } -void extract_mip_gnss_receiver_info_command_info(mip_serializer* serializer, mip_gnss_receiver_info_command_info* self) +void extract_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, mip_gnss_receiver_info_command_info* self) { microstrain_extract_u8(serializer, &self->receiver_id); @@ -57,8 +57,8 @@ mip_cmd_result mip_gnss_receiver_info(struct mip_interface* device, uint8_t* num if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(num_receivers_out); microstrain_extract_count(&deserializer, num_receivers_out, num_receivers_out_max); @@ -72,7 +72,7 @@ mip_cmd_result mip_gnss_receiver_info(struct mip_interface* device, uint8_t* num } return result; } -void insert_mip_gnss_signal_configuration_command(mip_serializer* serializer, const mip_gnss_signal_configuration_command* self) +void insert_mip_gnss_signal_configuration_command(microstrain_serializer* serializer, const mip_gnss_signal_configuration_command* self) { insert_mip_function_selector(serializer, self->function); @@ -91,7 +91,7 @@ void insert_mip_gnss_signal_configuration_command(mip_serializer* serializer, co } } -void extract_mip_gnss_signal_configuration_command(mip_serializer* serializer, mip_gnss_signal_configuration_command* self) +void extract_mip_gnss_signal_configuration_command(microstrain_serializer* serializer, mip_gnss_signal_configuration_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -111,7 +111,7 @@ void extract_mip_gnss_signal_configuration_command(mip_serializer* serializer, m } } -void insert_mip_gnss_signal_configuration_response(mip_serializer* serializer, const mip_gnss_signal_configuration_response* self) +void insert_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, const mip_gnss_signal_configuration_response* self) { microstrain_insert_u8(serializer, self->gps_enable); @@ -125,7 +125,7 @@ void insert_mip_gnss_signal_configuration_response(mip_serializer* serializer, c microstrain_insert_u8(serializer, self->reserved[i]); } -void extract_mip_gnss_signal_configuration_response(mip_serializer* serializer, mip_gnss_signal_configuration_response* self) +void extract_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, mip_gnss_signal_configuration_response* self) { microstrain_extract_u8(serializer, &self->gps_enable); @@ -142,9 +142,9 @@ void extract_mip_gnss_signal_configuration_response(mip_serializer* serializer, mip_cmd_result mip_gnss_write_signal_configuration(struct mip_interface* device, uint8_t gps_enable, uint8_t glonass_enable, uint8_t galileo_enable, uint8_t beidou_enable, const uint8_t* reserved) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -167,9 +167,9 @@ mip_cmd_result mip_gnss_write_signal_configuration(struct mip_interface* device, } mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, uint8_t* gps_enable_out, uint8_t* glonass_enable_out, uint8_t* galileo_enable_out, uint8_t* beidou_enable_out, uint8_t* reserved_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -181,8 +181,8 @@ mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(gps_enable_out); microstrain_extract_u8(&deserializer, gps_enable_out); @@ -207,9 +207,9 @@ mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, } mip_cmd_result mip_gnss_save_signal_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -220,9 +220,9 @@ mip_cmd_result mip_gnss_save_signal_configuration(struct mip_interface* device) } mip_cmd_result mip_gnss_load_signal_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -233,9 +233,9 @@ mip_cmd_result mip_gnss_load_signal_configuration(struct mip_interface* device) } mip_cmd_result mip_gnss_default_signal_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -244,7 +244,7 @@ mip_cmd_result mip_gnss_default_signal_configuration(struct mip_interface* devic return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_gnss_rtk_dongle_configuration_command(mip_serializer* serializer, const mip_gnss_rtk_dongle_configuration_command* self) +void insert_mip_gnss_rtk_dongle_configuration_command(microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_command* self) { insert_mip_function_selector(serializer, self->function); @@ -257,7 +257,7 @@ void insert_mip_gnss_rtk_dongle_configuration_command(mip_serializer* serializer } } -void extract_mip_gnss_rtk_dongle_configuration_command(mip_serializer* serializer, mip_gnss_rtk_dongle_configuration_command* self) +void extract_mip_gnss_rtk_dongle_configuration_command(microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -271,7 +271,7 @@ void extract_mip_gnss_rtk_dongle_configuration_command(mip_serializer* serialize } } -void insert_mip_gnss_rtk_dongle_configuration_response(mip_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self) +void insert_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self) { microstrain_insert_u8(serializer, self->enable); @@ -279,7 +279,7 @@ void insert_mip_gnss_rtk_dongle_configuration_response(mip_serializer* serialize microstrain_insert_u8(serializer, self->reserved[i]); } -void extract_mip_gnss_rtk_dongle_configuration_response(mip_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self) +void extract_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self) { microstrain_extract_u8(serializer, &self->enable); @@ -290,9 +290,9 @@ void extract_mip_gnss_rtk_dongle_configuration_response(mip_serializer* serializ mip_cmd_result mip_gnss_write_rtk_dongle_configuration(struct mip_interface* device, uint8_t enable, const uint8_t* reserved) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -309,9 +309,9 @@ mip_cmd_result mip_gnss_write_rtk_dongle_configuration(struct mip_interface* dev } mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* device, uint8_t* enable_out, uint8_t* reserved_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -323,8 +323,8 @@ mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* devi if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); @@ -340,9 +340,9 @@ mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* devi } mip_cmd_result mip_gnss_save_rtk_dongle_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -353,9 +353,9 @@ mip_cmd_result mip_gnss_save_rtk_dongle_configuration(struct mip_interface* devi } mip_cmd_result mip_gnss_load_rtk_dongle_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -366,9 +366,9 @@ mip_cmd_result mip_gnss_load_rtk_dongle_configuration(struct mip_interface* devi } mip_cmd_result mip_gnss_default_rtk_dongle_configuration(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); diff --git a/src/mip/definitions/commands_gnss.cpp b/src/mip/definitions/commands_gnss.cpp index 4873acc0c..c0f6b434f 100644 --- a/src/mip/definitions/commands_gnss.cpp +++ b/src/mip/definitions/commands_gnss.cpp @@ -186,7 +186,7 @@ TypedResult writeSignalConfiguration(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut) { @@ -197,7 +197,7 @@ TypedResult readSignalConfiguration(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SIGNAL_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SIGNAL_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -232,7 +232,7 @@ TypedResult saveSignalConfiguration(C::mip_interface& devic insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadSignalConfiguration(C::mip_interface& device) { @@ -242,7 +242,7 @@ TypedResult loadSignalConfiguration(C::mip_interface& devic insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultSignalConfiguration(C::mip_interface& device) { @@ -252,7 +252,7 @@ TypedResult defaultSignalConfiguration(C::mip_interface& de insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const RtkDongleConfiguration& self) { @@ -312,7 +312,7 @@ TypedResult writeRtkDongleConfiguration(C::mip_interface assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut) { @@ -323,7 +323,7 @@ TypedResult readRtkDongleConfiguration(C::mip_interface& assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -349,7 +349,7 @@ TypedResult saveRtkDongleConfiguration(C::mip_interface& insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadRtkDongleConfiguration(C::mip_interface& device) { @@ -359,7 +359,7 @@ TypedResult loadRtkDongleConfiguration(C::mip_interface& insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultRtkDongleConfiguration(C::mip_interface& device) { @@ -369,7 +369,7 @@ TypedResult defaultRtkDongleConfiguration(C::mip_interfa insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } } // namespace commands_gnss diff --git a/src/mip/definitions/commands_gnss.h b/src/mip/definitions/commands_gnss.h index 2f024f2cc..401382890 100644 --- a/src/mip/definitions/commands_gnss.h +++ b/src/mip/definitions/commands_gnss.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -74,8 +74,8 @@ struct mip_gnss_receiver_info_command_info }; typedef struct mip_gnss_receiver_info_command_info mip_gnss_receiver_info_command_info; -void insert_mip_gnss_receiver_info_command_info(struct mip_serializer* serializer, const mip_gnss_receiver_info_command_info* self); -void extract_mip_gnss_receiver_info_command_info(struct mip_serializer* serializer, mip_gnss_receiver_info_command_info* self); +void insert_mip_gnss_receiver_info_command_info(struct microstrain_serializer* serializer, const mip_gnss_receiver_info_command_info* self); +void extract_mip_gnss_receiver_info_command_info(struct microstrain_serializer* serializer, mip_gnss_receiver_info_command_info* self); struct mip_gnss_receiver_info_response { @@ -84,8 +84,8 @@ struct mip_gnss_receiver_info_response }; typedef struct mip_gnss_receiver_info_response mip_gnss_receiver_info_response; -void insert_mip_gnss_receiver_info_response(struct mip_serializer* serializer, const mip_gnss_receiver_info_response* self); -void extract_mip_gnss_receiver_info_response(struct mip_serializer* serializer, mip_gnss_receiver_info_response* self); +void insert_mip_gnss_receiver_info_response(struct microstrain_serializer* serializer, const mip_gnss_receiver_info_response* self); +void extract_mip_gnss_receiver_info_response(struct microstrain_serializer* serializer, mip_gnss_receiver_info_response* self); mip_cmd_result mip_gnss_receiver_info(struct mip_interface* device, uint8_t* num_receivers_out, uint8_t num_receivers_out_max, mip_gnss_receiver_info_command_info* receiver_info_out); @@ -109,8 +109,8 @@ struct mip_gnss_signal_configuration_command }; typedef struct mip_gnss_signal_configuration_command mip_gnss_signal_configuration_command; -void insert_mip_gnss_signal_configuration_command(struct mip_serializer* serializer, const mip_gnss_signal_configuration_command* self); -void extract_mip_gnss_signal_configuration_command(struct mip_serializer* serializer, mip_gnss_signal_configuration_command* self); +void insert_mip_gnss_signal_configuration_command(struct microstrain_serializer* serializer, const mip_gnss_signal_configuration_command* self); +void extract_mip_gnss_signal_configuration_command(struct microstrain_serializer* serializer, mip_gnss_signal_configuration_command* self); struct mip_gnss_signal_configuration_response { @@ -122,8 +122,8 @@ struct mip_gnss_signal_configuration_response }; typedef struct mip_gnss_signal_configuration_response mip_gnss_signal_configuration_response; -void insert_mip_gnss_signal_configuration_response(struct mip_serializer* serializer, const mip_gnss_signal_configuration_response* self); -void extract_mip_gnss_signal_configuration_response(struct mip_serializer* serializer, mip_gnss_signal_configuration_response* self); +void insert_mip_gnss_signal_configuration_response(struct microstrain_serializer* serializer, const mip_gnss_signal_configuration_response* self); +void extract_mip_gnss_signal_configuration_response(struct microstrain_serializer* serializer, mip_gnss_signal_configuration_response* self); mip_cmd_result mip_gnss_write_signal_configuration(struct mip_interface* device, uint8_t gps_enable, uint8_t glonass_enable, uint8_t galileo_enable, uint8_t beidou_enable, const uint8_t* reserved); mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, uint8_t* gps_enable_out, uint8_t* glonass_enable_out, uint8_t* galileo_enable_out, uint8_t* beidou_enable_out, uint8_t* reserved_out); @@ -148,8 +148,8 @@ struct mip_gnss_rtk_dongle_configuration_command }; typedef struct mip_gnss_rtk_dongle_configuration_command mip_gnss_rtk_dongle_configuration_command; -void insert_mip_gnss_rtk_dongle_configuration_command(struct mip_serializer* serializer, const mip_gnss_rtk_dongle_configuration_command* self); -void extract_mip_gnss_rtk_dongle_configuration_command(struct mip_serializer* serializer, mip_gnss_rtk_dongle_configuration_command* self); +void insert_mip_gnss_rtk_dongle_configuration_command(struct microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_command* self); +void extract_mip_gnss_rtk_dongle_configuration_command(struct microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_command* self); struct mip_gnss_rtk_dongle_configuration_response { @@ -158,8 +158,8 @@ struct mip_gnss_rtk_dongle_configuration_response }; typedef struct mip_gnss_rtk_dongle_configuration_response mip_gnss_rtk_dongle_configuration_response; -void insert_mip_gnss_rtk_dongle_configuration_response(struct mip_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self); -void extract_mip_gnss_rtk_dongle_configuration_response(struct mip_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self); +void insert_mip_gnss_rtk_dongle_configuration_response(struct microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self); +void extract_mip_gnss_rtk_dongle_configuration_response(struct microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self); mip_cmd_result mip_gnss_write_rtk_dongle_configuration(struct mip_interface* device, uint8_t enable, const uint8_t* reserved); mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* device, uint8_t* enable_out, uint8_t* reserved_out); diff --git a/src/mip/definitions/commands_rtk.c b/src/mip/definitions/commands_rtk.c index e77d060f1..335ecd7f3 100644 --- a/src/mip/definitions/commands_rtk.c +++ b/src/mip/definitions/commands_rtk.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -22,22 +22,22 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_media_selector(struct mip_serializer* serializer, const mip_media_selector self) +void insert_mip_media_selector(struct microstrain_serializer* serializer, const mip_media_selector self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_media_selector(struct mip_serializer* serializer, mip_media_selector* self) +void extract_mip_media_selector(struct microstrain_serializer* serializer, mip_media_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_led_action(struct mip_serializer* serializer, const mip_led_action self) +void insert_mip_led_action(struct microstrain_serializer* serializer, const mip_led_action self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_led_action(struct mip_serializer* serializer, mip_led_action* self) +void extract_mip_led_action(struct microstrain_serializer* serializer, mip_led_action* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -49,22 +49,22 @@ void extract_mip_led_action(struct mip_serializer* serializer, mip_led_action* s // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_rtk_get_status_flags_command_status_flags_legacy(struct mip_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self) +void insert_mip_rtk_get_status_flags_command_status_flags_legacy(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self) { microstrain_insert_u32(serializer, (uint32_t) (self)); } -void extract_mip_rtk_get_status_flags_command_status_flags_legacy(struct mip_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self) +void extract_mip_rtk_get_status_flags_command_status_flags_legacy(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self) { uint32_t tmp = 0; microstrain_extract_u32(serializer, &tmp); *self = tmp; } -void insert_mip_rtk_get_status_flags_command_status_flags(struct mip_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self) +void insert_mip_rtk_get_status_flags_command_status_flags(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self) { microstrain_insert_u32(serializer, (uint32_t) (self)); } -void extract_mip_rtk_get_status_flags_command_status_flags(struct mip_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self) +void extract_mip_rtk_get_status_flags_command_status_flags(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self) { uint32_t tmp = 0; microstrain_extract_u32(serializer, &tmp); @@ -80,8 +80,8 @@ mip_cmd_result mip_rtk_get_status_flags(struct mip_interface* device, mip_rtk_ge if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(flags_out); extract_mip_rtk_get_status_flags_command_status_flags(&deserializer, flags_out); @@ -100,8 +100,8 @@ mip_cmd_result mip_rtk_get_imei(struct mip_interface* device, char* imei_out) if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(imei_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -121,8 +121,8 @@ mip_cmd_result mip_rtk_get_imsi(struct mip_interface* device, char* imsi_out) if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(imsi_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -142,8 +142,8 @@ mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out) if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(iccid_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -154,7 +154,7 @@ mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out) } return result; } -void insert_mip_rtk_connected_device_type_command(mip_serializer* serializer, const mip_rtk_connected_device_type_command* self) +void insert_mip_rtk_connected_device_type_command(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command* self) { insert_mip_function_selector(serializer, self->function); @@ -164,7 +164,7 @@ void insert_mip_rtk_connected_device_type_command(mip_serializer* serializer, co } } -void extract_mip_rtk_connected_device_type_command(mip_serializer* serializer, mip_rtk_connected_device_type_command* self) +void extract_mip_rtk_connected_device_type_command(microstrain_serializer* serializer, mip_rtk_connected_device_type_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -175,22 +175,22 @@ void extract_mip_rtk_connected_device_type_command(mip_serializer* serializer, m } } -void insert_mip_rtk_connected_device_type_response(mip_serializer* serializer, const mip_rtk_connected_device_type_response* self) +void insert_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, const mip_rtk_connected_device_type_response* self) { insert_mip_rtk_connected_device_type_command_type(serializer, self->devType); } -void extract_mip_rtk_connected_device_type_response(mip_serializer* serializer, mip_rtk_connected_device_type_response* self) +void extract_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, mip_rtk_connected_device_type_response* self) { extract_mip_rtk_connected_device_type_command_type(serializer, &self->devType); } -void insert_mip_rtk_connected_device_type_command_type(struct mip_serializer* serializer, const mip_rtk_connected_device_type_command_type self) +void insert_mip_rtk_connected_device_type_command_type(struct microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_rtk_connected_device_type_command_type(struct mip_serializer* serializer, mip_rtk_connected_device_type_command_type* self) +void extract_mip_rtk_connected_device_type_command_type(struct microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -199,9 +199,9 @@ void extract_mip_rtk_connected_device_type_command_type(struct mip_serializer* s mip_cmd_result mip_rtk_write_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type dev_type) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -214,9 +214,9 @@ mip_cmd_result mip_rtk_write_connected_device_type(struct mip_interface* device, } mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type* dev_type_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -228,8 +228,8 @@ mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(dev_type_out); extract_mip_rtk_connected_device_type_command_type(&deserializer, dev_type_out); @@ -241,9 +241,9 @@ mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, } mip_cmd_result mip_rtk_save_connected_device_type(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); @@ -254,9 +254,9 @@ mip_cmd_result mip_rtk_save_connected_device_type(struct mip_interface* device) } mip_cmd_result mip_rtk_load_connected_device_type(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); @@ -267,9 +267,9 @@ mip_cmd_result mip_rtk_load_connected_device_type(struct mip_interface* device) } mip_cmd_result mip_rtk_default_connected_device_type(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); @@ -287,8 +287,8 @@ mip_cmd_result mip_rtk_get_act_code(struct mip_interface* device, char* activati if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(activation_code_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -308,8 +308,8 @@ mip_cmd_result mip_rtk_get_modem_firmware_version(struct mip_interface* device, if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(modem_firmware_version_out || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -329,8 +329,8 @@ mip_cmd_result mip_rtk_get_rssi(struct mip_interface* device, bool* valid_out, i if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(valid_out); microstrain_extract_bool(&deserializer, valid_out); @@ -346,14 +346,14 @@ mip_cmd_result mip_rtk_get_rssi(struct mip_interface* device, bool* valid_out, i } return result; } -void insert_mip_rtk_service_status_command(mip_serializer* serializer, const mip_rtk_service_status_command* self) +void insert_mip_rtk_service_status_command(microstrain_serializer* serializer, const mip_rtk_service_status_command* self) { microstrain_insert_u32(serializer, self->reserved1); microstrain_insert_u32(serializer, self->reserved2); } -void extract_mip_rtk_service_status_command(mip_serializer* serializer, mip_rtk_service_status_command* self) +void extract_mip_rtk_service_status_command(microstrain_serializer* serializer, mip_rtk_service_status_command* self) { microstrain_extract_u32(serializer, &self->reserved1); @@ -361,7 +361,7 @@ void extract_mip_rtk_service_status_command(mip_serializer* serializer, mip_rtk_ } -void insert_mip_rtk_service_status_response(mip_serializer* serializer, const mip_rtk_service_status_response* self) +void insert_mip_rtk_service_status_response(microstrain_serializer* serializer, const mip_rtk_service_status_response* self) { insert_mip_rtk_service_status_command_service_flags(serializer, self->flags); @@ -372,7 +372,7 @@ void insert_mip_rtk_service_status_response(mip_serializer* serializer, const mi microstrain_insert_u64(serializer, self->lastBytesTime); } -void extract_mip_rtk_service_status_response(mip_serializer* serializer, mip_rtk_service_status_response* self) +void extract_mip_rtk_service_status_response(microstrain_serializer* serializer, mip_rtk_service_status_response* self) { extract_mip_rtk_service_status_command_service_flags(serializer, &self->flags); @@ -384,11 +384,11 @@ void extract_mip_rtk_service_status_response(mip_serializer* serializer, mip_rtk } -void insert_mip_rtk_service_status_command_service_flags(struct mip_serializer* serializer, const mip_rtk_service_status_command_service_flags self) +void insert_mip_rtk_service_status_command_service_flags(struct microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_rtk_service_status_command_service_flags(struct mip_serializer* serializer, mip_rtk_service_status_command_service_flags* self) +void extract_mip_rtk_service_status_command_service_flags(struct microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -397,9 +397,9 @@ void extract_mip_rtk_service_status_command_service_flags(struct mip_serializer* mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t reserved1, uint32_t reserved2, mip_rtk_service_status_command_service_flags* flags_out, uint32_t* received_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); microstrain_insert_u32(&serializer, reserved1); @@ -413,8 +413,8 @@ mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t res if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(flags_out); extract_mip_rtk_service_status_command_service_flags(&deserializer, flags_out); @@ -433,12 +433,12 @@ mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t res } return result; } -void insert_mip_rtk_prod_erase_storage_command(mip_serializer* serializer, const mip_rtk_prod_erase_storage_command* self) +void insert_mip_rtk_prod_erase_storage_command(microstrain_serializer* serializer, const mip_rtk_prod_erase_storage_command* self) { insert_mip_media_selector(serializer, self->media); } -void extract_mip_rtk_prod_erase_storage_command(mip_serializer* serializer, mip_rtk_prod_erase_storage_command* self) +void extract_mip_rtk_prod_erase_storage_command(microstrain_serializer* serializer, mip_rtk_prod_erase_storage_command* self) { extract_mip_media_selector(serializer, &self->media); @@ -446,9 +446,9 @@ void extract_mip_rtk_prod_erase_storage_command(mip_serializer* serializer, mip_ mip_cmd_result mip_rtk_prod_erase_storage(struct mip_interface* device, mip_media_selector media) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_media_selector(&serializer, media); @@ -457,7 +457,7 @@ mip_cmd_result mip_rtk_prod_erase_storage(struct mip_interface* device, mip_medi return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_PROD_ERASE_STORAGE, buffer, (uint8_t) microstrain_serializer_length( &serializer)); } -void insert_mip_rtk_led_control_command(mip_serializer* serializer, const mip_rtk_led_control_command* self) +void insert_mip_rtk_led_control_command(microstrain_serializer* serializer, const mip_rtk_led_control_command* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_u8(serializer, self->primaryColor[i]); @@ -470,7 +470,7 @@ void insert_mip_rtk_led_control_command(mip_serializer* serializer, const mip_rt microstrain_insert_u32(serializer, self->period); } -void extract_mip_rtk_led_control_command(mip_serializer* serializer, mip_rtk_led_control_command* self) +void extract_mip_rtk_led_control_command(microstrain_serializer* serializer, mip_rtk_led_control_command* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_u8(serializer, &self->primaryColor[i]); @@ -486,9 +486,9 @@ void extract_mip_rtk_led_control_command(mip_serializer* serializer, mip_rtk_led mip_cmd_result mip_rtk_led_control(struct mip_interface* device, const uint8_t* primary_color, const uint8_t* alt_color, mip_led_action act, uint32_t period) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); assert(primary_color || (3 == 0)); for(unsigned int i=0; i < 3; i++) diff --git a/src/mip/definitions/commands_rtk.cpp b/src/mip/definitions/commands_rtk.cpp index 6c854c4db..3306403e3 100644 --- a/src/mip/definitions/commands_rtk.cpp +++ b/src/mip/definitions/commands_rtk.cpp @@ -244,7 +244,7 @@ TypedResult writeConnectedDeviceType(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut) { @@ -255,7 +255,7 @@ TypedResult readConnectedDeviceType(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_CONNECTED_DEVICE_TYPE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_CONNECTED_DEVICE_TYPE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -277,7 +277,7 @@ TypedResult saveConnectedDeviceType(C::mip_interface& devic insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult loadConnectedDeviceType(C::mip_interface& device) { @@ -287,7 +287,7 @@ TypedResult loadConnectedDeviceType(C::mip_interface& devic insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult defaultConnectedDeviceType(C::mip_interface& device) { @@ -297,7 +297,7 @@ TypedResult defaultConnectedDeviceType(C::mip_interface& de insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const GetActCode& self) { @@ -492,7 +492,7 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SERVICE_STATUS, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_SERVICE_STATUS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SERVICE_STATUS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SERVICE_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -535,7 +535,7 @@ TypedResult prodEraseStorage(C::mip_interface& device, MediaSe assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PROD_ERASE_STORAGE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PROD_ERASE_STORAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const LedControl& self) { @@ -583,7 +583,7 @@ TypedResult ledControl(C::mip_interface& device, const uint8_t* prim assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert(Serializer& serializer, const ModemHardReset& self) { diff --git a/src/mip/definitions/commands_rtk.h b/src/mip/definitions/commands_rtk.h index 6271716eb..41db0ab52 100644 --- a/src/mip/definitions/commands_rtk.h +++ b/src/mip/definitions/commands_rtk.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -65,16 +65,16 @@ typedef uint8_t mip_media_selector; static const mip_media_selector MIP_MEDIA_SELECTOR_MEDIA_EXTERNALFLASH = 0; ///< static const mip_media_selector MIP_MEDIA_SELECTOR_MEDIA_SD = 1; ///< -void insert_mip_media_selector(struct mip_serializer* serializer, const mip_media_selector self); -void extract_mip_media_selector(struct mip_serializer* serializer, mip_media_selector* self); +void insert_mip_media_selector(struct microstrain_serializer* serializer, const mip_media_selector self); +void extract_mip_media_selector(struct microstrain_serializer* serializer, mip_media_selector* self); typedef uint8_t mip_led_action; static const mip_led_action MIP_LED_ACTION_LED_NONE = 0; ///< static const mip_led_action MIP_LED_ACTION_LED_FLASH = 1; ///< static const mip_led_action MIP_LED_ACTION_LED_PULSATE = 2; ///< -void insert_mip_led_action(struct mip_serializer* serializer, const mip_led_action self); -void extract_mip_led_action(struct mip_serializer* serializer, mip_led_action* self); +void insert_mip_led_action(struct microstrain_serializer* serializer, const mip_led_action self); +void extract_mip_led_action(struct microstrain_serializer* serializer, mip_led_action* self); //////////////////////////////////////////////////////////////////////////////// @@ -117,11 +117,11 @@ static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FL static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_VERSION = 0xC0000000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_ALL = 0xFFFFFFFF; -void insert_mip_rtk_get_status_flags_command_status_flags_legacy(struct mip_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self); -void extract_mip_rtk_get_status_flags_command_status_flags_legacy(struct mip_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self); +void insert_mip_rtk_get_status_flags_command_status_flags_legacy(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self); +void extract_mip_rtk_get_status_flags_command_status_flags_legacy(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self); -void insert_mip_rtk_get_status_flags_command_status_flags(struct mip_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self); -void extract_mip_rtk_get_status_flags_command_status_flags(struct mip_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self); +void insert_mip_rtk_get_status_flags_command_status_flags(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self); +void extract_mip_rtk_get_status_flags_command_status_flags(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self); struct mip_rtk_get_status_flags_response { @@ -129,8 +129,8 @@ struct mip_rtk_get_status_flags_response }; typedef struct mip_rtk_get_status_flags_response mip_rtk_get_status_flags_response; -void insert_mip_rtk_get_status_flags_response(struct mip_serializer* serializer, const mip_rtk_get_status_flags_response* self); -void extract_mip_rtk_get_status_flags_response(struct mip_serializer* serializer, mip_rtk_get_status_flags_response* self); +void insert_mip_rtk_get_status_flags_response(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_response* self); +void extract_mip_rtk_get_status_flags_response(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_response* self); mip_cmd_result mip_rtk_get_status_flags(struct mip_interface* device, mip_rtk_get_status_flags_command_status_flags* flags_out); @@ -147,8 +147,8 @@ struct mip_rtk_get_imei_response }; typedef struct mip_rtk_get_imei_response mip_rtk_get_imei_response; -void insert_mip_rtk_get_imei_response(struct mip_serializer* serializer, const mip_rtk_get_imei_response* self); -void extract_mip_rtk_get_imei_response(struct mip_serializer* serializer, mip_rtk_get_imei_response* self); +void insert_mip_rtk_get_imei_response(struct microstrain_serializer* serializer, const mip_rtk_get_imei_response* self); +void extract_mip_rtk_get_imei_response(struct microstrain_serializer* serializer, mip_rtk_get_imei_response* self); mip_cmd_result mip_rtk_get_imei(struct mip_interface* device, char* imei_out); @@ -165,8 +165,8 @@ struct mip_rtk_get_imsi_response }; typedef struct mip_rtk_get_imsi_response mip_rtk_get_imsi_response; -void insert_mip_rtk_get_imsi_response(struct mip_serializer* serializer, const mip_rtk_get_imsi_response* self); -void extract_mip_rtk_get_imsi_response(struct mip_serializer* serializer, mip_rtk_get_imsi_response* self); +void insert_mip_rtk_get_imsi_response(struct microstrain_serializer* serializer, const mip_rtk_get_imsi_response* self); +void extract_mip_rtk_get_imsi_response(struct microstrain_serializer* serializer, mip_rtk_get_imsi_response* self); mip_cmd_result mip_rtk_get_imsi(struct mip_interface* device, char* imsi_out); @@ -183,8 +183,8 @@ struct mip_rtk_get_iccid_response }; typedef struct mip_rtk_get_iccid_response mip_rtk_get_iccid_response; -void insert_mip_rtk_get_iccid_response(struct mip_serializer* serializer, const mip_rtk_get_iccid_response* self); -void extract_mip_rtk_get_iccid_response(struct mip_serializer* serializer, mip_rtk_get_iccid_response* self); +void insert_mip_rtk_get_iccid_response(struct microstrain_serializer* serializer, const mip_rtk_get_iccid_response* self); +void extract_mip_rtk_get_iccid_response(struct microstrain_serializer* serializer, mip_rtk_get_iccid_response* self); mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out); @@ -206,11 +206,11 @@ struct mip_rtk_connected_device_type_command }; typedef struct mip_rtk_connected_device_type_command mip_rtk_connected_device_type_command; -void insert_mip_rtk_connected_device_type_command(struct mip_serializer* serializer, const mip_rtk_connected_device_type_command* self); -void extract_mip_rtk_connected_device_type_command(struct mip_serializer* serializer, mip_rtk_connected_device_type_command* self); +void insert_mip_rtk_connected_device_type_command(struct microstrain_serializer* serializer, const mip_rtk_connected_device_type_command* self); +void extract_mip_rtk_connected_device_type_command(struct microstrain_serializer* serializer, mip_rtk_connected_device_type_command* self); -void insert_mip_rtk_connected_device_type_command_type(struct mip_serializer* serializer, const mip_rtk_connected_device_type_command_type self); -void extract_mip_rtk_connected_device_type_command_type(struct mip_serializer* serializer, mip_rtk_connected_device_type_command_type* self); +void insert_mip_rtk_connected_device_type_command_type(struct microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self); +void extract_mip_rtk_connected_device_type_command_type(struct microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self); struct mip_rtk_connected_device_type_response { @@ -218,8 +218,8 @@ struct mip_rtk_connected_device_type_response }; typedef struct mip_rtk_connected_device_type_response mip_rtk_connected_device_type_response; -void insert_mip_rtk_connected_device_type_response(struct mip_serializer* serializer, const mip_rtk_connected_device_type_response* self); -void extract_mip_rtk_connected_device_type_response(struct mip_serializer* serializer, mip_rtk_connected_device_type_response* self); +void insert_mip_rtk_connected_device_type_response(struct microstrain_serializer* serializer, const mip_rtk_connected_device_type_response* self); +void extract_mip_rtk_connected_device_type_response(struct microstrain_serializer* serializer, mip_rtk_connected_device_type_response* self); mip_cmd_result mip_rtk_write_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type dev_type); mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type* dev_type_out); @@ -240,8 +240,8 @@ struct mip_rtk_get_act_code_response }; typedef struct mip_rtk_get_act_code_response mip_rtk_get_act_code_response; -void insert_mip_rtk_get_act_code_response(struct mip_serializer* serializer, const mip_rtk_get_act_code_response* self); -void extract_mip_rtk_get_act_code_response(struct mip_serializer* serializer, mip_rtk_get_act_code_response* self); +void insert_mip_rtk_get_act_code_response(struct microstrain_serializer* serializer, const mip_rtk_get_act_code_response* self); +void extract_mip_rtk_get_act_code_response(struct microstrain_serializer* serializer, mip_rtk_get_act_code_response* self); mip_cmd_result mip_rtk_get_act_code(struct mip_interface* device, char* activation_code_out); @@ -258,8 +258,8 @@ struct mip_rtk_get_modem_firmware_version_response }; typedef struct mip_rtk_get_modem_firmware_version_response mip_rtk_get_modem_firmware_version_response; -void insert_mip_rtk_get_modem_firmware_version_response(struct mip_serializer* serializer, const mip_rtk_get_modem_firmware_version_response* self); -void extract_mip_rtk_get_modem_firmware_version_response(struct mip_serializer* serializer, mip_rtk_get_modem_firmware_version_response* self); +void insert_mip_rtk_get_modem_firmware_version_response(struct microstrain_serializer* serializer, const mip_rtk_get_modem_firmware_version_response* self); +void extract_mip_rtk_get_modem_firmware_version_response(struct microstrain_serializer* serializer, mip_rtk_get_modem_firmware_version_response* self); mip_cmd_result mip_rtk_get_modem_firmware_version(struct mip_interface* device, char* modem_firmware_version_out); @@ -279,8 +279,8 @@ struct mip_rtk_get_rssi_response }; typedef struct mip_rtk_get_rssi_response mip_rtk_get_rssi_response; -void insert_mip_rtk_get_rssi_response(struct mip_serializer* serializer, const mip_rtk_get_rssi_response* self); -void extract_mip_rtk_get_rssi_response(struct mip_serializer* serializer, mip_rtk_get_rssi_response* self); +void insert_mip_rtk_get_rssi_response(struct microstrain_serializer* serializer, const mip_rtk_get_rssi_response* self); +void extract_mip_rtk_get_rssi_response(struct microstrain_serializer* serializer, mip_rtk_get_rssi_response* self); mip_cmd_result mip_rtk_get_rssi(struct mip_interface* device, bool* valid_out, int32_t* rssi_out, int32_t* signal_quality_out); @@ -306,11 +306,11 @@ struct mip_rtk_service_status_command }; typedef struct mip_rtk_service_status_command mip_rtk_service_status_command; -void insert_mip_rtk_service_status_command(struct mip_serializer* serializer, const mip_rtk_service_status_command* self); -void extract_mip_rtk_service_status_command(struct mip_serializer* serializer, mip_rtk_service_status_command* self); +void insert_mip_rtk_service_status_command(struct microstrain_serializer* serializer, const mip_rtk_service_status_command* self); +void extract_mip_rtk_service_status_command(struct microstrain_serializer* serializer, mip_rtk_service_status_command* self); -void insert_mip_rtk_service_status_command_service_flags(struct mip_serializer* serializer, const mip_rtk_service_status_command_service_flags self); -void extract_mip_rtk_service_status_command_service_flags(struct mip_serializer* serializer, mip_rtk_service_status_command_service_flags* self); +void insert_mip_rtk_service_status_command_service_flags(struct microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self); +void extract_mip_rtk_service_status_command_service_flags(struct microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self); struct mip_rtk_service_status_response { @@ -321,8 +321,8 @@ struct mip_rtk_service_status_response }; typedef struct mip_rtk_service_status_response mip_rtk_service_status_response; -void insert_mip_rtk_service_status_response(struct mip_serializer* serializer, const mip_rtk_service_status_response* self); -void extract_mip_rtk_service_status_response(struct mip_serializer* serializer, mip_rtk_service_status_response* self); +void insert_mip_rtk_service_status_response(struct microstrain_serializer* serializer, const mip_rtk_service_status_response* self); +void extract_mip_rtk_service_status_response(struct microstrain_serializer* serializer, mip_rtk_service_status_response* self); mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t reserved1, uint32_t reserved2, mip_rtk_service_status_command_service_flags* flags_out, uint32_t* received_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out); @@ -341,8 +341,8 @@ struct mip_rtk_prod_erase_storage_command }; typedef struct mip_rtk_prod_erase_storage_command mip_rtk_prod_erase_storage_command; -void insert_mip_rtk_prod_erase_storage_command(struct mip_serializer* serializer, const mip_rtk_prod_erase_storage_command* self); -void extract_mip_rtk_prod_erase_storage_command(struct mip_serializer* serializer, mip_rtk_prod_erase_storage_command* self); +void insert_mip_rtk_prod_erase_storage_command(struct microstrain_serializer* serializer, const mip_rtk_prod_erase_storage_command* self); +void extract_mip_rtk_prod_erase_storage_command(struct microstrain_serializer* serializer, mip_rtk_prod_erase_storage_command* self); mip_cmd_result mip_rtk_prod_erase_storage(struct mip_interface* device, mip_media_selector media); @@ -363,8 +363,8 @@ struct mip_rtk_led_control_command }; typedef struct mip_rtk_led_control_command mip_rtk_led_control_command; -void insert_mip_rtk_led_control_command(struct mip_serializer* serializer, const mip_rtk_led_control_command* self); -void extract_mip_rtk_led_control_command(struct mip_serializer* serializer, mip_rtk_led_control_command* self); +void insert_mip_rtk_led_control_command(struct microstrain_serializer* serializer, const mip_rtk_led_control_command* self); +void extract_mip_rtk_led_control_command(struct microstrain_serializer* serializer, mip_rtk_led_control_command* self); mip_cmd_result mip_rtk_led_control(struct mip_interface* device, const uint8_t* primary_color, const uint8_t* alt_color, mip_led_action act, uint32_t period); diff --git a/src/mip/definitions/commands_system.c b/src/mip/definitions/commands_system.c index 97fd45816..1e6cf5b16 100644 --- a/src/mip/definitions/commands_system.c +++ b/src/mip/definitions/commands_system.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -27,7 +27,7 @@ struct mip_field; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_system_comm_mode_command(mip_serializer* serializer, const mip_system_comm_mode_command* self) +void insert_mip_system_comm_mode_command(microstrain_serializer* serializer, const mip_system_comm_mode_command* self) { insert_mip_function_selector(serializer, self->function); @@ -37,7 +37,7 @@ void insert_mip_system_comm_mode_command(mip_serializer* serializer, const mip_s } } -void extract_mip_system_comm_mode_command(mip_serializer* serializer, mip_system_comm_mode_command* self) +void extract_mip_system_comm_mode_command(microstrain_serializer* serializer, mip_system_comm_mode_command* self) { extract_mip_function_selector(serializer, &self->function); @@ -48,12 +48,12 @@ void extract_mip_system_comm_mode_command(mip_serializer* serializer, mip_system } } -void insert_mip_system_comm_mode_response(mip_serializer* serializer, const mip_system_comm_mode_response* self) +void insert_mip_system_comm_mode_response(microstrain_serializer* serializer, const mip_system_comm_mode_response* self) { microstrain_insert_u8(serializer, self->mode); } -void extract_mip_system_comm_mode_response(mip_serializer* serializer, mip_system_comm_mode_response* self) +void extract_mip_system_comm_mode_response(microstrain_serializer* serializer, mip_system_comm_mode_response* self) { microstrain_extract_u8(serializer, &self->mode); @@ -61,9 +61,9 @@ void extract_mip_system_comm_mode_response(mip_serializer* serializer, mip_syste mip_cmd_result mip_system_write_comm_mode(struct mip_interface* device, uint8_t mode) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); @@ -76,9 +76,9 @@ mip_cmd_result mip_system_write_comm_mode(struct mip_interface* device, uint8_t } mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* mode_out) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); @@ -90,8 +90,8 @@ mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* if( result == MIP_ACK_OK ) { - mip_serializer deserializer; - mip_serializer_init_insertion(&deserializer, buffer, responseLength); + microstrain_serializer deserializer; + microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(mode_out); microstrain_extract_u8(&deserializer, mode_out); @@ -103,9 +103,9 @@ mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* } mip_cmd_result mip_system_default_comm_mode(struct mip_interface* device) { - mip_serializer serializer; + microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - mip_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); diff --git a/src/mip/definitions/commands_system.cpp b/src/mip/definitions/commands_system.cpp index d1c11614a..8e5935416 100644 --- a/src/mip/definitions/commands_system.cpp +++ b/src/mip/definitions/commands_system.cpp @@ -71,7 +71,7 @@ TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) { @@ -82,7 +82,7 @@ TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)mip_serializer_length(&serializer), REPLY_COM_MODE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_COM_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -104,7 +104,7 @@ TypedResult defaultCommMode(C::mip_interface& device) insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)mip_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } } // namespace commands_system diff --git a/src/mip/definitions/commands_system.h b/src/mip/definitions/commands_system.h index ebdd56585..34bec626a 100644 --- a/src/mip/definitions/commands_system.h +++ b/src/mip/definitions/commands_system.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -77,8 +77,8 @@ struct mip_system_comm_mode_command }; typedef struct mip_system_comm_mode_command mip_system_comm_mode_command; -void insert_mip_system_comm_mode_command(struct mip_serializer* serializer, const mip_system_comm_mode_command* self); -void extract_mip_system_comm_mode_command(struct mip_serializer* serializer, mip_system_comm_mode_command* self); +void insert_mip_system_comm_mode_command(struct microstrain_serializer* serializer, const mip_system_comm_mode_command* self); +void extract_mip_system_comm_mode_command(struct microstrain_serializer* serializer, mip_system_comm_mode_command* self); struct mip_system_comm_mode_response { @@ -86,8 +86,8 @@ struct mip_system_comm_mode_response }; typedef struct mip_system_comm_mode_response mip_system_comm_mode_response; -void insert_mip_system_comm_mode_response(struct mip_serializer* serializer, const mip_system_comm_mode_response* self); -void extract_mip_system_comm_mode_response(struct mip_serializer* serializer, mip_system_comm_mode_response* self); +void insert_mip_system_comm_mode_response(struct microstrain_serializer* serializer, const mip_system_comm_mode_response* self); +void extract_mip_system_comm_mode_response(struct microstrain_serializer* serializer, mip_system_comm_mode_response* self); mip_cmd_result mip_system_write_comm_mode(struct mip_interface* device, uint8_t mode); mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* mode_out); diff --git a/src/mip/definitions/common.c b/src/mip/definitions/common.c index 90023557c..bc12983f0 100644 --- a/src/mip/definitions/common.c +++ b/src/mip/definitions/common.c @@ -4,25 +4,25 @@ #include "microstrain/common/serialization.h" -void insert_mip_descriptor_rate(mip_serializer* serializer, const mip_descriptor_rate* self) +void insert_mip_descriptor_rate(microstrain_serializer* serializer, const mip_descriptor_rate* self) { microstrain_insert_u8(serializer, self->descriptor); microstrain_insert_u16(serializer, self->decimation); } -void extract_mip_descriptor_rate(mip_serializer* serializer, mip_descriptor_rate* self) +void extract_mip_descriptor_rate(microstrain_serializer* serializer, mip_descriptor_rate* self) { microstrain_extract_u8(serializer, &self->descriptor); microstrain_extract_u16(serializer, &self->decimation); } #define IMPLEMENT_MIP_VECTOR_FUNCTIONS(n,type,name) \ -void insert_##name(mip_serializer* serializer, const name self) \ +void insert_##name(microstrain_serializer* serializer, const name self) \ { \ for(unsigned int i=0; i; using Quatf = Vector4f; template -void insert(Serializer& serializer, const Vector& v) { for(size_t i=0; i& v) { for(size_t i=0; i -void extract(Serializer& serializer, Vector& v) { for(size_t i=0; i& v) { for(size_t i=0; ilatitude); @@ -104,7 +104,7 @@ void insert_mip_filter_position_llh_data(mip_serializer* serializer, const mip_f microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_position_llh_data(mip_serializer* serializer, mip_filter_position_llh_data* self) +void extract_mip_filter_position_llh_data(microstrain_serializer* serializer, mip_filter_position_llh_data* self) { microstrain_extract_double(serializer, &self->latitude); @@ -119,13 +119,13 @@ bool extract_mip_filter_position_llh_data_from_field(const mip_field* field, voi { assert(ptr); mip_filter_position_llh_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_position_llh_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_velocity_ned_data(mip_serializer* serializer, const mip_filter_velocity_ned_data* self) +void insert_mip_filter_velocity_ned_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_data* self) { microstrain_insert_float(serializer, self->north); @@ -136,7 +136,7 @@ void insert_mip_filter_velocity_ned_data(mip_serializer* serializer, const mip_f microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_velocity_ned_data(mip_serializer* serializer, mip_filter_velocity_ned_data* self) +void extract_mip_filter_velocity_ned_data(microstrain_serializer* serializer, mip_filter_velocity_ned_data* self) { microstrain_extract_float(serializer, &self->north); @@ -151,13 +151,13 @@ bool extract_mip_filter_velocity_ned_data_from_field(const mip_field* field, voi { assert(ptr); mip_filter_velocity_ned_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_velocity_ned_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_attitude_quaternion_data(mip_serializer* serializer, const mip_filter_attitude_quaternion_data* self) +void insert_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, const mip_filter_attitude_quaternion_data* self) { for(unsigned int i=0; i < 4; i++) microstrain_insert_float(serializer, self->q[i]); @@ -165,7 +165,7 @@ void insert_mip_filter_attitude_quaternion_data(mip_serializer* serializer, cons microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_attitude_quaternion_data(mip_serializer* serializer, mip_filter_attitude_quaternion_data* self) +void extract_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, mip_filter_attitude_quaternion_data* self) { for(unsigned int i=0; i < 4; i++) microstrain_extract_float(serializer, &self->q[i]); @@ -177,13 +177,13 @@ bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field* fie { assert(ptr); mip_filter_attitude_quaternion_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_attitude_quaternion_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_attitude_dcm_data(mip_serializer* serializer, const mip_filter_attitude_dcm_data* self) +void insert_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, const mip_filter_attitude_dcm_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->dcm[i]); @@ -191,7 +191,7 @@ void insert_mip_filter_attitude_dcm_data(mip_serializer* serializer, const mip_f microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_attitude_dcm_data(mip_serializer* serializer, mip_filter_attitude_dcm_data* self) +void extract_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, mip_filter_attitude_dcm_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->dcm[i]); @@ -203,13 +203,13 @@ bool extract_mip_filter_attitude_dcm_data_from_field(const mip_field* field, voi { assert(ptr); mip_filter_attitude_dcm_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_attitude_dcm_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_euler_angles_data(mip_serializer* serializer, const mip_filter_euler_angles_data* self) +void insert_mip_filter_euler_angles_data(microstrain_serializer* serializer, const mip_filter_euler_angles_data* self) { microstrain_insert_float(serializer, self->roll); @@ -220,7 +220,7 @@ void insert_mip_filter_euler_angles_data(mip_serializer* serializer, const mip_f microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_euler_angles_data(mip_serializer* serializer, mip_filter_euler_angles_data* self) +void extract_mip_filter_euler_angles_data(microstrain_serializer* serializer, mip_filter_euler_angles_data* self) { microstrain_extract_float(serializer, &self->roll); @@ -235,13 +235,13 @@ bool extract_mip_filter_euler_angles_data_from_field(const mip_field* field, voi { assert(ptr); mip_filter_euler_angles_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_euler_angles_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gyro_bias_data(mip_serializer* serializer, const mip_filter_gyro_bias_data* self) +void insert_mip_filter_gyro_bias_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->bias[i]); @@ -249,7 +249,7 @@ void insert_mip_filter_gyro_bias_data(mip_serializer* serializer, const mip_filt microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_gyro_bias_data(mip_serializer* serializer, mip_filter_gyro_bias_data* self) +void extract_mip_filter_gyro_bias_data(microstrain_serializer* serializer, mip_filter_gyro_bias_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->bias[i]); @@ -261,13 +261,13 @@ bool extract_mip_filter_gyro_bias_data_from_field(const mip_field* field, void* { assert(ptr); mip_filter_gyro_bias_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_bias_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_accel_bias_data(mip_serializer* serializer, const mip_filter_accel_bias_data* self) +void insert_mip_filter_accel_bias_data(microstrain_serializer* serializer, const mip_filter_accel_bias_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->bias[i]); @@ -275,7 +275,7 @@ void insert_mip_filter_accel_bias_data(mip_serializer* serializer, const mip_fil microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_accel_bias_data(mip_serializer* serializer, mip_filter_accel_bias_data* self) +void extract_mip_filter_accel_bias_data(microstrain_serializer* serializer, mip_filter_accel_bias_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->bias[i]); @@ -287,13 +287,13 @@ bool extract_mip_filter_accel_bias_data_from_field(const mip_field* field, void* { assert(ptr); mip_filter_accel_bias_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_bias_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_position_llh_uncertainty_data(mip_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self) +void insert_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self) { microstrain_insert_float(serializer, self->north); @@ -304,7 +304,7 @@ void insert_mip_filter_position_llh_uncertainty_data(mip_serializer* serializer, microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_position_llh_uncertainty_data(mip_serializer* serializer, mip_filter_position_llh_uncertainty_data* self) +void extract_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, mip_filter_position_llh_uncertainty_data* self) { microstrain_extract_float(serializer, &self->north); @@ -319,13 +319,13 @@ bool extract_mip_filter_position_llh_uncertainty_data_from_field(const mip_field { assert(ptr); mip_filter_position_llh_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_position_llh_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_velocity_ned_uncertainty_data(mip_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self) +void insert_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self) { microstrain_insert_float(serializer, self->north); @@ -336,7 +336,7 @@ void insert_mip_filter_velocity_ned_uncertainty_data(mip_serializer* serializer, microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_velocity_ned_uncertainty_data(mip_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self) +void extract_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self) { microstrain_extract_float(serializer, &self->north); @@ -351,13 +351,13 @@ bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const mip_field { assert(ptr); mip_filter_velocity_ned_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_velocity_ned_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_euler_angles_uncertainty_data(mip_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self) +void insert_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self) { microstrain_insert_float(serializer, self->roll); @@ -368,7 +368,7 @@ void insert_mip_filter_euler_angles_uncertainty_data(mip_serializer* serializer, microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_euler_angles_uncertainty_data(mip_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self) +void extract_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self) { microstrain_extract_float(serializer, &self->roll); @@ -383,13 +383,13 @@ bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const mip_field { assert(ptr); mip_filter_euler_angles_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_euler_angles_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gyro_bias_uncertainty_data(mip_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self) +void insert_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->bias_uncert[i]); @@ -397,7 +397,7 @@ void insert_mip_filter_gyro_bias_uncertainty_data(mip_serializer* serializer, co microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_gyro_bias_uncertainty_data(mip_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self) +void extract_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->bias_uncert[i]); @@ -409,13 +409,13 @@ bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const mip_field* f { assert(ptr); mip_filter_gyro_bias_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_bias_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_accel_bias_uncertainty_data(mip_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self) +void insert_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->bias_uncert[i]); @@ -423,7 +423,7 @@ void insert_mip_filter_accel_bias_uncertainty_data(mip_serializer* serializer, c microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_accel_bias_uncertainty_data(mip_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self) +void extract_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->bias_uncert[i]); @@ -435,13 +435,13 @@ bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const mip_field* { assert(ptr); mip_filter_accel_bias_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_bias_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_timestamp_data(mip_serializer* serializer, const mip_filter_timestamp_data* self) +void insert_mip_filter_timestamp_data(microstrain_serializer* serializer, const mip_filter_timestamp_data* self) { microstrain_insert_double(serializer, self->tow); @@ -450,7 +450,7 @@ void insert_mip_filter_timestamp_data(mip_serializer* serializer, const mip_filt microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_timestamp_data(mip_serializer* serializer, mip_filter_timestamp_data* self) +void extract_mip_filter_timestamp_data(microstrain_serializer* serializer, mip_filter_timestamp_data* self) { microstrain_extract_double(serializer, &self->tow); @@ -463,13 +463,13 @@ bool extract_mip_filter_timestamp_data_from_field(const mip_field* field, void* { assert(ptr); mip_filter_timestamp_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_status_data(mip_serializer* serializer, const mip_filter_status_data* self) +void insert_mip_filter_status_data(microstrain_serializer* serializer, const mip_filter_status_data* self) { insert_mip_filter_mode(serializer, self->filter_state); @@ -478,7 +478,7 @@ void insert_mip_filter_status_data(mip_serializer* serializer, const mip_filter_ insert_mip_filter_status_flags(serializer, self->status_flags); } -void extract_mip_filter_status_data(mip_serializer* serializer, mip_filter_status_data* self) +void extract_mip_filter_status_data(microstrain_serializer* serializer, mip_filter_status_data* self) { extract_mip_filter_mode(serializer, &self->filter_state); @@ -491,13 +491,13 @@ bool extract_mip_filter_status_data_from_field(const mip_field* field, void* ptr { assert(ptr); mip_filter_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_linear_accel_data(mip_serializer* serializer, const mip_filter_linear_accel_data* self) +void insert_mip_filter_linear_accel_data(microstrain_serializer* serializer, const mip_filter_linear_accel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->accel[i]); @@ -505,7 +505,7 @@ void insert_mip_filter_linear_accel_data(mip_serializer* serializer, const mip_f microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_linear_accel_data(mip_serializer* serializer, mip_filter_linear_accel_data* self) +void extract_mip_filter_linear_accel_data(microstrain_serializer* serializer, mip_filter_linear_accel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->accel[i]); @@ -517,13 +517,13 @@ bool extract_mip_filter_linear_accel_data_from_field(const mip_field* field, voi { assert(ptr); mip_filter_linear_accel_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_linear_accel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gravity_vector_data(mip_serializer* serializer, const mip_filter_gravity_vector_data* self) +void insert_mip_filter_gravity_vector_data(microstrain_serializer* serializer, const mip_filter_gravity_vector_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->gravity[i]); @@ -531,7 +531,7 @@ void insert_mip_filter_gravity_vector_data(mip_serializer* serializer, const mip microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_gravity_vector_data(mip_serializer* serializer, mip_filter_gravity_vector_data* self) +void extract_mip_filter_gravity_vector_data(microstrain_serializer* serializer, mip_filter_gravity_vector_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->gravity[i]); @@ -543,13 +543,13 @@ bool extract_mip_filter_gravity_vector_data_from_field(const mip_field* field, v { assert(ptr); mip_filter_gravity_vector_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gravity_vector_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_comp_accel_data(mip_serializer* serializer, const mip_filter_comp_accel_data* self) +void insert_mip_filter_comp_accel_data(microstrain_serializer* serializer, const mip_filter_comp_accel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->accel[i]); @@ -557,7 +557,7 @@ void insert_mip_filter_comp_accel_data(mip_serializer* serializer, const mip_fil microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_comp_accel_data(mip_serializer* serializer, mip_filter_comp_accel_data* self) +void extract_mip_filter_comp_accel_data(microstrain_serializer* serializer, mip_filter_comp_accel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->accel[i]); @@ -569,13 +569,13 @@ bool extract_mip_filter_comp_accel_data_from_field(const mip_field* field, void* { assert(ptr); mip_filter_comp_accel_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_comp_accel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_comp_angular_rate_data(mip_serializer* serializer, const mip_filter_comp_angular_rate_data* self) +void insert_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, const mip_filter_comp_angular_rate_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->gyro[i]); @@ -583,7 +583,7 @@ void insert_mip_filter_comp_angular_rate_data(mip_serializer* serializer, const microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_comp_angular_rate_data(mip_serializer* serializer, mip_filter_comp_angular_rate_data* self) +void extract_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, mip_filter_comp_angular_rate_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->gyro[i]); @@ -595,13 +595,13 @@ bool extract_mip_filter_comp_angular_rate_data_from_field(const mip_field* field { assert(ptr); mip_filter_comp_angular_rate_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_comp_angular_rate_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_quaternion_attitude_uncertainty_data(mip_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self) +void insert_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self) { for(unsigned int i=0; i < 4; i++) microstrain_insert_float(serializer, self->q[i]); @@ -609,7 +609,7 @@ void insert_mip_filter_quaternion_attitude_uncertainty_data(mip_serializer* seri microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_quaternion_attitude_uncertainty_data(mip_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self) +void extract_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self) { for(unsigned int i=0; i < 4; i++) microstrain_extract_float(serializer, &self->q[i]); @@ -621,20 +621,20 @@ bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const mi { assert(ptr); mip_filter_quaternion_attitude_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_quaternion_attitude_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_wgs84_gravity_mag_data(mip_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self) +void insert_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self) { microstrain_insert_float(serializer, self->magnitude); microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_wgs84_gravity_mag_data(mip_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self) +void extract_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self) { microstrain_extract_float(serializer, &self->magnitude); @@ -645,13 +645,13 @@ bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const mip_field* field { assert(ptr); mip_filter_wgs84_gravity_mag_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_wgs84_gravity_mag_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_heading_update_state_data(mip_serializer* serializer, const mip_filter_heading_update_state_data* self) +void insert_mip_filter_heading_update_state_data(microstrain_serializer* serializer, const mip_filter_heading_update_state_data* self) { microstrain_insert_float(serializer, self->heading); @@ -662,7 +662,7 @@ void insert_mip_filter_heading_update_state_data(mip_serializer* serializer, con microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_heading_update_state_data(mip_serializer* serializer, mip_filter_heading_update_state_data* self) +void extract_mip_filter_heading_update_state_data(microstrain_serializer* serializer, mip_filter_heading_update_state_data* self) { microstrain_extract_float(serializer, &self->heading); @@ -677,24 +677,24 @@ bool extract_mip_filter_heading_update_state_data_from_field(const mip_field* fi { assert(ptr); mip_filter_heading_update_state_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_heading_update_state_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_heading_update_state_data_heading_source(struct mip_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self) +void insert_mip_filter_heading_update_state_data_heading_source(struct microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_heading_update_state_data_heading_source(struct mip_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self) +void extract_mip_filter_heading_update_state_data_heading_source(struct microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_filter_magnetic_model_data(mip_serializer* serializer, const mip_filter_magnetic_model_data* self) +void insert_mip_filter_magnetic_model_data(microstrain_serializer* serializer, const mip_filter_magnetic_model_data* self) { microstrain_insert_float(serializer, self->intensity_north); @@ -709,7 +709,7 @@ void insert_mip_filter_magnetic_model_data(mip_serializer* serializer, const mip microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_magnetic_model_data(mip_serializer* serializer, mip_filter_magnetic_model_data* self) +void extract_mip_filter_magnetic_model_data(microstrain_serializer* serializer, mip_filter_magnetic_model_data* self) { microstrain_extract_float(serializer, &self->intensity_north); @@ -728,13 +728,13 @@ bool extract_mip_filter_magnetic_model_data_from_field(const mip_field* field, v { assert(ptr); mip_filter_magnetic_model_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetic_model_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_accel_scale_factor_data(mip_serializer* serializer, const mip_filter_accel_scale_factor_data* self) +void insert_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->scale_factor[i]); @@ -742,7 +742,7 @@ void insert_mip_filter_accel_scale_factor_data(mip_serializer* serializer, const microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_accel_scale_factor_data(mip_serializer* serializer, mip_filter_accel_scale_factor_data* self) +void extract_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->scale_factor[i]); @@ -754,13 +754,13 @@ bool extract_mip_filter_accel_scale_factor_data_from_field(const mip_field* fiel { assert(ptr); mip_filter_accel_scale_factor_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_scale_factor_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_accel_scale_factor_uncertainty_data(mip_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self) +void insert_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->scale_factor_uncert[i]); @@ -768,7 +768,7 @@ void insert_mip_filter_accel_scale_factor_uncertainty_data(mip_serializer* seria microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_accel_scale_factor_uncertainty_data(mip_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self) +void extract_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->scale_factor_uncert[i]); @@ -780,13 +780,13 @@ bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const mip { assert(ptr); mip_filter_accel_scale_factor_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_scale_factor_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gyro_scale_factor_data(mip_serializer* serializer, const mip_filter_gyro_scale_factor_data* self) +void insert_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->scale_factor[i]); @@ -794,7 +794,7 @@ void insert_mip_filter_gyro_scale_factor_data(mip_serializer* serializer, const microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_gyro_scale_factor_data(mip_serializer* serializer, mip_filter_gyro_scale_factor_data* self) +void extract_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->scale_factor[i]); @@ -806,13 +806,13 @@ bool extract_mip_filter_gyro_scale_factor_data_from_field(const mip_field* field { assert(ptr); mip_filter_gyro_scale_factor_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_scale_factor_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gyro_scale_factor_uncertainty_data(mip_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self) +void insert_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->scale_factor_uncert[i]); @@ -820,7 +820,7 @@ void insert_mip_filter_gyro_scale_factor_uncertainty_data(mip_serializer* serial microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_gyro_scale_factor_uncertainty_data(mip_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self) +void extract_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->scale_factor_uncert[i]); @@ -832,13 +832,13 @@ bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const mip_ { assert(ptr); mip_filter_gyro_scale_factor_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_scale_factor_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_mag_bias_data(mip_serializer* serializer, const mip_filter_mag_bias_data* self) +void insert_mip_filter_mag_bias_data(microstrain_serializer* serializer, const mip_filter_mag_bias_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->bias[i]); @@ -846,7 +846,7 @@ void insert_mip_filter_mag_bias_data(mip_serializer* serializer, const mip_filte microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_mag_bias_data(mip_serializer* serializer, mip_filter_mag_bias_data* self) +void extract_mip_filter_mag_bias_data(microstrain_serializer* serializer, mip_filter_mag_bias_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->bias[i]); @@ -858,13 +858,13 @@ bool extract_mip_filter_mag_bias_data_from_field(const mip_field* field, void* p { assert(ptr); mip_filter_mag_bias_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_mag_bias_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_mag_bias_uncertainty_data(mip_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self) +void insert_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->bias_uncert[i]); @@ -872,7 +872,7 @@ void insert_mip_filter_mag_bias_uncertainty_data(mip_serializer* serializer, con microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_mag_bias_uncertainty_data(mip_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self) +void extract_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->bias_uncert[i]); @@ -884,13 +884,13 @@ bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const mip_field* fi { assert(ptr); mip_filter_mag_bias_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_mag_bias_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_standard_atmosphere_data(mip_serializer* serializer, const mip_filter_standard_atmosphere_data* self) +void insert_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, const mip_filter_standard_atmosphere_data* self) { microstrain_insert_float(serializer, self->geometric_altitude); @@ -905,7 +905,7 @@ void insert_mip_filter_standard_atmosphere_data(mip_serializer* serializer, cons microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_standard_atmosphere_data(mip_serializer* serializer, mip_filter_standard_atmosphere_data* self) +void extract_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, mip_filter_standard_atmosphere_data* self) { microstrain_extract_float(serializer, &self->geometric_altitude); @@ -924,20 +924,20 @@ bool extract_mip_filter_standard_atmosphere_data_from_field(const mip_field* fie { assert(ptr); mip_filter_standard_atmosphere_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_standard_atmosphere_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_pressure_altitude_data(mip_serializer* serializer, const mip_filter_pressure_altitude_data* self) +void insert_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, const mip_filter_pressure_altitude_data* self) { microstrain_insert_float(serializer, self->pressure_altitude); microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_pressure_altitude_data(mip_serializer* serializer, mip_filter_pressure_altitude_data* self) +void extract_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, mip_filter_pressure_altitude_data* self) { microstrain_extract_float(serializer, &self->pressure_altitude); @@ -948,20 +948,20 @@ bool extract_mip_filter_pressure_altitude_data_from_field(const mip_field* field { assert(ptr); mip_filter_pressure_altitude_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_pressure_altitude_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_density_altitude_data(mip_serializer* serializer, const mip_filter_density_altitude_data* self) +void insert_mip_filter_density_altitude_data(microstrain_serializer* serializer, const mip_filter_density_altitude_data* self) { microstrain_insert_float(serializer, self->density_altitude); microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_density_altitude_data(mip_serializer* serializer, mip_filter_density_altitude_data* self) +void extract_mip_filter_density_altitude_data(microstrain_serializer* serializer, mip_filter_density_altitude_data* self) { microstrain_extract_float(serializer, &self->density_altitude); @@ -972,13 +972,13 @@ bool extract_mip_filter_density_altitude_data_from_field(const mip_field* field, { assert(ptr); mip_filter_density_altitude_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_density_altitude_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_antenna_offset_correction_data(mip_serializer* serializer, const mip_filter_antenna_offset_correction_data* self) +void insert_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->offset[i]); @@ -986,7 +986,7 @@ void insert_mip_filter_antenna_offset_correction_data(mip_serializer* serializer microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_antenna_offset_correction_data(mip_serializer* serializer, mip_filter_antenna_offset_correction_data* self) +void extract_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->offset[i]); @@ -998,13 +998,13 @@ bool extract_mip_filter_antenna_offset_correction_data_from_field(const mip_fiel { assert(ptr); mip_filter_antenna_offset_correction_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_antenna_offset_correction_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_antenna_offset_correction_uncertainty_data(mip_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self) +void insert_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->offset_uncert[i]); @@ -1012,7 +1012,7 @@ void insert_mip_filter_antenna_offset_correction_uncertainty_data(mip_serializer microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_antenna_offset_correction_uncertainty_data(mip_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self) +void extract_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->offset_uncert[i]); @@ -1024,13 +1024,13 @@ bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(co { assert(ptr); mip_filter_antenna_offset_correction_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_antenna_offset_correction_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_multi_antenna_offset_correction_data(mip_serializer* serializer, const mip_filter_multi_antenna_offset_correction_data* self) +void insert_mip_filter_multi_antenna_offset_correction_data(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_data* self) { microstrain_insert_u8(serializer, self->receiver_id); @@ -1040,7 +1040,7 @@ void insert_mip_filter_multi_antenna_offset_correction_data(mip_serializer* seri microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_multi_antenna_offset_correction_data(mip_serializer* serializer, mip_filter_multi_antenna_offset_correction_data* self) +void extract_mip_filter_multi_antenna_offset_correction_data(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_data* self) { microstrain_extract_u8(serializer, &self->receiver_id); @@ -1054,13 +1054,13 @@ bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const mi { assert(ptr); mip_filter_multi_antenna_offset_correction_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_multi_antenna_offset_correction_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(mip_serializer* serializer, const mip_filter_multi_antenna_offset_correction_uncertainty_data* self) +void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_uncertainty_data* self) { microstrain_insert_u8(serializer, self->receiver_id); @@ -1070,7 +1070,7 @@ void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(mip_seri microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(mip_serializer* serializer, mip_filter_multi_antenna_offset_correction_uncertainty_data* self) +void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_uncertainty_data* self) { microstrain_extract_u8(serializer, &self->receiver_id); @@ -1084,13 +1084,13 @@ bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_fi { assert(ptr); mip_filter_multi_antenna_offset_correction_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_magnetometer_offset_data(mip_serializer* serializer, const mip_filter_magnetometer_offset_data* self) +void insert_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->hard_iron[i]); @@ -1098,7 +1098,7 @@ void insert_mip_filter_magnetometer_offset_data(mip_serializer* serializer, cons microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_magnetometer_offset_data(mip_serializer* serializer, mip_filter_magnetometer_offset_data* self) +void extract_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->hard_iron[i]); @@ -1110,13 +1110,13 @@ bool extract_mip_filter_magnetometer_offset_data_from_field(const mip_field* fie { assert(ptr); mip_filter_magnetometer_offset_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_offset_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_magnetometer_matrix_data(mip_serializer* serializer, const mip_filter_magnetometer_matrix_data* self) +void insert_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->soft_iron[i]); @@ -1124,7 +1124,7 @@ void insert_mip_filter_magnetometer_matrix_data(mip_serializer* serializer, cons microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_magnetometer_matrix_data(mip_serializer* serializer, mip_filter_magnetometer_matrix_data* self) +void extract_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->soft_iron[i]); @@ -1136,13 +1136,13 @@ bool extract_mip_filter_magnetometer_matrix_data_from_field(const mip_field* fie { assert(ptr); mip_filter_magnetometer_matrix_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_matrix_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_magnetometer_offset_uncertainty_data(mip_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self) +void insert_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->hard_iron_uncertainty[i]); @@ -1150,7 +1150,7 @@ void insert_mip_filter_magnetometer_offset_uncertainty_data(mip_serializer* seri microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_magnetometer_offset_uncertainty_data(mip_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self) +void extract_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->hard_iron_uncertainty[i]); @@ -1162,13 +1162,13 @@ bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const mi { assert(ptr); mip_filter_magnetometer_offset_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_offset_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_magnetometer_matrix_uncertainty_data(mip_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self) +void insert_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->soft_iron_uncertainty[i]); @@ -1176,7 +1176,7 @@ void insert_mip_filter_magnetometer_matrix_uncertainty_data(mip_serializer* seri microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_magnetometer_matrix_uncertainty_data(mip_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self) +void extract_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->soft_iron_uncertainty[i]); @@ -1188,13 +1188,13 @@ bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const mi { assert(ptr); mip_filter_magnetometer_matrix_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_matrix_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_magnetometer_covariance_matrix_data(mip_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self) +void insert_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->covariance[i]); @@ -1202,7 +1202,7 @@ void insert_mip_filter_magnetometer_covariance_matrix_data(mip_serializer* seria microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_magnetometer_covariance_matrix_data(mip_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self) +void extract_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->covariance[i]); @@ -1214,13 +1214,13 @@ bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const mip { assert(ptr); mip_filter_magnetometer_covariance_matrix_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_covariance_matrix_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_magnetometer_residual_vector_data(mip_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self) +void insert_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->residual[i]); @@ -1228,7 +1228,7 @@ void insert_mip_filter_magnetometer_residual_vector_data(mip_serializer* seriali microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_magnetometer_residual_vector_data(mip_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self) +void extract_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->residual[i]); @@ -1240,13 +1240,13 @@ bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const mip_f { assert(ptr); mip_filter_magnetometer_residual_vector_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_residual_vector_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_clock_correction_data(mip_serializer* serializer, const mip_filter_clock_correction_data* self) +void insert_mip_filter_clock_correction_data(microstrain_serializer* serializer, const mip_filter_clock_correction_data* self) { microstrain_insert_u8(serializer, self->receiver_id); @@ -1257,7 +1257,7 @@ void insert_mip_filter_clock_correction_data(mip_serializer* serializer, const m microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_clock_correction_data(mip_serializer* serializer, mip_filter_clock_correction_data* self) +void extract_mip_filter_clock_correction_data(microstrain_serializer* serializer, mip_filter_clock_correction_data* self) { microstrain_extract_u8(serializer, &self->receiver_id); @@ -1272,13 +1272,13 @@ bool extract_mip_filter_clock_correction_data_from_field(const mip_field* field, { assert(ptr); mip_filter_clock_correction_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_clock_correction_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_clock_correction_uncertainty_data(mip_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self) +void insert_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self) { microstrain_insert_u8(serializer, self->receiver_id); @@ -1289,7 +1289,7 @@ void insert_mip_filter_clock_correction_uncertainty_data(mip_serializer* seriali microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_clock_correction_uncertainty_data(mip_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self) +void extract_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self) { microstrain_extract_u8(serializer, &self->receiver_id); @@ -1304,13 +1304,13 @@ bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const mip_f { assert(ptr); mip_filter_clock_correction_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_clock_correction_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gnss_pos_aid_status_data(mip_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self) +void insert_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self) { microstrain_insert_u8(serializer, self->receiver_id); @@ -1322,7 +1322,7 @@ void insert_mip_filter_gnss_pos_aid_status_data(mip_serializer* serializer, cons microstrain_insert_u8(serializer, self->reserved[i]); } -void extract_mip_filter_gnss_pos_aid_status_data(mip_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self) +void extract_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self) { microstrain_extract_u8(serializer, &self->receiver_id); @@ -1338,13 +1338,13 @@ bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const mip_field* fie { assert(ptr); mip_filter_gnss_pos_aid_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gnss_pos_aid_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gnss_att_aid_status_data(mip_serializer* serializer, const mip_filter_gnss_att_aid_status_data* self) +void insert_mip_filter_gnss_att_aid_status_data(microstrain_serializer* serializer, const mip_filter_gnss_att_aid_status_data* self) { microstrain_insert_float(serializer, self->time_of_week); @@ -1354,7 +1354,7 @@ void insert_mip_filter_gnss_att_aid_status_data(mip_serializer* serializer, cons microstrain_insert_u8(serializer, self->reserved[i]); } -void extract_mip_filter_gnss_att_aid_status_data(mip_serializer* serializer, mip_filter_gnss_att_aid_status_data* self) +void extract_mip_filter_gnss_att_aid_status_data(microstrain_serializer* serializer, mip_filter_gnss_att_aid_status_data* self) { microstrain_extract_float(serializer, &self->time_of_week); @@ -1368,13 +1368,13 @@ bool extract_mip_filter_gnss_att_aid_status_data_from_field(const mip_field* fie { assert(ptr); mip_filter_gnss_att_aid_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gnss_att_aid_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_head_aid_status_data(mip_serializer* serializer, const mip_filter_head_aid_status_data* self) +void insert_mip_filter_head_aid_status_data(microstrain_serializer* serializer, const mip_filter_head_aid_status_data* self) { microstrain_insert_float(serializer, self->time_of_week); @@ -1384,7 +1384,7 @@ void insert_mip_filter_head_aid_status_data(mip_serializer* serializer, const mi microstrain_insert_float(serializer, self->reserved[i]); } -void extract_mip_filter_head_aid_status_data(mip_serializer* serializer, mip_filter_head_aid_status_data* self) +void extract_mip_filter_head_aid_status_data(microstrain_serializer* serializer, mip_filter_head_aid_status_data* self) { microstrain_extract_float(serializer, &self->time_of_week); @@ -1398,24 +1398,24 @@ bool extract_mip_filter_head_aid_status_data_from_field(const mip_field* field, { assert(ptr); mip_filter_head_aid_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_head_aid_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_head_aid_status_data_heading_aid_type(struct mip_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self) +void insert_mip_filter_head_aid_status_data_heading_aid_type(struct microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_head_aid_status_data_heading_aid_type(struct mip_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self) +void extract_mip_filter_head_aid_status_data_heading_aid_type(struct microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_rel_pos_ned_data(mip_serializer* serializer, const mip_filter_rel_pos_ned_data* self) +void insert_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, const mip_filter_rel_pos_ned_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_double(serializer, self->relative_position[i]); @@ -1423,7 +1423,7 @@ void insert_mip_filter_rel_pos_ned_data(mip_serializer* serializer, const mip_fi microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_rel_pos_ned_data(mip_serializer* serializer, mip_filter_rel_pos_ned_data* self) +void extract_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, mip_filter_rel_pos_ned_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_double(serializer, &self->relative_position[i]); @@ -1435,13 +1435,13 @@ bool extract_mip_filter_rel_pos_ned_data_from_field(const mip_field* field, void { assert(ptr); mip_filter_rel_pos_ned_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_rel_pos_ned_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_ecef_pos_data(mip_serializer* serializer, const mip_filter_ecef_pos_data* self) +void insert_mip_filter_ecef_pos_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_double(serializer, self->position_ecef[i]); @@ -1449,7 +1449,7 @@ void insert_mip_filter_ecef_pos_data(mip_serializer* serializer, const mip_filte microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_ecef_pos_data(mip_serializer* serializer, mip_filter_ecef_pos_data* self) +void extract_mip_filter_ecef_pos_data(microstrain_serializer* serializer, mip_filter_ecef_pos_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_double(serializer, &self->position_ecef[i]); @@ -1461,13 +1461,13 @@ bool extract_mip_filter_ecef_pos_data_from_field(const mip_field* field, void* p { assert(ptr); mip_filter_ecef_pos_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_pos_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_ecef_vel_data(mip_serializer* serializer, const mip_filter_ecef_vel_data* self) +void insert_mip_filter_ecef_vel_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->velocity_ecef[i]); @@ -1475,7 +1475,7 @@ void insert_mip_filter_ecef_vel_data(mip_serializer* serializer, const mip_filte microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_ecef_vel_data(mip_serializer* serializer, mip_filter_ecef_vel_data* self) +void extract_mip_filter_ecef_vel_data(microstrain_serializer* serializer, mip_filter_ecef_vel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->velocity_ecef[i]); @@ -1487,13 +1487,13 @@ bool extract_mip_filter_ecef_vel_data_from_field(const mip_field* field, void* p { assert(ptr); mip_filter_ecef_vel_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_vel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_ecef_pos_uncertainty_data(mip_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self) +void insert_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->pos_uncertainty[i]); @@ -1501,7 +1501,7 @@ void insert_mip_filter_ecef_pos_uncertainty_data(mip_serializer* serializer, con microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_ecef_pos_uncertainty_data(mip_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self) +void extract_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->pos_uncertainty[i]); @@ -1513,13 +1513,13 @@ bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const mip_field* fi { assert(ptr); mip_filter_ecef_pos_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_pos_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_ecef_vel_uncertainty_data(mip_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self) +void insert_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->vel_uncertainty[i]); @@ -1527,7 +1527,7 @@ void insert_mip_filter_ecef_vel_uncertainty_data(mip_serializer* serializer, con microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_ecef_vel_uncertainty_data(mip_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self) +void extract_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->vel_uncertainty[i]); @@ -1539,13 +1539,13 @@ bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const mip_field* fi { assert(ptr); mip_filter_ecef_vel_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_vel_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_aiding_measurement_summary_data(mip_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self) +void insert_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self) { microstrain_insert_float(serializer, self->time_of_week); @@ -1556,7 +1556,7 @@ void insert_mip_filter_aiding_measurement_summary_data(mip_serializer* serialize insert_mip_filter_measurement_indicator(serializer, self->indicator); } -void extract_mip_filter_aiding_measurement_summary_data(mip_serializer* serializer, mip_filter_aiding_measurement_summary_data* self) +void extract_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, mip_filter_aiding_measurement_summary_data* self) { microstrain_extract_float(serializer, &self->time_of_week); @@ -1571,20 +1571,20 @@ bool extract_mip_filter_aiding_measurement_summary_data_from_field(const mip_fie { assert(ptr); mip_filter_aiding_measurement_summary_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_aiding_measurement_summary_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_odometer_scale_factor_error_data(mip_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self) +void insert_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self) { microstrain_insert_float(serializer, self->scale_factor_error); microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_odometer_scale_factor_error_data(mip_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self) +void extract_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self) { microstrain_extract_float(serializer, &self->scale_factor_error); @@ -1595,20 +1595,20 @@ bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const mip_fi { assert(ptr); mip_filter_odometer_scale_factor_error_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_odometer_scale_factor_error_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(mip_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self) +void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self) { microstrain_insert_float(serializer, self->scale_factor_error_uncertainty); microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(mip_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self) +void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self) { microstrain_extract_float(serializer, &self->scale_factor_error_uncertainty); @@ -1619,13 +1619,13 @@ bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field( { assert(ptr); mip_filter_odometer_scale_factor_error_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_odometer_scale_factor_error_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gnss_dual_antenna_status_data(mip_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self) +void insert_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self) { microstrain_insert_float(serializer, self->time_of_week); @@ -1640,7 +1640,7 @@ void insert_mip_filter_gnss_dual_antenna_status_data(mip_serializer* serializer, microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_filter_gnss_dual_antenna_status_data(mip_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self) +void extract_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self) { microstrain_extract_float(serializer, &self->time_of_week); @@ -1659,35 +1659,35 @@ bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const mip_field { assert(ptr); mip_filter_gnss_dual_antenna_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gnss_dual_antenna_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(struct mip_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self) +void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(struct mip_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self) +void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct mip_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self) +void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct mip_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self) +void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_filter_aiding_frame_config_error_data(mip_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self) +void insert_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self) { microstrain_insert_u8(serializer, self->frame_id); @@ -1698,7 +1698,7 @@ void insert_mip_filter_aiding_frame_config_error_data(mip_serializer* serializer microstrain_insert_float(serializer, self->attitude[i]); } -void extract_mip_filter_aiding_frame_config_error_data(mip_serializer* serializer, mip_filter_aiding_frame_config_error_data* self) +void extract_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_data* self) { microstrain_extract_u8(serializer, &self->frame_id); @@ -1713,13 +1713,13 @@ bool extract_mip_filter_aiding_frame_config_error_data_from_field(const mip_fiel { assert(ptr); mip_filter_aiding_frame_config_error_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_aiding_frame_config_error_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_aiding_frame_config_error_uncertainty_data(mip_serializer* serializer, const mip_filter_aiding_frame_config_error_uncertainty_data* self) +void insert_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_uncertainty_data* self) { microstrain_insert_u8(serializer, self->frame_id); @@ -1730,7 +1730,7 @@ void insert_mip_filter_aiding_frame_config_error_uncertainty_data(mip_serializer microstrain_insert_float(serializer, self->attitude_unc[i]); } -void extract_mip_filter_aiding_frame_config_error_uncertainty_data(mip_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self) +void extract_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self) { microstrain_extract_u8(serializer, &self->frame_id); @@ -1745,8 +1745,8 @@ bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(co { assert(ptr); mip_filter_aiding_frame_config_error_uncertainty_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_aiding_frame_config_error_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } diff --git a/src/mip/definitions/data_filter.h b/src/mip/definitions/data_filter.h index 8898c974b..fc251001f 100644 --- a/src/mip/definitions/data_filter.h +++ b/src/mip/definitions/data_filter.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -112,8 +112,8 @@ static const mip_filter_mode MIP_FILTER_MODE_VERT_GYRO = 2; ///< static const mip_filter_mode MIP_FILTER_MODE_AHRS = 3; ///< static const mip_filter_mode MIP_FILTER_MODE_FULL_NAV = 4; ///< -void insert_mip_filter_mode(struct mip_serializer* serializer, const mip_filter_mode self); -void extract_mip_filter_mode(struct mip_serializer* serializer, mip_filter_mode* self); +void insert_mip_filter_mode(struct microstrain_serializer* serializer, const mip_filter_mode self); +void extract_mip_filter_mode(struct microstrain_serializer* serializer, mip_filter_mode* self); typedef uint16_t mip_filter_dynamics_mode; static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GX5_PORTABLE = 1; ///< @@ -121,8 +121,8 @@ static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GX5_AUTOMOTIVE = static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GX5_AIRBORNE = 3; ///< static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GQ7_DEFAULT = 1; ///< -void insert_mip_filter_dynamics_mode(struct mip_serializer* serializer, const mip_filter_dynamics_mode self); -void extract_mip_filter_dynamics_mode(struct mip_serializer* serializer, mip_filter_dynamics_mode* self); +void insert_mip_filter_dynamics_mode(struct microstrain_serializer* serializer, const mip_filter_dynamics_mode self); +void extract_mip_filter_dynamics_mode(struct microstrain_serializer* serializer, mip_filter_dynamics_mode* self); typedef uint16_t mip_filter_status_flags; static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_NONE = 0x0000; @@ -156,8 +156,8 @@ static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_TIME_SYNC_WARNI static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_SOLUTION_ERROR = 0xF000; ///< Filter computation warning flags. If any bits 12-15 are set, and all filter outputs will be invalid. static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_ALL = 0xFFFF; -void insert_mip_filter_status_flags(struct mip_serializer* serializer, const mip_filter_status_flags self); -void extract_mip_filter_status_flags(struct mip_serializer* serializer, mip_filter_status_flags* self); +void insert_mip_filter_status_flags(struct microstrain_serializer* serializer, const mip_filter_status_flags self); +void extract_mip_filter_status_flags(struct microstrain_serializer* serializer, mip_filter_status_flags* self); typedef uint8_t mip_filter_aiding_measurement_type; static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1; ///< @@ -173,8 +173,8 @@ static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TY static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_VEHICLE_FRAME = 42; ///< static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING_TRUE = 49; ///< -void insert_mip_filter_aiding_measurement_type(struct mip_serializer* serializer, const mip_filter_aiding_measurement_type self); -void extract_mip_filter_aiding_measurement_type(struct mip_serializer* serializer, mip_filter_aiding_measurement_type* self); +void insert_mip_filter_aiding_measurement_type(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self); +void extract_mip_filter_aiding_measurement_type(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self); typedef uint8_t mip_filter_measurement_indicator; static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_NONE = 0x00; @@ -186,8 +186,8 @@ static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_C static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_MAX_NUM_MEAS_EXCEEDED = 0x20; ///< static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_ALL = 0x3F; -void insert_mip_filter_measurement_indicator(struct mip_serializer* serializer, const mip_filter_measurement_indicator self); -void extract_mip_filter_measurement_indicator(struct mip_serializer* serializer, mip_filter_measurement_indicator* self); +void insert_mip_filter_measurement_indicator(struct microstrain_serializer* serializer, const mip_filter_measurement_indicator self); +void extract_mip_filter_measurement_indicator(struct microstrain_serializer* serializer, mip_filter_measurement_indicator* self); typedef uint16_t mip_gnss_aid_status_flags; static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_NONE = 0x0000; @@ -209,8 +209,8 @@ static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_NO_FIX static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_CONFIG_ERROR = 0x8000; ///< If 1, there is likely an issue with the antenna offset for this GNSS module static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_ALL = 0xFFFF; -void insert_mip_gnss_aid_status_flags(struct mip_serializer* serializer, const mip_gnss_aid_status_flags self); -void extract_mip_gnss_aid_status_flags(struct mip_serializer* serializer, mip_gnss_aid_status_flags* self); +void insert_mip_gnss_aid_status_flags(struct microstrain_serializer* serializer, const mip_gnss_aid_status_flags self); +void extract_mip_gnss_aid_status_flags(struct microstrain_serializer* serializer, mip_gnss_aid_status_flags* self); //////////////////////////////////////////////////////////////////////////////// @@ -232,8 +232,8 @@ struct mip_filter_position_llh_data }; typedef struct mip_filter_position_llh_data mip_filter_position_llh_data; -void insert_mip_filter_position_llh_data(struct mip_serializer* serializer, const mip_filter_position_llh_data* self); -void extract_mip_filter_position_llh_data(struct mip_serializer* serializer, mip_filter_position_llh_data* self); +void insert_mip_filter_position_llh_data(struct microstrain_serializer* serializer, const mip_filter_position_llh_data* self); +void extract_mip_filter_position_llh_data(struct microstrain_serializer* serializer, mip_filter_position_llh_data* self); bool extract_mip_filter_position_llh_data_from_field(const struct mip_field* field, void* ptr); @@ -254,8 +254,8 @@ struct mip_filter_velocity_ned_data }; typedef struct mip_filter_velocity_ned_data mip_filter_velocity_ned_data; -void insert_mip_filter_velocity_ned_data(struct mip_serializer* serializer, const mip_filter_velocity_ned_data* self); -void extract_mip_filter_velocity_ned_data(struct mip_serializer* serializer, mip_filter_velocity_ned_data* self); +void insert_mip_filter_velocity_ned_data(struct microstrain_serializer* serializer, const mip_filter_velocity_ned_data* self); +void extract_mip_filter_velocity_ned_data(struct microstrain_serializer* serializer, mip_filter_velocity_ned_data* self); bool extract_mip_filter_velocity_ned_data_from_field(const struct mip_field* field, void* ptr); @@ -282,8 +282,8 @@ struct mip_filter_attitude_quaternion_data }; typedef struct mip_filter_attitude_quaternion_data mip_filter_attitude_quaternion_data; -void insert_mip_filter_attitude_quaternion_data(struct mip_serializer* serializer, const mip_filter_attitude_quaternion_data* self); -void extract_mip_filter_attitude_quaternion_data(struct mip_serializer* serializer, mip_filter_attitude_quaternion_data* self); +void insert_mip_filter_attitude_quaternion_data(struct microstrain_serializer* serializer, const mip_filter_attitude_quaternion_data* self); +void extract_mip_filter_attitude_quaternion_data(struct microstrain_serializer* serializer, mip_filter_attitude_quaternion_data* self); bool extract_mip_filter_attitude_quaternion_data_from_field(const struct mip_field* field, void* ptr); @@ -312,8 +312,8 @@ struct mip_filter_attitude_dcm_data }; typedef struct mip_filter_attitude_dcm_data mip_filter_attitude_dcm_data; -void insert_mip_filter_attitude_dcm_data(struct mip_serializer* serializer, const mip_filter_attitude_dcm_data* self); -void extract_mip_filter_attitude_dcm_data(struct mip_serializer* serializer, mip_filter_attitude_dcm_data* self); +void insert_mip_filter_attitude_dcm_data(struct microstrain_serializer* serializer, const mip_filter_attitude_dcm_data* self); +void extract_mip_filter_attitude_dcm_data(struct microstrain_serializer* serializer, mip_filter_attitude_dcm_data* self); bool extract_mip_filter_attitude_dcm_data_from_field(const struct mip_field* field, void* ptr); @@ -335,8 +335,8 @@ struct mip_filter_euler_angles_data }; typedef struct mip_filter_euler_angles_data mip_filter_euler_angles_data; -void insert_mip_filter_euler_angles_data(struct mip_serializer* serializer, const mip_filter_euler_angles_data* self); -void extract_mip_filter_euler_angles_data(struct mip_serializer* serializer, mip_filter_euler_angles_data* self); +void insert_mip_filter_euler_angles_data(struct microstrain_serializer* serializer, const mip_filter_euler_angles_data* self); +void extract_mip_filter_euler_angles_data(struct microstrain_serializer* serializer, mip_filter_euler_angles_data* self); bool extract_mip_filter_euler_angles_data_from_field(const struct mip_field* field, void* ptr); @@ -355,8 +355,8 @@ struct mip_filter_gyro_bias_data }; typedef struct mip_filter_gyro_bias_data mip_filter_gyro_bias_data; -void insert_mip_filter_gyro_bias_data(struct mip_serializer* serializer, const mip_filter_gyro_bias_data* self); -void extract_mip_filter_gyro_bias_data(struct mip_serializer* serializer, mip_filter_gyro_bias_data* self); +void insert_mip_filter_gyro_bias_data(struct microstrain_serializer* serializer, const mip_filter_gyro_bias_data* self); +void extract_mip_filter_gyro_bias_data(struct microstrain_serializer* serializer, mip_filter_gyro_bias_data* self); bool extract_mip_filter_gyro_bias_data_from_field(const struct mip_field* field, void* ptr); @@ -375,8 +375,8 @@ struct mip_filter_accel_bias_data }; typedef struct mip_filter_accel_bias_data mip_filter_accel_bias_data; -void insert_mip_filter_accel_bias_data(struct mip_serializer* serializer, const mip_filter_accel_bias_data* self); -void extract_mip_filter_accel_bias_data(struct mip_serializer* serializer, mip_filter_accel_bias_data* self); +void insert_mip_filter_accel_bias_data(struct microstrain_serializer* serializer, const mip_filter_accel_bias_data* self); +void extract_mip_filter_accel_bias_data(struct microstrain_serializer* serializer, mip_filter_accel_bias_data* self); bool extract_mip_filter_accel_bias_data_from_field(const struct mip_field* field, void* ptr); @@ -397,8 +397,8 @@ struct mip_filter_position_llh_uncertainty_data }; typedef struct mip_filter_position_llh_uncertainty_data mip_filter_position_llh_uncertainty_data; -void insert_mip_filter_position_llh_uncertainty_data(struct mip_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self); -void extract_mip_filter_position_llh_uncertainty_data(struct mip_serializer* serializer, mip_filter_position_llh_uncertainty_data* self); +void insert_mip_filter_position_llh_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self); +void extract_mip_filter_position_llh_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_position_llh_uncertainty_data* self); bool extract_mip_filter_position_llh_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -419,8 +419,8 @@ struct mip_filter_velocity_ned_uncertainty_data }; typedef struct mip_filter_velocity_ned_uncertainty_data mip_filter_velocity_ned_uncertainty_data; -void insert_mip_filter_velocity_ned_uncertainty_data(struct mip_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self); -void extract_mip_filter_velocity_ned_uncertainty_data(struct mip_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self); +void insert_mip_filter_velocity_ned_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self); +void extract_mip_filter_velocity_ned_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self); bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -442,8 +442,8 @@ struct mip_filter_euler_angles_uncertainty_data }; typedef struct mip_filter_euler_angles_uncertainty_data mip_filter_euler_angles_uncertainty_data; -void insert_mip_filter_euler_angles_uncertainty_data(struct mip_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self); -void extract_mip_filter_euler_angles_uncertainty_data(struct mip_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self); +void insert_mip_filter_euler_angles_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self); +void extract_mip_filter_euler_angles_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self); bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -462,8 +462,8 @@ struct mip_filter_gyro_bias_uncertainty_data }; typedef struct mip_filter_gyro_bias_uncertainty_data mip_filter_gyro_bias_uncertainty_data; -void insert_mip_filter_gyro_bias_uncertainty_data(struct mip_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self); -void extract_mip_filter_gyro_bias_uncertainty_data(struct mip_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self); +void insert_mip_filter_gyro_bias_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self); +void extract_mip_filter_gyro_bias_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self); bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -482,8 +482,8 @@ struct mip_filter_accel_bias_uncertainty_data }; typedef struct mip_filter_accel_bias_uncertainty_data mip_filter_accel_bias_uncertainty_data; -void insert_mip_filter_accel_bias_uncertainty_data(struct mip_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self); -void extract_mip_filter_accel_bias_uncertainty_data(struct mip_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self); +void insert_mip_filter_accel_bias_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self); +void extract_mip_filter_accel_bias_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self); bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -509,8 +509,8 @@ struct mip_filter_timestamp_data }; typedef struct mip_filter_timestamp_data mip_filter_timestamp_data; -void insert_mip_filter_timestamp_data(struct mip_serializer* serializer, const mip_filter_timestamp_data* self); -void extract_mip_filter_timestamp_data(struct mip_serializer* serializer, mip_filter_timestamp_data* self); +void insert_mip_filter_timestamp_data(struct microstrain_serializer* serializer, const mip_filter_timestamp_data* self); +void extract_mip_filter_timestamp_data(struct microstrain_serializer* serializer, mip_filter_timestamp_data* self); bool extract_mip_filter_timestamp_data_from_field(const struct mip_field* field, void* ptr); @@ -530,8 +530,8 @@ struct mip_filter_status_data }; typedef struct mip_filter_status_data mip_filter_status_data; -void insert_mip_filter_status_data(struct mip_serializer* serializer, const mip_filter_status_data* self); -void extract_mip_filter_status_data(struct mip_serializer* serializer, mip_filter_status_data* self); +void insert_mip_filter_status_data(struct microstrain_serializer* serializer, const mip_filter_status_data* self); +void extract_mip_filter_status_data(struct microstrain_serializer* serializer, mip_filter_status_data* self); bool extract_mip_filter_status_data_from_field(const struct mip_field* field, void* ptr); @@ -551,8 +551,8 @@ struct mip_filter_linear_accel_data }; typedef struct mip_filter_linear_accel_data mip_filter_linear_accel_data; -void insert_mip_filter_linear_accel_data(struct mip_serializer* serializer, const mip_filter_linear_accel_data* self); -void extract_mip_filter_linear_accel_data(struct mip_serializer* serializer, mip_filter_linear_accel_data* self); +void insert_mip_filter_linear_accel_data(struct microstrain_serializer* serializer, const mip_filter_linear_accel_data* self); +void extract_mip_filter_linear_accel_data(struct microstrain_serializer* serializer, mip_filter_linear_accel_data* self); bool extract_mip_filter_linear_accel_data_from_field(const struct mip_field* field, void* ptr); @@ -571,8 +571,8 @@ struct mip_filter_gravity_vector_data }; typedef struct mip_filter_gravity_vector_data mip_filter_gravity_vector_data; -void insert_mip_filter_gravity_vector_data(struct mip_serializer* serializer, const mip_filter_gravity_vector_data* self); -void extract_mip_filter_gravity_vector_data(struct mip_serializer* serializer, mip_filter_gravity_vector_data* self); +void insert_mip_filter_gravity_vector_data(struct microstrain_serializer* serializer, const mip_filter_gravity_vector_data* self); +void extract_mip_filter_gravity_vector_data(struct microstrain_serializer* serializer, mip_filter_gravity_vector_data* self); bool extract_mip_filter_gravity_vector_data_from_field(const struct mip_field* field, void* ptr); @@ -591,8 +591,8 @@ struct mip_filter_comp_accel_data }; typedef struct mip_filter_comp_accel_data mip_filter_comp_accel_data; -void insert_mip_filter_comp_accel_data(struct mip_serializer* serializer, const mip_filter_comp_accel_data* self); -void extract_mip_filter_comp_accel_data(struct mip_serializer* serializer, mip_filter_comp_accel_data* self); +void insert_mip_filter_comp_accel_data(struct microstrain_serializer* serializer, const mip_filter_comp_accel_data* self); +void extract_mip_filter_comp_accel_data(struct microstrain_serializer* serializer, mip_filter_comp_accel_data* self); bool extract_mip_filter_comp_accel_data_from_field(const struct mip_field* field, void* ptr); @@ -611,8 +611,8 @@ struct mip_filter_comp_angular_rate_data }; typedef struct mip_filter_comp_angular_rate_data mip_filter_comp_angular_rate_data; -void insert_mip_filter_comp_angular_rate_data(struct mip_serializer* serializer, const mip_filter_comp_angular_rate_data* self); -void extract_mip_filter_comp_angular_rate_data(struct mip_serializer* serializer, mip_filter_comp_angular_rate_data* self); +void insert_mip_filter_comp_angular_rate_data(struct microstrain_serializer* serializer, const mip_filter_comp_angular_rate_data* self); +void extract_mip_filter_comp_angular_rate_data(struct microstrain_serializer* serializer, mip_filter_comp_angular_rate_data* self); bool extract_mip_filter_comp_angular_rate_data_from_field(const struct mip_field* field, void* ptr); @@ -631,8 +631,8 @@ struct mip_filter_quaternion_attitude_uncertainty_data }; typedef struct mip_filter_quaternion_attitude_uncertainty_data mip_filter_quaternion_attitude_uncertainty_data; -void insert_mip_filter_quaternion_attitude_uncertainty_data(struct mip_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self); -void extract_mip_filter_quaternion_attitude_uncertainty_data(struct mip_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self); +void insert_mip_filter_quaternion_attitude_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self); +void extract_mip_filter_quaternion_attitude_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self); bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -651,8 +651,8 @@ struct mip_filter_wgs84_gravity_mag_data }; typedef struct mip_filter_wgs84_gravity_mag_data mip_filter_wgs84_gravity_mag_data; -void insert_mip_filter_wgs84_gravity_mag_data(struct mip_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self); -void extract_mip_filter_wgs84_gravity_mag_data(struct mip_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self); +void insert_mip_filter_wgs84_gravity_mag_data(struct microstrain_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self); +void extract_mip_filter_wgs84_gravity_mag_data(struct microstrain_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self); bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const struct mip_field* field, void* ptr); @@ -683,12 +683,12 @@ struct mip_filter_heading_update_state_data }; typedef struct mip_filter_heading_update_state_data mip_filter_heading_update_state_data; -void insert_mip_filter_heading_update_state_data(struct mip_serializer* serializer, const mip_filter_heading_update_state_data* self); -void extract_mip_filter_heading_update_state_data(struct mip_serializer* serializer, mip_filter_heading_update_state_data* self); +void insert_mip_filter_heading_update_state_data(struct microstrain_serializer* serializer, const mip_filter_heading_update_state_data* self); +void extract_mip_filter_heading_update_state_data(struct microstrain_serializer* serializer, mip_filter_heading_update_state_data* self); bool extract_mip_filter_heading_update_state_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_filter_heading_update_state_data_heading_source(struct mip_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self); -void extract_mip_filter_heading_update_state_data_heading_source(struct mip_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self); +void insert_mip_filter_heading_update_state_data_heading_source(struct microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self); +void extract_mip_filter_heading_update_state_data_heading_source(struct microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self); ///@} @@ -711,8 +711,8 @@ struct mip_filter_magnetic_model_data }; typedef struct mip_filter_magnetic_model_data mip_filter_magnetic_model_data; -void insert_mip_filter_magnetic_model_data(struct mip_serializer* serializer, const mip_filter_magnetic_model_data* self); -void extract_mip_filter_magnetic_model_data(struct mip_serializer* serializer, mip_filter_magnetic_model_data* self); +void insert_mip_filter_magnetic_model_data(struct microstrain_serializer* serializer, const mip_filter_magnetic_model_data* self); +void extract_mip_filter_magnetic_model_data(struct microstrain_serializer* serializer, mip_filter_magnetic_model_data* self); bool extract_mip_filter_magnetic_model_data_from_field(const struct mip_field* field, void* ptr); @@ -731,8 +731,8 @@ struct mip_filter_accel_scale_factor_data }; typedef struct mip_filter_accel_scale_factor_data mip_filter_accel_scale_factor_data; -void insert_mip_filter_accel_scale_factor_data(struct mip_serializer* serializer, const mip_filter_accel_scale_factor_data* self); -void extract_mip_filter_accel_scale_factor_data(struct mip_serializer* serializer, mip_filter_accel_scale_factor_data* self); +void insert_mip_filter_accel_scale_factor_data(struct microstrain_serializer* serializer, const mip_filter_accel_scale_factor_data* self); +void extract_mip_filter_accel_scale_factor_data(struct microstrain_serializer* serializer, mip_filter_accel_scale_factor_data* self); bool extract_mip_filter_accel_scale_factor_data_from_field(const struct mip_field* field, void* ptr); @@ -751,8 +751,8 @@ struct mip_filter_accel_scale_factor_uncertainty_data }; typedef struct mip_filter_accel_scale_factor_uncertainty_data mip_filter_accel_scale_factor_uncertainty_data; -void insert_mip_filter_accel_scale_factor_uncertainty_data(struct mip_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self); -void extract_mip_filter_accel_scale_factor_uncertainty_data(struct mip_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self); +void insert_mip_filter_accel_scale_factor_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self); +void extract_mip_filter_accel_scale_factor_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self); bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -771,8 +771,8 @@ struct mip_filter_gyro_scale_factor_data }; typedef struct mip_filter_gyro_scale_factor_data mip_filter_gyro_scale_factor_data; -void insert_mip_filter_gyro_scale_factor_data(struct mip_serializer* serializer, const mip_filter_gyro_scale_factor_data* self); -void extract_mip_filter_gyro_scale_factor_data(struct mip_serializer* serializer, mip_filter_gyro_scale_factor_data* self); +void insert_mip_filter_gyro_scale_factor_data(struct microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_data* self); +void extract_mip_filter_gyro_scale_factor_data(struct microstrain_serializer* serializer, mip_filter_gyro_scale_factor_data* self); bool extract_mip_filter_gyro_scale_factor_data_from_field(const struct mip_field* field, void* ptr); @@ -791,8 +791,8 @@ struct mip_filter_gyro_scale_factor_uncertainty_data }; typedef struct mip_filter_gyro_scale_factor_uncertainty_data mip_filter_gyro_scale_factor_uncertainty_data; -void insert_mip_filter_gyro_scale_factor_uncertainty_data(struct mip_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self); -void extract_mip_filter_gyro_scale_factor_uncertainty_data(struct mip_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self); +void insert_mip_filter_gyro_scale_factor_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self); +void extract_mip_filter_gyro_scale_factor_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self); bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -811,8 +811,8 @@ struct mip_filter_mag_bias_data }; typedef struct mip_filter_mag_bias_data mip_filter_mag_bias_data; -void insert_mip_filter_mag_bias_data(struct mip_serializer* serializer, const mip_filter_mag_bias_data* self); -void extract_mip_filter_mag_bias_data(struct mip_serializer* serializer, mip_filter_mag_bias_data* self); +void insert_mip_filter_mag_bias_data(struct microstrain_serializer* serializer, const mip_filter_mag_bias_data* self); +void extract_mip_filter_mag_bias_data(struct microstrain_serializer* serializer, mip_filter_mag_bias_data* self); bool extract_mip_filter_mag_bias_data_from_field(const struct mip_field* field, void* ptr); @@ -831,8 +831,8 @@ struct mip_filter_mag_bias_uncertainty_data }; typedef struct mip_filter_mag_bias_uncertainty_data mip_filter_mag_bias_uncertainty_data; -void insert_mip_filter_mag_bias_uncertainty_data(struct mip_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self); -void extract_mip_filter_mag_bias_uncertainty_data(struct mip_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self); +void insert_mip_filter_mag_bias_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self); +void extract_mip_filter_mag_bias_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self); bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -857,8 +857,8 @@ struct mip_filter_standard_atmosphere_data }; typedef struct mip_filter_standard_atmosphere_data mip_filter_standard_atmosphere_data; -void insert_mip_filter_standard_atmosphere_data(struct mip_serializer* serializer, const mip_filter_standard_atmosphere_data* self); -void extract_mip_filter_standard_atmosphere_data(struct mip_serializer* serializer, mip_filter_standard_atmosphere_data* self); +void insert_mip_filter_standard_atmosphere_data(struct microstrain_serializer* serializer, const mip_filter_standard_atmosphere_data* self); +void extract_mip_filter_standard_atmosphere_data(struct microstrain_serializer* serializer, mip_filter_standard_atmosphere_data* self); bool extract_mip_filter_standard_atmosphere_data_from_field(const struct mip_field* field, void* ptr); @@ -881,8 +881,8 @@ struct mip_filter_pressure_altitude_data }; typedef struct mip_filter_pressure_altitude_data mip_filter_pressure_altitude_data; -void insert_mip_filter_pressure_altitude_data(struct mip_serializer* serializer, const mip_filter_pressure_altitude_data* self); -void extract_mip_filter_pressure_altitude_data(struct mip_serializer* serializer, mip_filter_pressure_altitude_data* self); +void insert_mip_filter_pressure_altitude_data(struct microstrain_serializer* serializer, const mip_filter_pressure_altitude_data* self); +void extract_mip_filter_pressure_altitude_data(struct microstrain_serializer* serializer, mip_filter_pressure_altitude_data* self); bool extract_mip_filter_pressure_altitude_data_from_field(const struct mip_field* field, void* ptr); @@ -900,8 +900,8 @@ struct mip_filter_density_altitude_data }; typedef struct mip_filter_density_altitude_data mip_filter_density_altitude_data; -void insert_mip_filter_density_altitude_data(struct mip_serializer* serializer, const mip_filter_density_altitude_data* self); -void extract_mip_filter_density_altitude_data(struct mip_serializer* serializer, mip_filter_density_altitude_data* self); +void insert_mip_filter_density_altitude_data(struct microstrain_serializer* serializer, const mip_filter_density_altitude_data* self); +void extract_mip_filter_density_altitude_data(struct microstrain_serializer* serializer, mip_filter_density_altitude_data* self); bool extract_mip_filter_density_altitude_data_from_field(const struct mip_field* field, void* ptr); @@ -922,8 +922,8 @@ struct mip_filter_antenna_offset_correction_data }; typedef struct mip_filter_antenna_offset_correction_data mip_filter_antenna_offset_correction_data; -void insert_mip_filter_antenna_offset_correction_data(struct mip_serializer* serializer, const mip_filter_antenna_offset_correction_data* self); -void extract_mip_filter_antenna_offset_correction_data(struct mip_serializer* serializer, mip_filter_antenna_offset_correction_data* self); +void insert_mip_filter_antenna_offset_correction_data(struct microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_data* self); +void extract_mip_filter_antenna_offset_correction_data(struct microstrain_serializer* serializer, mip_filter_antenna_offset_correction_data* self); bool extract_mip_filter_antenna_offset_correction_data_from_field(const struct mip_field* field, void* ptr); @@ -942,8 +942,8 @@ struct mip_filter_antenna_offset_correction_uncertainty_data }; typedef struct mip_filter_antenna_offset_correction_uncertainty_data mip_filter_antenna_offset_correction_uncertainty_data; -void insert_mip_filter_antenna_offset_correction_uncertainty_data(struct mip_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self); -void extract_mip_filter_antenna_offset_correction_uncertainty_data(struct mip_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self); +void insert_mip_filter_antenna_offset_correction_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self); +void extract_mip_filter_antenna_offset_correction_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self); bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -965,8 +965,8 @@ struct mip_filter_multi_antenna_offset_correction_data }; typedef struct mip_filter_multi_antenna_offset_correction_data mip_filter_multi_antenna_offset_correction_data; -void insert_mip_filter_multi_antenna_offset_correction_data(struct mip_serializer* serializer, const mip_filter_multi_antenna_offset_correction_data* self); -void extract_mip_filter_multi_antenna_offset_correction_data(struct mip_serializer* serializer, mip_filter_multi_antenna_offset_correction_data* self); +void insert_mip_filter_multi_antenna_offset_correction_data(struct microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_data* self); +void extract_mip_filter_multi_antenna_offset_correction_data(struct microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_data* self); bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const struct mip_field* field, void* ptr); @@ -986,8 +986,8 @@ struct mip_filter_multi_antenna_offset_correction_uncertainty_data }; typedef struct mip_filter_multi_antenna_offset_correction_uncertainty_data mip_filter_multi_antenna_offset_correction_uncertainty_data; -void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(struct mip_serializer* serializer, const mip_filter_multi_antenna_offset_correction_uncertainty_data* self); -void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(struct mip_serializer* serializer, mip_filter_multi_antenna_offset_correction_uncertainty_data* self); +void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_uncertainty_data* self); +void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_uncertainty_data* self); bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1008,8 +1008,8 @@ struct mip_filter_magnetometer_offset_data }; typedef struct mip_filter_magnetometer_offset_data mip_filter_magnetometer_offset_data; -void insert_mip_filter_magnetometer_offset_data(struct mip_serializer* serializer, const mip_filter_magnetometer_offset_data* self); -void extract_mip_filter_magnetometer_offset_data(struct mip_serializer* serializer, mip_filter_magnetometer_offset_data* self); +void insert_mip_filter_magnetometer_offset_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_offset_data* self); +void extract_mip_filter_magnetometer_offset_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_offset_data* self); bool extract_mip_filter_magnetometer_offset_data_from_field(const struct mip_field* field, void* ptr); @@ -1030,8 +1030,8 @@ struct mip_filter_magnetometer_matrix_data }; typedef struct mip_filter_magnetometer_matrix_data mip_filter_magnetometer_matrix_data; -void insert_mip_filter_magnetometer_matrix_data(struct mip_serializer* serializer, const mip_filter_magnetometer_matrix_data* self); -void extract_mip_filter_magnetometer_matrix_data(struct mip_serializer* serializer, mip_filter_magnetometer_matrix_data* self); +void insert_mip_filter_magnetometer_matrix_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_data* self); +void extract_mip_filter_magnetometer_matrix_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_matrix_data* self); bool extract_mip_filter_magnetometer_matrix_data_from_field(const struct mip_field* field, void* ptr); @@ -1050,8 +1050,8 @@ struct mip_filter_magnetometer_offset_uncertainty_data }; typedef struct mip_filter_magnetometer_offset_uncertainty_data mip_filter_magnetometer_offset_uncertainty_data; -void insert_mip_filter_magnetometer_offset_uncertainty_data(struct mip_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self); -void extract_mip_filter_magnetometer_offset_uncertainty_data(struct mip_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self); +void insert_mip_filter_magnetometer_offset_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self); +void extract_mip_filter_magnetometer_offset_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self); bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1070,8 +1070,8 @@ struct mip_filter_magnetometer_matrix_uncertainty_data }; typedef struct mip_filter_magnetometer_matrix_uncertainty_data mip_filter_magnetometer_matrix_uncertainty_data; -void insert_mip_filter_magnetometer_matrix_uncertainty_data(struct mip_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self); -void extract_mip_filter_magnetometer_matrix_uncertainty_data(struct mip_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self); +void insert_mip_filter_magnetometer_matrix_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self); +void extract_mip_filter_magnetometer_matrix_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self); bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1089,8 +1089,8 @@ struct mip_filter_magnetometer_covariance_matrix_data }; typedef struct mip_filter_magnetometer_covariance_matrix_data mip_filter_magnetometer_covariance_matrix_data; -void insert_mip_filter_magnetometer_covariance_matrix_data(struct mip_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self); -void extract_mip_filter_magnetometer_covariance_matrix_data(struct mip_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self); +void insert_mip_filter_magnetometer_covariance_matrix_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self); +void extract_mip_filter_magnetometer_covariance_matrix_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self); bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const struct mip_field* field, void* ptr); @@ -1109,8 +1109,8 @@ struct mip_filter_magnetometer_residual_vector_data }; typedef struct mip_filter_magnetometer_residual_vector_data mip_filter_magnetometer_residual_vector_data; -void insert_mip_filter_magnetometer_residual_vector_data(struct mip_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self); -void extract_mip_filter_magnetometer_residual_vector_data(struct mip_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self); +void insert_mip_filter_magnetometer_residual_vector_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self); +void extract_mip_filter_magnetometer_residual_vector_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self); bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const struct mip_field* field, void* ptr); @@ -1131,8 +1131,8 @@ struct mip_filter_clock_correction_data }; typedef struct mip_filter_clock_correction_data mip_filter_clock_correction_data; -void insert_mip_filter_clock_correction_data(struct mip_serializer* serializer, const mip_filter_clock_correction_data* self); -void extract_mip_filter_clock_correction_data(struct mip_serializer* serializer, mip_filter_clock_correction_data* self); +void insert_mip_filter_clock_correction_data(struct microstrain_serializer* serializer, const mip_filter_clock_correction_data* self); +void extract_mip_filter_clock_correction_data(struct microstrain_serializer* serializer, mip_filter_clock_correction_data* self); bool extract_mip_filter_clock_correction_data_from_field(const struct mip_field* field, void* ptr); @@ -1153,8 +1153,8 @@ struct mip_filter_clock_correction_uncertainty_data }; typedef struct mip_filter_clock_correction_uncertainty_data mip_filter_clock_correction_uncertainty_data; -void insert_mip_filter_clock_correction_uncertainty_data(struct mip_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self); -void extract_mip_filter_clock_correction_uncertainty_data(struct mip_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self); +void insert_mip_filter_clock_correction_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self); +void extract_mip_filter_clock_correction_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self); bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1175,8 +1175,8 @@ struct mip_filter_gnss_pos_aid_status_data }; typedef struct mip_filter_gnss_pos_aid_status_data mip_filter_gnss_pos_aid_status_data; -void insert_mip_filter_gnss_pos_aid_status_data(struct mip_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self); -void extract_mip_filter_gnss_pos_aid_status_data(struct mip_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self); +void insert_mip_filter_gnss_pos_aid_status_data(struct microstrain_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self); +void extract_mip_filter_gnss_pos_aid_status_data(struct microstrain_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self); bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const struct mip_field* field, void* ptr); @@ -1196,8 +1196,8 @@ struct mip_filter_gnss_att_aid_status_data }; typedef struct mip_filter_gnss_att_aid_status_data mip_filter_gnss_att_aid_status_data; -void insert_mip_filter_gnss_att_aid_status_data(struct mip_serializer* serializer, const mip_filter_gnss_att_aid_status_data* self); -void extract_mip_filter_gnss_att_aid_status_data(struct mip_serializer* serializer, mip_filter_gnss_att_aid_status_data* self); +void insert_mip_filter_gnss_att_aid_status_data(struct microstrain_serializer* serializer, const mip_filter_gnss_att_aid_status_data* self); +void extract_mip_filter_gnss_att_aid_status_data(struct microstrain_serializer* serializer, mip_filter_gnss_att_aid_status_data* self); bool extract_mip_filter_gnss_att_aid_status_data_from_field(const struct mip_field* field, void* ptr); @@ -1221,12 +1221,12 @@ struct mip_filter_head_aid_status_data }; typedef struct mip_filter_head_aid_status_data mip_filter_head_aid_status_data; -void insert_mip_filter_head_aid_status_data(struct mip_serializer* serializer, const mip_filter_head_aid_status_data* self); -void extract_mip_filter_head_aid_status_data(struct mip_serializer* serializer, mip_filter_head_aid_status_data* self); +void insert_mip_filter_head_aid_status_data(struct microstrain_serializer* serializer, const mip_filter_head_aid_status_data* self); +void extract_mip_filter_head_aid_status_data(struct microstrain_serializer* serializer, mip_filter_head_aid_status_data* self); bool extract_mip_filter_head_aid_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_filter_head_aid_status_data_heading_aid_type(struct mip_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self); -void extract_mip_filter_head_aid_status_data_heading_aid_type(struct mip_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self); +void insert_mip_filter_head_aid_status_data_heading_aid_type(struct microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self); +void extract_mip_filter_head_aid_status_data_heading_aid_type(struct microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self); ///@} @@ -1244,8 +1244,8 @@ struct mip_filter_rel_pos_ned_data }; typedef struct mip_filter_rel_pos_ned_data mip_filter_rel_pos_ned_data; -void insert_mip_filter_rel_pos_ned_data(struct mip_serializer* serializer, const mip_filter_rel_pos_ned_data* self); -void extract_mip_filter_rel_pos_ned_data(struct mip_serializer* serializer, mip_filter_rel_pos_ned_data* self); +void insert_mip_filter_rel_pos_ned_data(struct microstrain_serializer* serializer, const mip_filter_rel_pos_ned_data* self); +void extract_mip_filter_rel_pos_ned_data(struct microstrain_serializer* serializer, mip_filter_rel_pos_ned_data* self); bool extract_mip_filter_rel_pos_ned_data_from_field(const struct mip_field* field, void* ptr); @@ -1264,8 +1264,8 @@ struct mip_filter_ecef_pos_data }; typedef struct mip_filter_ecef_pos_data mip_filter_ecef_pos_data; -void insert_mip_filter_ecef_pos_data(struct mip_serializer* serializer, const mip_filter_ecef_pos_data* self); -void extract_mip_filter_ecef_pos_data(struct mip_serializer* serializer, mip_filter_ecef_pos_data* self); +void insert_mip_filter_ecef_pos_data(struct microstrain_serializer* serializer, const mip_filter_ecef_pos_data* self); +void extract_mip_filter_ecef_pos_data(struct microstrain_serializer* serializer, mip_filter_ecef_pos_data* self); bool extract_mip_filter_ecef_pos_data_from_field(const struct mip_field* field, void* ptr); @@ -1284,8 +1284,8 @@ struct mip_filter_ecef_vel_data }; typedef struct mip_filter_ecef_vel_data mip_filter_ecef_vel_data; -void insert_mip_filter_ecef_vel_data(struct mip_serializer* serializer, const mip_filter_ecef_vel_data* self); -void extract_mip_filter_ecef_vel_data(struct mip_serializer* serializer, mip_filter_ecef_vel_data* self); +void insert_mip_filter_ecef_vel_data(struct microstrain_serializer* serializer, const mip_filter_ecef_vel_data* self); +void extract_mip_filter_ecef_vel_data(struct microstrain_serializer* serializer, mip_filter_ecef_vel_data* self); bool extract_mip_filter_ecef_vel_data_from_field(const struct mip_field* field, void* ptr); @@ -1304,8 +1304,8 @@ struct mip_filter_ecef_pos_uncertainty_data }; typedef struct mip_filter_ecef_pos_uncertainty_data mip_filter_ecef_pos_uncertainty_data; -void insert_mip_filter_ecef_pos_uncertainty_data(struct mip_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self); -void extract_mip_filter_ecef_pos_uncertainty_data(struct mip_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self); +void insert_mip_filter_ecef_pos_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self); +void extract_mip_filter_ecef_pos_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self); bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1324,8 +1324,8 @@ struct mip_filter_ecef_vel_uncertainty_data }; typedef struct mip_filter_ecef_vel_uncertainty_data mip_filter_ecef_vel_uncertainty_data; -void insert_mip_filter_ecef_vel_uncertainty_data(struct mip_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self); -void extract_mip_filter_ecef_vel_uncertainty_data(struct mip_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self); +void insert_mip_filter_ecef_vel_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self); +void extract_mip_filter_ecef_vel_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self); bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1346,8 +1346,8 @@ struct mip_filter_aiding_measurement_summary_data }; typedef struct mip_filter_aiding_measurement_summary_data mip_filter_aiding_measurement_summary_data; -void insert_mip_filter_aiding_measurement_summary_data(struct mip_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self); -void extract_mip_filter_aiding_measurement_summary_data(struct mip_serializer* serializer, mip_filter_aiding_measurement_summary_data* self); +void insert_mip_filter_aiding_measurement_summary_data(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self); +void extract_mip_filter_aiding_measurement_summary_data(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_summary_data* self); bool extract_mip_filter_aiding_measurement_summary_data_from_field(const struct mip_field* field, void* ptr); @@ -1366,8 +1366,8 @@ struct mip_filter_odometer_scale_factor_error_data }; typedef struct mip_filter_odometer_scale_factor_error_data mip_filter_odometer_scale_factor_error_data; -void insert_mip_filter_odometer_scale_factor_error_data(struct mip_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self); -void extract_mip_filter_odometer_scale_factor_error_data(struct mip_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self); +void insert_mip_filter_odometer_scale_factor_error_data(struct microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self); +void extract_mip_filter_odometer_scale_factor_error_data(struct microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self); bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const struct mip_field* field, void* ptr); @@ -1386,8 +1386,8 @@ struct mip_filter_odometer_scale_factor_error_uncertainty_data }; typedef struct mip_filter_odometer_scale_factor_error_uncertainty_data mip_filter_odometer_scale_factor_error_uncertainty_data; -void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(struct mip_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self); -void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(struct mip_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self); +void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self); +void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self); bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1422,15 +1422,15 @@ struct mip_filter_gnss_dual_antenna_status_data }; typedef struct mip_filter_gnss_dual_antenna_status_data mip_filter_gnss_dual_antenna_status_data; -void insert_mip_filter_gnss_dual_antenna_status_data(struct mip_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self); -void extract_mip_filter_gnss_dual_antenna_status_data(struct mip_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self); +void insert_mip_filter_gnss_dual_antenna_status_data(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self); +void extract_mip_filter_gnss_dual_antenna_status_data(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self); bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(struct mip_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self); -void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(struct mip_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self); +void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self); +void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self); -void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct mip_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self); -void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct mip_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self); +void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self); +void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self); ///@} @@ -1451,8 +1451,8 @@ struct mip_filter_aiding_frame_config_error_data }; typedef struct mip_filter_aiding_frame_config_error_data mip_filter_aiding_frame_config_error_data; -void insert_mip_filter_aiding_frame_config_error_data(struct mip_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self); -void extract_mip_filter_aiding_frame_config_error_data(struct mip_serializer* serializer, mip_filter_aiding_frame_config_error_data* self); +void insert_mip_filter_aiding_frame_config_error_data(struct microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self); +void extract_mip_filter_aiding_frame_config_error_data(struct microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_data* self); bool extract_mip_filter_aiding_frame_config_error_data_from_field(const struct mip_field* field, void* ptr); @@ -1474,8 +1474,8 @@ struct mip_filter_aiding_frame_config_error_uncertainty_data }; typedef struct mip_filter_aiding_frame_config_error_uncertainty_data mip_filter_aiding_frame_config_error_uncertainty_data; -void insert_mip_filter_aiding_frame_config_error_uncertainty_data(struct mip_serializer* serializer, const mip_filter_aiding_frame_config_error_uncertainty_data* self); -void extract_mip_filter_aiding_frame_config_error_uncertainty_data(struct mip_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self); +void insert_mip_filter_aiding_frame_config_error_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_uncertainty_data* self); +void extract_mip_filter_aiding_frame_config_error_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self); bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const struct mip_field* field, void* ptr); diff --git a/src/mip/definitions/data_gnss.c b/src/mip/definitions/data_gnss.c index 7849b677b..e30aa5123 100644 --- a/src/mip/definitions/data_gnss.c +++ b/src/mip/definitions/data_gnss.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -22,33 +22,33 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_gnss_constellation_id(struct mip_serializer* serializer, const mip_gnss_constellation_id self) +void insert_mip_gnss_constellation_id(struct microstrain_serializer* serializer, const mip_gnss_constellation_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_constellation_id(struct mip_serializer* serializer, mip_gnss_constellation_id* self) +void extract_mip_gnss_constellation_id(struct microstrain_serializer* serializer, mip_gnss_constellation_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_signal_id(struct mip_serializer* serializer, const mip_gnss_signal_id self) +void insert_mip_gnss_signal_id(struct microstrain_serializer* serializer, const mip_gnss_signal_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_signal_id(struct mip_serializer* serializer, mip_gnss_signal_id* self) +void extract_mip_gnss_signal_id(struct microstrain_serializer* serializer, mip_gnss_signal_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_sbas_system(struct mip_serializer* serializer, const mip_sbas_system self) +void insert_mip_sbas_system(struct microstrain_serializer* serializer, const mip_sbas_system self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_sbas_system(struct mip_serializer* serializer, mip_sbas_system* self) +void extract_mip_sbas_system(struct microstrain_serializer* serializer, mip_sbas_system* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -60,7 +60,7 @@ void extract_mip_sbas_system(struct mip_serializer* serializer, mip_sbas_system* // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_gnss_pos_llh_data(mip_serializer* serializer, const mip_gnss_pos_llh_data* self) +void insert_mip_gnss_pos_llh_data(microstrain_serializer* serializer, const mip_gnss_pos_llh_data* self) { microstrain_insert_double(serializer, self->latitude); @@ -77,7 +77,7 @@ void insert_mip_gnss_pos_llh_data(mip_serializer* serializer, const mip_gnss_pos insert_mip_gnss_pos_llh_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_pos_llh_data(mip_serializer* serializer, mip_gnss_pos_llh_data* self) +void extract_mip_gnss_pos_llh_data(microstrain_serializer* serializer, mip_gnss_pos_llh_data* self) { microstrain_extract_double(serializer, &self->latitude); @@ -98,24 +98,24 @@ bool extract_mip_gnss_pos_llh_data_from_field(const mip_field* field, void* ptr) { assert(ptr); mip_gnss_pos_llh_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_pos_llh_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_pos_llh_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self) +void insert_mip_gnss_pos_llh_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_pos_llh_data_valid_flags(struct mip_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self) +void extract_mip_gnss_pos_llh_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_pos_ecef_data(mip_serializer* serializer, const mip_gnss_pos_ecef_data* self) +void insert_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_double(serializer, self->x[i]); @@ -125,7 +125,7 @@ void insert_mip_gnss_pos_ecef_data(mip_serializer* serializer, const mip_gnss_po insert_mip_gnss_pos_ecef_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_pos_ecef_data(mip_serializer* serializer, mip_gnss_pos_ecef_data* self) +void extract_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, mip_gnss_pos_ecef_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_double(serializer, &self->x[i]); @@ -139,24 +139,24 @@ bool extract_mip_gnss_pos_ecef_data_from_field(const mip_field* field, void* ptr { assert(ptr); mip_gnss_pos_ecef_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_pos_ecef_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_pos_ecef_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self) +void insert_mip_gnss_pos_ecef_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_pos_ecef_data_valid_flags(struct mip_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self) +void extract_mip_gnss_pos_ecef_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_vel_ned_data(mip_serializer* serializer, const mip_gnss_vel_ned_data* self) +void insert_mip_gnss_vel_ned_data(microstrain_serializer* serializer, const mip_gnss_vel_ned_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->v[i]); @@ -174,7 +174,7 @@ void insert_mip_gnss_vel_ned_data(mip_serializer* serializer, const mip_gnss_vel insert_mip_gnss_vel_ned_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_vel_ned_data(mip_serializer* serializer, mip_gnss_vel_ned_data* self) +void extract_mip_gnss_vel_ned_data(microstrain_serializer* serializer, mip_gnss_vel_ned_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->v[i]); @@ -196,24 +196,24 @@ bool extract_mip_gnss_vel_ned_data_from_field(const mip_field* field, void* ptr) { assert(ptr); mip_gnss_vel_ned_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_vel_ned_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_vel_ned_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self) +void insert_mip_gnss_vel_ned_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_vel_ned_data_valid_flags(struct mip_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self) +void extract_mip_gnss_vel_ned_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_vel_ecef_data(mip_serializer* serializer, const mip_gnss_vel_ecef_data* self) +void insert_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->v[i]); @@ -223,7 +223,7 @@ void insert_mip_gnss_vel_ecef_data(mip_serializer* serializer, const mip_gnss_ve insert_mip_gnss_vel_ecef_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_vel_ecef_data(mip_serializer* serializer, mip_gnss_vel_ecef_data* self) +void extract_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, mip_gnss_vel_ecef_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->v[i]); @@ -237,24 +237,24 @@ bool extract_mip_gnss_vel_ecef_data_from_field(const mip_field* field, void* ptr { assert(ptr); mip_gnss_vel_ecef_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_vel_ecef_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_vel_ecef_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self) +void insert_mip_gnss_vel_ecef_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_vel_ecef_data_valid_flags(struct mip_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self) +void extract_mip_gnss_vel_ecef_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_dop_data(mip_serializer* serializer, const mip_gnss_dop_data* self) +void insert_mip_gnss_dop_data(microstrain_serializer* serializer, const mip_gnss_dop_data* self) { microstrain_insert_float(serializer, self->gdop); @@ -273,7 +273,7 @@ void insert_mip_gnss_dop_data(mip_serializer* serializer, const mip_gnss_dop_dat insert_mip_gnss_dop_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_dop_data(mip_serializer* serializer, mip_gnss_dop_data* self) +void extract_mip_gnss_dop_data(microstrain_serializer* serializer, mip_gnss_dop_data* self) { microstrain_extract_float(serializer, &self->gdop); @@ -296,24 +296,24 @@ bool extract_mip_gnss_dop_data_from_field(const mip_field* field, void* ptr) { assert(ptr); mip_gnss_dop_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_dop_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_dop_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_dop_data_valid_flags self) +void insert_mip_gnss_dop_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_dop_data_valid_flags(struct mip_serializer* serializer, mip_gnss_dop_data_valid_flags* self) +void extract_mip_gnss_dop_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_utc_time_data(mip_serializer* serializer, const mip_gnss_utc_time_data* self) +void insert_mip_gnss_utc_time_data(microstrain_serializer* serializer, const mip_gnss_utc_time_data* self) { microstrain_insert_u16(serializer, self->year); @@ -332,7 +332,7 @@ void insert_mip_gnss_utc_time_data(mip_serializer* serializer, const mip_gnss_ut insert_mip_gnss_utc_time_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_utc_time_data(mip_serializer* serializer, mip_gnss_utc_time_data* self) +void extract_mip_gnss_utc_time_data(microstrain_serializer* serializer, mip_gnss_utc_time_data* self) { microstrain_extract_u16(serializer, &self->year); @@ -355,24 +355,24 @@ bool extract_mip_gnss_utc_time_data_from_field(const mip_field* field, void* ptr { assert(ptr); mip_gnss_utc_time_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_utc_time_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_utc_time_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self) +void insert_mip_gnss_utc_time_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_utc_time_data_valid_flags(struct mip_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self) +void extract_mip_gnss_utc_time_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_gps_time_data(mip_serializer* serializer, const mip_gnss_gps_time_data* self) +void insert_mip_gnss_gps_time_data(microstrain_serializer* serializer, const mip_gnss_gps_time_data* self) { microstrain_insert_double(serializer, self->tow); @@ -381,7 +381,7 @@ void insert_mip_gnss_gps_time_data(mip_serializer* serializer, const mip_gnss_gp insert_mip_gnss_gps_time_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_gps_time_data(mip_serializer* serializer, mip_gnss_gps_time_data* self) +void extract_mip_gnss_gps_time_data(microstrain_serializer* serializer, mip_gnss_gps_time_data* self) { microstrain_extract_double(serializer, &self->tow); @@ -394,24 +394,24 @@ bool extract_mip_gnss_gps_time_data_from_field(const mip_field* field, void* ptr { assert(ptr); mip_gnss_gps_time_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_time_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_time_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self) +void insert_mip_gnss_gps_time_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_gps_time_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self) +void extract_mip_gnss_gps_time_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_clock_info_data(mip_serializer* serializer, const mip_gnss_clock_info_data* self) +void insert_mip_gnss_clock_info_data(microstrain_serializer* serializer, const mip_gnss_clock_info_data* self) { microstrain_insert_double(serializer, self->bias); @@ -422,7 +422,7 @@ void insert_mip_gnss_clock_info_data(mip_serializer* serializer, const mip_gnss_ insert_mip_gnss_clock_info_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_clock_info_data(mip_serializer* serializer, mip_gnss_clock_info_data* self) +void extract_mip_gnss_clock_info_data(microstrain_serializer* serializer, mip_gnss_clock_info_data* self) { microstrain_extract_double(serializer, &self->bias); @@ -437,24 +437,24 @@ bool extract_mip_gnss_clock_info_data_from_field(const mip_field* field, void* p { assert(ptr); mip_gnss_clock_info_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_clock_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_clock_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self) +void insert_mip_gnss_clock_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_clock_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self) +void extract_mip_gnss_clock_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_fix_info_data(mip_serializer* serializer, const mip_gnss_fix_info_data* self) +void insert_mip_gnss_fix_info_data(microstrain_serializer* serializer, const mip_gnss_fix_info_data* self) { insert_mip_gnss_fix_info_data_fix_type(serializer, self->fix_type); @@ -465,7 +465,7 @@ void insert_mip_gnss_fix_info_data(mip_serializer* serializer, const mip_gnss_fi insert_mip_gnss_fix_info_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_fix_info_data(mip_serializer* serializer, mip_gnss_fix_info_data* self) +void extract_mip_gnss_fix_info_data(microstrain_serializer* serializer, mip_gnss_fix_info_data* self) { extract_mip_gnss_fix_info_data_fix_type(serializer, &self->fix_type); @@ -480,46 +480,46 @@ bool extract_mip_gnss_fix_info_data_from_field(const mip_field* field, void* ptr { assert(ptr); mip_gnss_fix_info_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_fix_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_fix_info_data_fix_type(struct mip_serializer* serializer, const mip_gnss_fix_info_data_fix_type self) +void insert_mip_gnss_fix_info_data_fix_type(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_fix_info_data_fix_type(struct mip_serializer* serializer, mip_gnss_fix_info_data_fix_type* self) +void extract_mip_gnss_fix_info_data_fix_type(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_fix_info_data_fix_flags(struct mip_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self) +void insert_mip_gnss_fix_info_data_fix_flags(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_fix_info_data_fix_flags(struct mip_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self) +void extract_mip_gnss_fix_info_data_fix_flags(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_fix_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self) +void insert_mip_gnss_fix_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_fix_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self) +void extract_mip_gnss_fix_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_sv_info_data(mip_serializer* serializer, const mip_gnss_sv_info_data* self) +void insert_mip_gnss_sv_info_data(microstrain_serializer* serializer, const mip_gnss_sv_info_data* self) { microstrain_insert_u8(serializer, self->channel); @@ -536,7 +536,7 @@ void insert_mip_gnss_sv_info_data(mip_serializer* serializer, const mip_gnss_sv_ insert_mip_gnss_sv_info_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_sv_info_data(mip_serializer* serializer, mip_gnss_sv_info_data* self) +void extract_mip_gnss_sv_info_data(microstrain_serializer* serializer, mip_gnss_sv_info_data* self) { microstrain_extract_u8(serializer, &self->channel); @@ -557,35 +557,35 @@ bool extract_mip_gnss_sv_info_data_from_field(const mip_field* field, void* ptr) { assert(ptr); mip_gnss_sv_info_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_sv_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_sv_info_data_svflags(struct mip_serializer* serializer, const mip_gnss_sv_info_data_svflags self) +void insert_mip_gnss_sv_info_data_svflags(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_sv_info_data_svflags(struct mip_serializer* serializer, mip_gnss_sv_info_data_svflags* self) +void extract_mip_gnss_sv_info_data_svflags(struct microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_sv_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self) +void insert_mip_gnss_sv_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_sv_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self) +void extract_mip_gnss_sv_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_hw_status_data(mip_serializer* serializer, const mip_gnss_hw_status_data* self) +void insert_mip_gnss_hw_status_data(microstrain_serializer* serializer, const mip_gnss_hw_status_data* self) { insert_mip_gnss_hw_status_data_receiver_state(serializer, self->receiver_state); @@ -596,7 +596,7 @@ void insert_mip_gnss_hw_status_data(mip_serializer* serializer, const mip_gnss_h insert_mip_gnss_hw_status_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_hw_status_data(mip_serializer* serializer, mip_gnss_hw_status_data* self) +void extract_mip_gnss_hw_status_data(microstrain_serializer* serializer, mip_gnss_hw_status_data* self) { extract_mip_gnss_hw_status_data_receiver_state(serializer, &self->receiver_state); @@ -611,57 +611,57 @@ bool extract_mip_gnss_hw_status_data_from_field(const mip_field* field, void* pt { assert(ptr); mip_gnss_hw_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_hw_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_hw_status_data_receiver_state(struct mip_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self) +void insert_mip_gnss_hw_status_data_receiver_state(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_hw_status_data_receiver_state(struct mip_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self) +void extract_mip_gnss_hw_status_data_receiver_state(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_hw_status_data_antenna_state(struct mip_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self) +void insert_mip_gnss_hw_status_data_antenna_state(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_hw_status_data_antenna_state(struct mip_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self) +void extract_mip_gnss_hw_status_data_antenna_state(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_hw_status_data_antenna_power(struct mip_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self) +void insert_mip_gnss_hw_status_data_antenna_power(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_hw_status_data_antenna_power(struct mip_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self) +void extract_mip_gnss_hw_status_data_antenna_power(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_hw_status_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self) +void insert_mip_gnss_hw_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_hw_status_data_valid_flags(struct mip_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self) +void extract_mip_gnss_hw_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_dgps_info_data(mip_serializer* serializer, const mip_gnss_dgps_info_data* self) +void insert_mip_gnss_dgps_info_data(microstrain_serializer* serializer, const mip_gnss_dgps_info_data* self) { microstrain_insert_u8(serializer, self->sv_id); @@ -674,7 +674,7 @@ void insert_mip_gnss_dgps_info_data(mip_serializer* serializer, const mip_gnss_d insert_mip_gnss_dgps_info_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_dgps_info_data(mip_serializer* serializer, mip_gnss_dgps_info_data* self) +void extract_mip_gnss_dgps_info_data(microstrain_serializer* serializer, mip_gnss_dgps_info_data* self) { microstrain_extract_u8(serializer, &self->sv_id); @@ -691,24 +691,24 @@ bool extract_mip_gnss_dgps_info_data_from_field(const mip_field* field, void* pt { assert(ptr); mip_gnss_dgps_info_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_dgps_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_dgps_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self) +void insert_mip_gnss_dgps_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_dgps_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self) +void extract_mip_gnss_dgps_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_dgps_channel_data(mip_serializer* serializer, const mip_gnss_dgps_channel_data* self) +void insert_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data* self) { microstrain_insert_u8(serializer, self->sv_id); @@ -721,7 +721,7 @@ void insert_mip_gnss_dgps_channel_data(mip_serializer* serializer, const mip_gns insert_mip_gnss_dgps_channel_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_dgps_channel_data(mip_serializer* serializer, mip_gnss_dgps_channel_data* self) +void extract_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, mip_gnss_dgps_channel_data* self) { microstrain_extract_u8(serializer, &self->sv_id); @@ -738,24 +738,24 @@ bool extract_mip_gnss_dgps_channel_data_from_field(const mip_field* field, void* { assert(ptr); mip_gnss_dgps_channel_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_dgps_channel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_dgps_channel_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self) +void insert_mip_gnss_dgps_channel_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_dgps_channel_data_valid_flags(struct mip_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self) +void extract_mip_gnss_dgps_channel_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_clock_info_2_data(mip_serializer* serializer, const mip_gnss_clock_info_2_data* self) +void insert_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data* self) { microstrain_insert_double(serializer, self->bias); @@ -768,7 +768,7 @@ void insert_mip_gnss_clock_info_2_data(mip_serializer* serializer, const mip_gns insert_mip_gnss_clock_info_2_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_clock_info_2_data(mip_serializer* serializer, mip_gnss_clock_info_2_data* self) +void extract_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, mip_gnss_clock_info_2_data* self) { microstrain_extract_double(serializer, &self->bias); @@ -785,31 +785,31 @@ bool extract_mip_gnss_clock_info_2_data_from_field(const mip_field* field, void* { assert(ptr); mip_gnss_clock_info_2_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_clock_info_2_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_clock_info_2_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self) +void insert_mip_gnss_clock_info_2_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_clock_info_2_data_valid_flags(struct mip_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self) +void extract_mip_gnss_clock_info_2_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_gps_leap_seconds_data(mip_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self) +void insert_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self) { microstrain_insert_u8(serializer, self->leap_seconds); insert_mip_gnss_gps_leap_seconds_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_gps_leap_seconds_data(mip_serializer* serializer, mip_gnss_gps_leap_seconds_data* self) +void extract_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data* self) { microstrain_extract_u8(serializer, &self->leap_seconds); @@ -820,24 +820,24 @@ bool extract_mip_gnss_gps_leap_seconds_data_from_field(const mip_field* field, v { assert(ptr); mip_gnss_gps_leap_seconds_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_leap_seconds_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_leap_seconds_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self) +void insert_mip_gnss_gps_leap_seconds_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_gps_leap_seconds_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self) +void extract_mip_gnss_gps_leap_seconds_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_sbas_info_data(mip_serializer* serializer, const mip_gnss_sbas_info_data* self) +void insert_mip_gnss_sbas_info_data(microstrain_serializer* serializer, const mip_gnss_sbas_info_data* self) { microstrain_insert_double(serializer, self->time_of_week); @@ -854,7 +854,7 @@ void insert_mip_gnss_sbas_info_data(mip_serializer* serializer, const mip_gnss_s insert_mip_gnss_sbas_info_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_sbas_info_data(mip_serializer* serializer, mip_gnss_sbas_info_data* self) +void extract_mip_gnss_sbas_info_data(microstrain_serializer* serializer, mip_gnss_sbas_info_data* self) { microstrain_extract_double(serializer, &self->time_of_week); @@ -875,35 +875,35 @@ bool extract_mip_gnss_sbas_info_data_from_field(const mip_field* field, void* pt { assert(ptr); mip_gnss_sbas_info_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_sbas_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_sbas_info_data_sbas_status(struct mip_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self) +void insert_mip_gnss_sbas_info_data_sbas_status(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_sbas_info_data_sbas_status(struct mip_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self) +void extract_mip_gnss_sbas_info_data_sbas_status(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_sbas_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self) +void insert_mip_gnss_sbas_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_sbas_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self) +void extract_mip_gnss_sbas_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_sbas_correction_data(mip_serializer* serializer, const mip_gnss_sbas_correction_data* self) +void insert_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data* self) { microstrain_insert_u8(serializer, self->index); @@ -926,7 +926,7 @@ void insert_mip_gnss_sbas_correction_data(mip_serializer* serializer, const mip_ insert_mip_gnss_sbas_correction_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_sbas_correction_data(mip_serializer* serializer, mip_gnss_sbas_correction_data* self) +void extract_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, mip_gnss_sbas_correction_data* self) { microstrain_extract_u8(serializer, &self->index); @@ -953,24 +953,24 @@ bool extract_mip_gnss_sbas_correction_data_from_field(const mip_field* field, vo { assert(ptr); mip_gnss_sbas_correction_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_sbas_correction_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_sbas_correction_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self) +void insert_mip_gnss_sbas_correction_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_sbas_correction_data_valid_flags(struct mip_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self) +void extract_mip_gnss_sbas_correction_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rf_error_detection_data(mip_serializer* serializer, const mip_gnss_rf_error_detection_data* self) +void insert_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data* self) { insert_mip_gnss_rf_error_detection_data_rfband(serializer, self->rf_band); @@ -984,7 +984,7 @@ void insert_mip_gnss_rf_error_detection_data(mip_serializer* serializer, const m insert_mip_gnss_rf_error_detection_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_rf_error_detection_data(mip_serializer* serializer, mip_gnss_rf_error_detection_data* self) +void extract_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data* self) { extract_mip_gnss_rf_error_detection_data_rfband(serializer, &self->rf_band); @@ -1002,57 +1002,57 @@ bool extract_mip_gnss_rf_error_detection_data_from_field(const mip_field* field, { assert(ptr); mip_gnss_rf_error_detection_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_rf_error_detection_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_rf_error_detection_data_rfband(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self) +void insert_mip_gnss_rf_error_detection_data_rfband(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_rf_error_detection_data_rfband(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self) +void extract_mip_gnss_rf_error_detection_data_rfband(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rf_error_detection_data_jamming_state(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self) +void insert_mip_gnss_rf_error_detection_data_jamming_state(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_rf_error_detection_data_jamming_state(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self) +void extract_mip_gnss_rf_error_detection_data_jamming_state(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rf_error_detection_data_spoofing_state(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self) +void insert_mip_gnss_rf_error_detection_data_spoofing_state(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_rf_error_detection_data_spoofing_state(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self) +void extract_mip_gnss_rf_error_detection_data_spoofing_state(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rf_error_detection_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self) +void insert_mip_gnss_rf_error_detection_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_rf_error_detection_data_valid_flags(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self) +void extract_mip_gnss_rf_error_detection_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_base_station_info_data(mip_serializer* serializer, const mip_gnss_base_station_info_data* self) +void insert_mip_gnss_base_station_info_data(microstrain_serializer* serializer, const mip_gnss_base_station_info_data* self) { microstrain_insert_double(serializer, self->time_of_week); @@ -1070,7 +1070,7 @@ void insert_mip_gnss_base_station_info_data(mip_serializer* serializer, const mi insert_mip_gnss_base_station_info_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_base_station_info_data(mip_serializer* serializer, mip_gnss_base_station_info_data* self) +void extract_mip_gnss_base_station_info_data(microstrain_serializer* serializer, mip_gnss_base_station_info_data* self) { microstrain_extract_double(serializer, &self->time_of_week); @@ -1092,35 +1092,35 @@ bool extract_mip_gnss_base_station_info_data_from_field(const mip_field* field, { assert(ptr); mip_gnss_base_station_info_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_base_station_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_base_station_info_data_indicator_flags(struct mip_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self) +void insert_mip_gnss_base_station_info_data_indicator_flags(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_base_station_info_data_indicator_flags(struct mip_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self) +void extract_mip_gnss_base_station_info_data_indicator_flags(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_base_station_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self) +void insert_mip_gnss_base_station_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_base_station_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self) +void extract_mip_gnss_base_station_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rtk_corrections_status_data(mip_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self) +void insert_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self) { microstrain_insert_double(serializer, self->time_of_week); @@ -1144,7 +1144,7 @@ void insert_mip_gnss_rtk_corrections_status_data(mip_serializer* serializer, con insert_mip_gnss_rtk_corrections_status_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_rtk_corrections_status_data(mip_serializer* serializer, mip_gnss_rtk_corrections_status_data* self) +void extract_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data* self) { microstrain_extract_double(serializer, &self->time_of_week); @@ -1172,35 +1172,35 @@ bool extract_mip_gnss_rtk_corrections_status_data_from_field(const mip_field* fi { assert(ptr); mip_gnss_rtk_corrections_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_rtk_corrections_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_rtk_corrections_status_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self) +void insert_mip_gnss_rtk_corrections_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_rtk_corrections_status_data_valid_flags(struct mip_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self) +void extract_mip_gnss_rtk_corrections_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rtk_corrections_status_data_epoch_status(struct mip_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self) +void insert_mip_gnss_rtk_corrections_status_data_epoch_status(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_rtk_corrections_status_data_epoch_status(struct mip_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self) +void extract_mip_gnss_rtk_corrections_status_data_epoch_status(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_satellite_status_data(mip_serializer* serializer, const mip_gnss_satellite_status_data* self) +void insert_mip_gnss_satellite_status_data(microstrain_serializer* serializer, const mip_gnss_satellite_status_data* self) { microstrain_insert_u8(serializer, self->index); @@ -1223,7 +1223,7 @@ void insert_mip_gnss_satellite_status_data(mip_serializer* serializer, const mip insert_mip_gnss_satellite_status_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_satellite_status_data(mip_serializer* serializer, mip_gnss_satellite_status_data* self) +void extract_mip_gnss_satellite_status_data(microstrain_serializer* serializer, mip_gnss_satellite_status_data* self) { microstrain_extract_u8(serializer, &self->index); @@ -1250,24 +1250,24 @@ bool extract_mip_gnss_satellite_status_data_from_field(const mip_field* field, v { assert(ptr); mip_gnss_satellite_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_satellite_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_satellite_status_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self) +void insert_mip_gnss_satellite_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_satellite_status_data_valid_flags(struct mip_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self) +void extract_mip_gnss_satellite_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_raw_data(mip_serializer* serializer, const mip_gnss_raw_data* self) +void insert_mip_gnss_raw_data(microstrain_serializer* serializer, const mip_gnss_raw_data* self) { microstrain_insert_u8(serializer, self->index); @@ -1308,7 +1308,7 @@ void insert_mip_gnss_raw_data(mip_serializer* serializer, const mip_gnss_raw_dat insert_mip_gnss_raw_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_raw_data(mip_serializer* serializer, mip_gnss_raw_data* self) +void extract_mip_gnss_raw_data(microstrain_serializer* serializer, mip_gnss_raw_data* self) { microstrain_extract_u8(serializer, &self->index); @@ -1353,35 +1353,35 @@ bool extract_mip_gnss_raw_data_from_field(const mip_field* field, void* ptr) { assert(ptr); mip_gnss_raw_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_raw_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_raw_data_gnss_signal_quality(struct mip_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self) +void insert_mip_gnss_raw_data_gnss_signal_quality(struct microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_raw_data_gnss_signal_quality(struct mip_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self) +void extract_mip_gnss_raw_data_gnss_signal_quality(struct microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_raw_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_raw_data_valid_flags self) +void insert_mip_gnss_raw_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_raw_data_valid_flags(struct mip_serializer* serializer, mip_gnss_raw_data_valid_flags* self) +void extract_mip_gnss_raw_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_gps_ephemeris_data(mip_serializer* serializer, const mip_gnss_gps_ephemeris_data* self) +void insert_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data* self) { microstrain_insert_u8(serializer, self->index); @@ -1452,7 +1452,7 @@ void insert_mip_gnss_gps_ephemeris_data(mip_serializer* serializer, const mip_gn insert_mip_gnss_gps_ephemeris_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_gps_ephemeris_data(mip_serializer* serializer, mip_gnss_gps_ephemeris_data* self) +void extract_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data* self) { microstrain_extract_u8(serializer, &self->index); @@ -1527,24 +1527,24 @@ bool extract_mip_gnss_gps_ephemeris_data_from_field(const mip_field* field, void { assert(ptr); mip_gnss_gps_ephemeris_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_ephemeris_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_ephemeris_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) +void insert_mip_gnss_gps_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_gps_ephemeris_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self) +void extract_mip_gnss_gps_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_galileo_ephemeris_data(mip_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self) +void insert_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self) { microstrain_insert_u8(serializer, self->index); @@ -1615,7 +1615,7 @@ void insert_mip_gnss_galileo_ephemeris_data(mip_serializer* serializer, const mi insert_mip_gnss_galileo_ephemeris_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_galileo_ephemeris_data(mip_serializer* serializer, mip_gnss_galileo_ephemeris_data* self) +void extract_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data* self) { microstrain_extract_u8(serializer, &self->index); @@ -1690,24 +1690,24 @@ bool extract_mip_gnss_galileo_ephemeris_data_from_field(const mip_field* field, { assert(ptr); mip_gnss_galileo_ephemeris_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_galileo_ephemeris_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_galileo_ephemeris_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) +void insert_mip_gnss_galileo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_galileo_ephemeris_data_valid_flags(struct mip_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self) +void extract_mip_gnss_galileo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_glo_ephemeris_data(mip_serializer* serializer, const mip_gnss_glo_ephemeris_data* self) +void insert_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data* self) { microstrain_insert_u8(serializer, self->index); @@ -1763,7 +1763,7 @@ void insert_mip_gnss_glo_ephemeris_data(mip_serializer* serializer, const mip_gn insert_mip_gnss_glo_ephemeris_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_glo_ephemeris_data(mip_serializer* serializer, mip_gnss_glo_ephemeris_data* self) +void extract_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data* self) { microstrain_extract_u8(serializer, &self->index); @@ -1823,24 +1823,24 @@ bool extract_mip_gnss_glo_ephemeris_data_from_field(const mip_field* field, void { assert(ptr); mip_gnss_glo_ephemeris_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_glo_ephemeris_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_glo_ephemeris_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self) +void insert_mip_gnss_glo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_glo_ephemeris_data_valid_flags(struct mip_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self) +void extract_mip_gnss_glo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_gps_iono_corr_data(mip_serializer* serializer, const mip_gnss_gps_iono_corr_data* self) +void insert_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data* self) { microstrain_insert_double(serializer, self->time_of_week); @@ -1855,7 +1855,7 @@ void insert_mip_gnss_gps_iono_corr_data(mip_serializer* serializer, const mip_gn insert_mip_gnss_gps_iono_corr_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_gps_iono_corr_data(mip_serializer* serializer, mip_gnss_gps_iono_corr_data* self) +void extract_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data* self) { microstrain_extract_double(serializer, &self->time_of_week); @@ -1874,24 +1874,24 @@ bool extract_mip_gnss_gps_iono_corr_data_from_field(const mip_field* field, void { assert(ptr); mip_gnss_gps_iono_corr_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_iono_corr_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_iono_corr_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self) +void insert_mip_gnss_gps_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_gps_iono_corr_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self) +void extract_mip_gnss_gps_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_galileo_iono_corr_data(mip_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self) +void insert_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self) { microstrain_insert_double(serializer, self->time_of_week); @@ -1905,7 +1905,7 @@ void insert_mip_gnss_galileo_iono_corr_data(mip_serializer* serializer, const mi insert_mip_gnss_galileo_iono_corr_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_gnss_galileo_iono_corr_data(mip_serializer* serializer, mip_gnss_galileo_iono_corr_data* self) +void extract_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data* self) { microstrain_extract_double(serializer, &self->time_of_week); @@ -1923,17 +1923,17 @@ bool extract_mip_gnss_galileo_iono_corr_data_from_field(const mip_field* field, { assert(ptr); mip_gnss_galileo_iono_corr_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_galileo_iono_corr_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_galileo_iono_corr_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self) +void insert_mip_gnss_galileo_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_galileo_iono_corr_data_valid_flags(struct mip_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self) +void extract_mip_gnss_galileo_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/mip/definitions/data_gnss.h b/src/mip/definitions/data_gnss.h index c2bb9a258..e955692df 100644 --- a/src/mip/definitions/data_gnss.h +++ b/src/mip/definitions/data_gnss.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -82,8 +82,8 @@ static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_GALILEO = 3; // static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_BEIDOU = 4; ///< static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_SBAS = 5; ///< -void insert_mip_gnss_constellation_id(struct mip_serializer* serializer, const mip_gnss_constellation_id self); -void extract_mip_gnss_constellation_id(struct mip_serializer* serializer, mip_gnss_constellation_id* self); +void insert_mip_gnss_constellation_id(struct microstrain_serializer* serializer, const mip_gnss_constellation_id self); +void extract_mip_gnss_constellation_id(struct microstrain_serializer* serializer, mip_gnss_constellation_id* self); typedef uint8_t mip_gnss_signal_id; static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_UNKNOWN = 0; ///< @@ -152,8 +152,8 @@ static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2I = 166; ///< static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2Q = 167; ///< static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2IQ = 168; ///< -void insert_mip_gnss_signal_id(struct mip_serializer* serializer, const mip_gnss_signal_id self); -void extract_mip_gnss_signal_id(struct mip_serializer* serializer, mip_gnss_signal_id* self); +void insert_mip_gnss_signal_id(struct microstrain_serializer* serializer, const mip_gnss_signal_id self); +void extract_mip_gnss_signal_id(struct microstrain_serializer* serializer, mip_gnss_signal_id* self); typedef uint8_t mip_sbas_system; static const mip_sbas_system MIP_SBAS_SYSTEM_UNKNOWN = 0; ///< @@ -162,8 +162,8 @@ static const mip_sbas_system MIP_SBAS_SYSTEM_EGNOS = 2; ///< static const mip_sbas_system MIP_SBAS_SYSTEM_MSAS = 3; ///< static const mip_sbas_system MIP_SBAS_SYSTEM_GAGAN = 4; ///< -void insert_mip_sbas_system(struct mip_serializer* serializer, const mip_sbas_system self); -void extract_mip_sbas_system(struct mip_serializer* serializer, mip_sbas_system* self); +void insert_mip_sbas_system(struct microstrain_serializer* serializer, const mip_sbas_system self); +void extract_mip_sbas_system(struct microstrain_serializer* serializer, mip_sbas_system* self); enum { MIP_GNSS_DGPS_INFO_MAX_CHANNEL_NUMBER = 32 }; enum { MIP_GNSS_SV_INFO_MAX_SV_NUMBER = 32 }; @@ -200,12 +200,12 @@ struct mip_gnss_pos_llh_data }; typedef struct mip_gnss_pos_llh_data mip_gnss_pos_llh_data; -void insert_mip_gnss_pos_llh_data(struct mip_serializer* serializer, const mip_gnss_pos_llh_data* self); -void extract_mip_gnss_pos_llh_data(struct mip_serializer* serializer, mip_gnss_pos_llh_data* self); +void insert_mip_gnss_pos_llh_data(struct microstrain_serializer* serializer, const mip_gnss_pos_llh_data* self); +void extract_mip_gnss_pos_llh_data(struct microstrain_serializer* serializer, mip_gnss_pos_llh_data* self); bool extract_mip_gnss_pos_llh_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_pos_llh_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self); -void extract_mip_gnss_pos_llh_data_valid_flags(struct mip_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self); +void insert_mip_gnss_pos_llh_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self); +void extract_mip_gnss_pos_llh_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self); ///@} @@ -231,12 +231,12 @@ struct mip_gnss_pos_ecef_data }; typedef struct mip_gnss_pos_ecef_data mip_gnss_pos_ecef_data; -void insert_mip_gnss_pos_ecef_data(struct mip_serializer* serializer, const mip_gnss_pos_ecef_data* self); -void extract_mip_gnss_pos_ecef_data(struct mip_serializer* serializer, mip_gnss_pos_ecef_data* self); +void insert_mip_gnss_pos_ecef_data(struct microstrain_serializer* serializer, const mip_gnss_pos_ecef_data* self); +void extract_mip_gnss_pos_ecef_data(struct microstrain_serializer* serializer, mip_gnss_pos_ecef_data* self); bool extract_mip_gnss_pos_ecef_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_pos_ecef_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self); -void extract_mip_gnss_pos_ecef_data_valid_flags(struct mip_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self); +void insert_mip_gnss_pos_ecef_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self); +void extract_mip_gnss_pos_ecef_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self); ///@} @@ -270,12 +270,12 @@ struct mip_gnss_vel_ned_data }; typedef struct mip_gnss_vel_ned_data mip_gnss_vel_ned_data; -void insert_mip_gnss_vel_ned_data(struct mip_serializer* serializer, const mip_gnss_vel_ned_data* self); -void extract_mip_gnss_vel_ned_data(struct mip_serializer* serializer, mip_gnss_vel_ned_data* self); +void insert_mip_gnss_vel_ned_data(struct microstrain_serializer* serializer, const mip_gnss_vel_ned_data* self); +void extract_mip_gnss_vel_ned_data(struct microstrain_serializer* serializer, mip_gnss_vel_ned_data* self); bool extract_mip_gnss_vel_ned_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_vel_ned_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self); -void extract_mip_gnss_vel_ned_data_valid_flags(struct mip_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self); +void insert_mip_gnss_vel_ned_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self); +void extract_mip_gnss_vel_ned_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self); ///@} @@ -301,12 +301,12 @@ struct mip_gnss_vel_ecef_data }; typedef struct mip_gnss_vel_ecef_data mip_gnss_vel_ecef_data; -void insert_mip_gnss_vel_ecef_data(struct mip_serializer* serializer, const mip_gnss_vel_ecef_data* self); -void extract_mip_gnss_vel_ecef_data(struct mip_serializer* serializer, mip_gnss_vel_ecef_data* self); +void insert_mip_gnss_vel_ecef_data(struct microstrain_serializer* serializer, const mip_gnss_vel_ecef_data* self); +void extract_mip_gnss_vel_ecef_data(struct microstrain_serializer* serializer, mip_gnss_vel_ecef_data* self); bool extract_mip_gnss_vel_ecef_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_vel_ecef_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self); -void extract_mip_gnss_vel_ecef_data_valid_flags(struct mip_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self); +void insert_mip_gnss_vel_ecef_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self); +void extract_mip_gnss_vel_ecef_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self); ///@} @@ -342,12 +342,12 @@ struct mip_gnss_dop_data }; typedef struct mip_gnss_dop_data mip_gnss_dop_data; -void insert_mip_gnss_dop_data(struct mip_serializer* serializer, const mip_gnss_dop_data* self); -void extract_mip_gnss_dop_data(struct mip_serializer* serializer, mip_gnss_dop_data* self); +void insert_mip_gnss_dop_data(struct microstrain_serializer* serializer, const mip_gnss_dop_data* self); +void extract_mip_gnss_dop_data(struct microstrain_serializer* serializer, mip_gnss_dop_data* self); bool extract_mip_gnss_dop_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_dop_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_dop_data_valid_flags self); -void extract_mip_gnss_dop_data_valid_flags(struct mip_serializer* serializer, mip_gnss_dop_data_valid_flags* self); +void insert_mip_gnss_dop_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self); +void extract_mip_gnss_dop_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self); ///@} @@ -378,12 +378,12 @@ struct mip_gnss_utc_time_data }; typedef struct mip_gnss_utc_time_data mip_gnss_utc_time_data; -void insert_mip_gnss_utc_time_data(struct mip_serializer* serializer, const mip_gnss_utc_time_data* self); -void extract_mip_gnss_utc_time_data(struct mip_serializer* serializer, mip_gnss_utc_time_data* self); +void insert_mip_gnss_utc_time_data(struct microstrain_serializer* serializer, const mip_gnss_utc_time_data* self); +void extract_mip_gnss_utc_time_data(struct microstrain_serializer* serializer, mip_gnss_utc_time_data* self); bool extract_mip_gnss_utc_time_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_utc_time_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self); -void extract_mip_gnss_utc_time_data_valid_flags(struct mip_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self); +void insert_mip_gnss_utc_time_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self); +void extract_mip_gnss_utc_time_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self); ///@} @@ -409,12 +409,12 @@ struct mip_gnss_gps_time_data }; typedef struct mip_gnss_gps_time_data mip_gnss_gps_time_data; -void insert_mip_gnss_gps_time_data(struct mip_serializer* serializer, const mip_gnss_gps_time_data* self); -void extract_mip_gnss_gps_time_data(struct mip_serializer* serializer, mip_gnss_gps_time_data* self); +void insert_mip_gnss_gps_time_data(struct microstrain_serializer* serializer, const mip_gnss_gps_time_data* self); +void extract_mip_gnss_gps_time_data(struct microstrain_serializer* serializer, mip_gnss_gps_time_data* self); bool extract_mip_gnss_gps_time_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_gps_time_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self); -void extract_mip_gnss_gps_time_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self); +void insert_mip_gnss_gps_time_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self); +void extract_mip_gnss_gps_time_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self); ///@} @@ -442,12 +442,12 @@ struct mip_gnss_clock_info_data }; typedef struct mip_gnss_clock_info_data mip_gnss_clock_info_data; -void insert_mip_gnss_clock_info_data(struct mip_serializer* serializer, const mip_gnss_clock_info_data* self); -void extract_mip_gnss_clock_info_data(struct mip_serializer* serializer, mip_gnss_clock_info_data* self); +void insert_mip_gnss_clock_info_data(struct microstrain_serializer* serializer, const mip_gnss_clock_info_data* self); +void extract_mip_gnss_clock_info_data(struct microstrain_serializer* serializer, mip_gnss_clock_info_data* self); bool extract_mip_gnss_clock_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_clock_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self); -void extract_mip_gnss_clock_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self); +void insert_mip_gnss_clock_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self); +void extract_mip_gnss_clock_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self); ///@} @@ -491,18 +491,18 @@ struct mip_gnss_fix_info_data }; typedef struct mip_gnss_fix_info_data mip_gnss_fix_info_data; -void insert_mip_gnss_fix_info_data(struct mip_serializer* serializer, const mip_gnss_fix_info_data* self); -void extract_mip_gnss_fix_info_data(struct mip_serializer* serializer, mip_gnss_fix_info_data* self); +void insert_mip_gnss_fix_info_data(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data* self); +void extract_mip_gnss_fix_info_data(struct microstrain_serializer* serializer, mip_gnss_fix_info_data* self); bool extract_mip_gnss_fix_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_fix_info_data_fix_type(struct mip_serializer* serializer, const mip_gnss_fix_info_data_fix_type self); -void extract_mip_gnss_fix_info_data_fix_type(struct mip_serializer* serializer, mip_gnss_fix_info_data_fix_type* self); +void insert_mip_gnss_fix_info_data_fix_type(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self); +void extract_mip_gnss_fix_info_data_fix_type(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self); -void insert_mip_gnss_fix_info_data_fix_flags(struct mip_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self); -void extract_mip_gnss_fix_info_data_fix_flags(struct mip_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self); +void insert_mip_gnss_fix_info_data_fix_flags(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self); +void extract_mip_gnss_fix_info_data_fix_flags(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self); -void insert_mip_gnss_fix_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self); -void extract_mip_gnss_fix_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self); +void insert_mip_gnss_fix_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self); +void extract_mip_gnss_fix_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self); ///@} @@ -544,15 +544,15 @@ struct mip_gnss_sv_info_data }; typedef struct mip_gnss_sv_info_data mip_gnss_sv_info_data; -void insert_mip_gnss_sv_info_data(struct mip_serializer* serializer, const mip_gnss_sv_info_data* self); -void extract_mip_gnss_sv_info_data(struct mip_serializer* serializer, mip_gnss_sv_info_data* self); +void insert_mip_gnss_sv_info_data(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data* self); +void extract_mip_gnss_sv_info_data(struct microstrain_serializer* serializer, mip_gnss_sv_info_data* self); bool extract_mip_gnss_sv_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_sv_info_data_svflags(struct mip_serializer* serializer, const mip_gnss_sv_info_data_svflags self); -void extract_mip_gnss_sv_info_data_svflags(struct mip_serializer* serializer, mip_gnss_sv_info_data_svflags* self); +void insert_mip_gnss_sv_info_data_svflags(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self); +void extract_mip_gnss_sv_info_data_svflags(struct microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self); -void insert_mip_gnss_sv_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self); -void extract_mip_gnss_sv_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self); +void insert_mip_gnss_sv_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self); +void extract_mip_gnss_sv_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self); ///@} @@ -597,21 +597,21 @@ struct mip_gnss_hw_status_data }; typedef struct mip_gnss_hw_status_data mip_gnss_hw_status_data; -void insert_mip_gnss_hw_status_data(struct mip_serializer* serializer, const mip_gnss_hw_status_data* self); -void extract_mip_gnss_hw_status_data(struct mip_serializer* serializer, mip_gnss_hw_status_data* self); +void insert_mip_gnss_hw_status_data(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data* self); +void extract_mip_gnss_hw_status_data(struct microstrain_serializer* serializer, mip_gnss_hw_status_data* self); bool extract_mip_gnss_hw_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_hw_status_data_receiver_state(struct mip_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self); -void extract_mip_gnss_hw_status_data_receiver_state(struct mip_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self); +void insert_mip_gnss_hw_status_data_receiver_state(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self); +void extract_mip_gnss_hw_status_data_receiver_state(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self); -void insert_mip_gnss_hw_status_data_antenna_state(struct mip_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self); -void extract_mip_gnss_hw_status_data_antenna_state(struct mip_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self); +void insert_mip_gnss_hw_status_data_antenna_state(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self); +void extract_mip_gnss_hw_status_data_antenna_state(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self); -void insert_mip_gnss_hw_status_data_antenna_power(struct mip_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self); -void extract_mip_gnss_hw_status_data_antenna_power(struct mip_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self); +void insert_mip_gnss_hw_status_data_antenna_power(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self); +void extract_mip_gnss_hw_status_data_antenna_power(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self); -void insert_mip_gnss_hw_status_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self); -void extract_mip_gnss_hw_status_data_valid_flags(struct mip_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self); +void insert_mip_gnss_hw_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self); +void extract_mip_gnss_hw_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self); ///@} @@ -653,12 +653,12 @@ struct mip_gnss_dgps_info_data }; typedef struct mip_gnss_dgps_info_data mip_gnss_dgps_info_data; -void insert_mip_gnss_dgps_info_data(struct mip_serializer* serializer, const mip_gnss_dgps_info_data* self); -void extract_mip_gnss_dgps_info_data(struct mip_serializer* serializer, mip_gnss_dgps_info_data* self); +void insert_mip_gnss_dgps_info_data(struct microstrain_serializer* serializer, const mip_gnss_dgps_info_data* self); +void extract_mip_gnss_dgps_info_data(struct microstrain_serializer* serializer, mip_gnss_dgps_info_data* self); bool extract_mip_gnss_dgps_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_dgps_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self); -void extract_mip_gnss_dgps_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self); +void insert_mip_gnss_dgps_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self); +void extract_mip_gnss_dgps_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self); ///@} @@ -690,12 +690,12 @@ struct mip_gnss_dgps_channel_data }; typedef struct mip_gnss_dgps_channel_data mip_gnss_dgps_channel_data; -void insert_mip_gnss_dgps_channel_data(struct mip_serializer* serializer, const mip_gnss_dgps_channel_data* self); -void extract_mip_gnss_dgps_channel_data(struct mip_serializer* serializer, mip_gnss_dgps_channel_data* self); +void insert_mip_gnss_dgps_channel_data(struct microstrain_serializer* serializer, const mip_gnss_dgps_channel_data* self); +void extract_mip_gnss_dgps_channel_data(struct microstrain_serializer* serializer, mip_gnss_dgps_channel_data* self); bool extract_mip_gnss_dgps_channel_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_dgps_channel_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self); -void extract_mip_gnss_dgps_channel_data_valid_flags(struct mip_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self); +void insert_mip_gnss_dgps_channel_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self); +void extract_mip_gnss_dgps_channel_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self); ///@} @@ -727,12 +727,12 @@ struct mip_gnss_clock_info_2_data }; typedef struct mip_gnss_clock_info_2_data mip_gnss_clock_info_2_data; -void insert_mip_gnss_clock_info_2_data(struct mip_serializer* serializer, const mip_gnss_clock_info_2_data* self); -void extract_mip_gnss_clock_info_2_data(struct mip_serializer* serializer, mip_gnss_clock_info_2_data* self); +void insert_mip_gnss_clock_info_2_data(struct microstrain_serializer* serializer, const mip_gnss_clock_info_2_data* self); +void extract_mip_gnss_clock_info_2_data(struct microstrain_serializer* serializer, mip_gnss_clock_info_2_data* self); bool extract_mip_gnss_clock_info_2_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_clock_info_2_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self); -void extract_mip_gnss_clock_info_2_data_valid_flags(struct mip_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self); +void insert_mip_gnss_clock_info_2_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self); +void extract_mip_gnss_clock_info_2_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self); ///@} @@ -755,12 +755,12 @@ struct mip_gnss_gps_leap_seconds_data }; typedef struct mip_gnss_gps_leap_seconds_data mip_gnss_gps_leap_seconds_data; -void insert_mip_gnss_gps_leap_seconds_data(struct mip_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self); -void extract_mip_gnss_gps_leap_seconds_data(struct mip_serializer* serializer, mip_gnss_gps_leap_seconds_data* self); +void insert_mip_gnss_gps_leap_seconds_data(struct microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self); +void extract_mip_gnss_gps_leap_seconds_data(struct microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data* self); bool extract_mip_gnss_gps_leap_seconds_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_gps_leap_seconds_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self); -void extract_mip_gnss_gps_leap_seconds_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self); +void insert_mip_gnss_gps_leap_seconds_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self); +void extract_mip_gnss_gps_leap_seconds_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self); ///@} @@ -802,15 +802,15 @@ struct mip_gnss_sbas_info_data }; typedef struct mip_gnss_sbas_info_data mip_gnss_sbas_info_data; -void insert_mip_gnss_sbas_info_data(struct mip_serializer* serializer, const mip_gnss_sbas_info_data* self); -void extract_mip_gnss_sbas_info_data(struct mip_serializer* serializer, mip_gnss_sbas_info_data* self); +void insert_mip_gnss_sbas_info_data(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data* self); +void extract_mip_gnss_sbas_info_data(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data* self); bool extract_mip_gnss_sbas_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_sbas_info_data_sbas_status(struct mip_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self); -void extract_mip_gnss_sbas_info_data_sbas_status(struct mip_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self); +void insert_mip_gnss_sbas_info_data_sbas_status(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self); +void extract_mip_gnss_sbas_info_data_sbas_status(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self); -void insert_mip_gnss_sbas_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self); -void extract_mip_gnss_sbas_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self); +void insert_mip_gnss_sbas_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self); +void extract_mip_gnss_sbas_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self); ///@} @@ -866,12 +866,12 @@ struct mip_gnss_sbas_correction_data }; typedef struct mip_gnss_sbas_correction_data mip_gnss_sbas_correction_data; -void insert_mip_gnss_sbas_correction_data(struct mip_serializer* serializer, const mip_gnss_sbas_correction_data* self); -void extract_mip_gnss_sbas_correction_data(struct mip_serializer* serializer, mip_gnss_sbas_correction_data* self); +void insert_mip_gnss_sbas_correction_data(struct microstrain_serializer* serializer, const mip_gnss_sbas_correction_data* self); +void extract_mip_gnss_sbas_correction_data(struct microstrain_serializer* serializer, mip_gnss_sbas_correction_data* self); bool extract_mip_gnss_sbas_correction_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_sbas_correction_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self); -void extract_mip_gnss_sbas_correction_data_valid_flags(struct mip_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self); +void insert_mip_gnss_sbas_correction_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self); +void extract_mip_gnss_sbas_correction_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self); ///@} @@ -918,21 +918,21 @@ struct mip_gnss_rf_error_detection_data }; typedef struct mip_gnss_rf_error_detection_data mip_gnss_rf_error_detection_data; -void insert_mip_gnss_rf_error_detection_data(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data* self); -void extract_mip_gnss_rf_error_detection_data(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data* self); +void insert_mip_gnss_rf_error_detection_data(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data* self); +void extract_mip_gnss_rf_error_detection_data(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data* self); bool extract_mip_gnss_rf_error_detection_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_rf_error_detection_data_rfband(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self); -void extract_mip_gnss_rf_error_detection_data_rfband(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self); +void insert_mip_gnss_rf_error_detection_data_rfband(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self); +void extract_mip_gnss_rf_error_detection_data_rfband(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self); -void insert_mip_gnss_rf_error_detection_data_jamming_state(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self); -void extract_mip_gnss_rf_error_detection_data_jamming_state(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self); +void insert_mip_gnss_rf_error_detection_data_jamming_state(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self); +void extract_mip_gnss_rf_error_detection_data_jamming_state(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self); -void insert_mip_gnss_rf_error_detection_data_spoofing_state(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self); -void extract_mip_gnss_rf_error_detection_data_spoofing_state(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self); +void insert_mip_gnss_rf_error_detection_data_spoofing_state(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self); +void extract_mip_gnss_rf_error_detection_data_spoofing_state(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self); -void insert_mip_gnss_rf_error_detection_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self); -void extract_mip_gnss_rf_error_detection_data_valid_flags(struct mip_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self); +void insert_mip_gnss_rf_error_detection_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self); +void extract_mip_gnss_rf_error_detection_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self); ///@} @@ -981,15 +981,15 @@ struct mip_gnss_base_station_info_data }; typedef struct mip_gnss_base_station_info_data mip_gnss_base_station_info_data; -void insert_mip_gnss_base_station_info_data(struct mip_serializer* serializer, const mip_gnss_base_station_info_data* self); -void extract_mip_gnss_base_station_info_data(struct mip_serializer* serializer, mip_gnss_base_station_info_data* self); +void insert_mip_gnss_base_station_info_data(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data* self); +void extract_mip_gnss_base_station_info_data(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data* self); bool extract_mip_gnss_base_station_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_base_station_info_data_indicator_flags(struct mip_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self); -void extract_mip_gnss_base_station_info_data_indicator_flags(struct mip_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self); +void insert_mip_gnss_base_station_info_data_indicator_flags(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self); +void extract_mip_gnss_base_station_info_data_indicator_flags(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self); -void insert_mip_gnss_base_station_info_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self); -void extract_mip_gnss_base_station_info_data_valid_flags(struct mip_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self); +void insert_mip_gnss_base_station_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self); +void extract_mip_gnss_base_station_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self); ///@} @@ -1040,15 +1040,15 @@ struct mip_gnss_rtk_corrections_status_data }; typedef struct mip_gnss_rtk_corrections_status_data mip_gnss_rtk_corrections_status_data; -void insert_mip_gnss_rtk_corrections_status_data(struct mip_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self); -void extract_mip_gnss_rtk_corrections_status_data(struct mip_serializer* serializer, mip_gnss_rtk_corrections_status_data* self); +void insert_mip_gnss_rtk_corrections_status_data(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self); +void extract_mip_gnss_rtk_corrections_status_data(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data* self); bool extract_mip_gnss_rtk_corrections_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_rtk_corrections_status_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self); -void extract_mip_gnss_rtk_corrections_status_data_valid_flags(struct mip_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self); +void insert_mip_gnss_rtk_corrections_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self); +void extract_mip_gnss_rtk_corrections_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self); -void insert_mip_gnss_rtk_corrections_status_data_epoch_status(struct mip_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self); -void extract_mip_gnss_rtk_corrections_status_data_epoch_status(struct mip_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self); +void insert_mip_gnss_rtk_corrections_status_data_epoch_status(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self); +void extract_mip_gnss_rtk_corrections_status_data_epoch_status(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self); ///@} @@ -1086,12 +1086,12 @@ struct mip_gnss_satellite_status_data }; typedef struct mip_gnss_satellite_status_data mip_gnss_satellite_status_data; -void insert_mip_gnss_satellite_status_data(struct mip_serializer* serializer, const mip_gnss_satellite_status_data* self); -void extract_mip_gnss_satellite_status_data(struct mip_serializer* serializer, mip_gnss_satellite_status_data* self); +void insert_mip_gnss_satellite_status_data(struct microstrain_serializer* serializer, const mip_gnss_satellite_status_data* self); +void extract_mip_gnss_satellite_status_data(struct microstrain_serializer* serializer, mip_gnss_satellite_status_data* self); bool extract_mip_gnss_satellite_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_satellite_status_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self); -void extract_mip_gnss_satellite_status_data_valid_flags(struct mip_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self); +void insert_mip_gnss_satellite_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self); +void extract_mip_gnss_satellite_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self); ///@} @@ -1155,15 +1155,15 @@ struct mip_gnss_raw_data }; typedef struct mip_gnss_raw_data mip_gnss_raw_data; -void insert_mip_gnss_raw_data(struct mip_serializer* serializer, const mip_gnss_raw_data* self); -void extract_mip_gnss_raw_data(struct mip_serializer* serializer, mip_gnss_raw_data* self); +void insert_mip_gnss_raw_data(struct microstrain_serializer* serializer, const mip_gnss_raw_data* self); +void extract_mip_gnss_raw_data(struct microstrain_serializer* serializer, mip_gnss_raw_data* self); bool extract_mip_gnss_raw_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_raw_data_gnss_signal_quality(struct mip_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self); -void extract_mip_gnss_raw_data_gnss_signal_quality(struct mip_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self); +void insert_mip_gnss_raw_data_gnss_signal_quality(struct microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self); +void extract_mip_gnss_raw_data_gnss_signal_quality(struct microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self); -void insert_mip_gnss_raw_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_raw_data_valid_flags self); -void extract_mip_gnss_raw_data_valid_flags(struct mip_serializer* serializer, mip_gnss_raw_data_valid_flags* self); +void insert_mip_gnss_raw_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self); +void extract_mip_gnss_raw_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self); ///@} @@ -1220,12 +1220,12 @@ struct mip_gnss_gps_ephemeris_data }; typedef struct mip_gnss_gps_ephemeris_data mip_gnss_gps_ephemeris_data; -void insert_mip_gnss_gps_ephemeris_data(struct mip_serializer* serializer, const mip_gnss_gps_ephemeris_data* self); -void extract_mip_gnss_gps_ephemeris_data(struct mip_serializer* serializer, mip_gnss_gps_ephemeris_data* self); +void insert_mip_gnss_gps_ephemeris_data(struct microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data* self); +void extract_mip_gnss_gps_ephemeris_data(struct microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data* self); bool extract_mip_gnss_gps_ephemeris_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_gps_ephemeris_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self); -void extract_mip_gnss_gps_ephemeris_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self); +void insert_mip_gnss_gps_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self); +void extract_mip_gnss_gps_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self); ///@} @@ -1282,12 +1282,12 @@ struct mip_gnss_galileo_ephemeris_data }; typedef struct mip_gnss_galileo_ephemeris_data mip_gnss_galileo_ephemeris_data; -void insert_mip_gnss_galileo_ephemeris_data(struct mip_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self); -void extract_mip_gnss_galileo_ephemeris_data(struct mip_serializer* serializer, mip_gnss_galileo_ephemeris_data* self); +void insert_mip_gnss_galileo_ephemeris_data(struct microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self); +void extract_mip_gnss_galileo_ephemeris_data(struct microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data* self); bool extract_mip_gnss_galileo_ephemeris_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_galileo_ephemeris_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self); -void extract_mip_gnss_galileo_ephemeris_data_valid_flags(struct mip_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self); +void insert_mip_gnss_galileo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self); +void extract_mip_gnss_galileo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self); ///@} @@ -1334,12 +1334,12 @@ struct mip_gnss_glo_ephemeris_data }; typedef struct mip_gnss_glo_ephemeris_data mip_gnss_glo_ephemeris_data; -void insert_mip_gnss_glo_ephemeris_data(struct mip_serializer* serializer, const mip_gnss_glo_ephemeris_data* self); -void extract_mip_gnss_glo_ephemeris_data(struct mip_serializer* serializer, mip_gnss_glo_ephemeris_data* self); +void insert_mip_gnss_glo_ephemeris_data(struct microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data* self); +void extract_mip_gnss_glo_ephemeris_data(struct microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data* self); bool extract_mip_gnss_glo_ephemeris_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_glo_ephemeris_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self); -void extract_mip_gnss_glo_ephemeris_data_valid_flags(struct mip_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self); +void insert_mip_gnss_glo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self); +void extract_mip_gnss_glo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self); ///@} @@ -1369,12 +1369,12 @@ struct mip_gnss_gps_iono_corr_data }; typedef struct mip_gnss_gps_iono_corr_data mip_gnss_gps_iono_corr_data; -void insert_mip_gnss_gps_iono_corr_data(struct mip_serializer* serializer, const mip_gnss_gps_iono_corr_data* self); -void extract_mip_gnss_gps_iono_corr_data(struct mip_serializer* serializer, mip_gnss_gps_iono_corr_data* self); +void insert_mip_gnss_gps_iono_corr_data(struct microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data* self); +void extract_mip_gnss_gps_iono_corr_data(struct microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data* self); bool extract_mip_gnss_gps_iono_corr_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_gps_iono_corr_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self); -void extract_mip_gnss_gps_iono_corr_data_valid_flags(struct mip_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self); +void insert_mip_gnss_gps_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self); +void extract_mip_gnss_gps_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self); ///@} @@ -1404,12 +1404,12 @@ struct mip_gnss_galileo_iono_corr_data }; typedef struct mip_gnss_galileo_iono_corr_data mip_gnss_galileo_iono_corr_data; -void insert_mip_gnss_galileo_iono_corr_data(struct mip_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self); -void extract_mip_gnss_galileo_iono_corr_data(struct mip_serializer* serializer, mip_gnss_galileo_iono_corr_data* self); +void insert_mip_gnss_galileo_iono_corr_data(struct microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self); +void extract_mip_gnss_galileo_iono_corr_data(struct microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data* self); bool extract_mip_gnss_galileo_iono_corr_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_galileo_iono_corr_data_valid_flags(struct mip_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self); -void extract_mip_gnss_galileo_iono_corr_data_valid_flags(struct mip_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self); +void insert_mip_gnss_galileo_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self); +void extract_mip_gnss_galileo_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self); ///@} diff --git a/src/mip/definitions/data_sensor.c b/src/mip/definitions/data_sensor.c index d788d8fcb..99a8c0318 100644 --- a/src/mip/definitions/data_sensor.c +++ b/src/mip/definitions/data_sensor.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -27,13 +27,13 @@ struct mip_field; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_sensor_raw_accel_data(mip_serializer* serializer, const mip_sensor_raw_accel_data* self) +void insert_mip_sensor_raw_accel_data(microstrain_serializer* serializer, const mip_sensor_raw_accel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->raw_accel[i]); } -void extract_mip_sensor_raw_accel_data(mip_serializer* serializer, mip_sensor_raw_accel_data* self) +void extract_mip_sensor_raw_accel_data(microstrain_serializer* serializer, mip_sensor_raw_accel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->raw_accel[i]); @@ -43,19 +43,19 @@ bool extract_mip_sensor_raw_accel_data_from_field(const mip_field* field, void* { assert(ptr); mip_sensor_raw_accel_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_accel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_raw_gyro_data(mip_serializer* serializer, const mip_sensor_raw_gyro_data* self) +void insert_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, const mip_sensor_raw_gyro_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->raw_gyro[i]); } -void extract_mip_sensor_raw_gyro_data(mip_serializer* serializer, mip_sensor_raw_gyro_data* self) +void extract_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, mip_sensor_raw_gyro_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->raw_gyro[i]); @@ -65,19 +65,19 @@ bool extract_mip_sensor_raw_gyro_data_from_field(const mip_field* field, void* p { assert(ptr); mip_sensor_raw_gyro_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_gyro_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_raw_mag_data(mip_serializer* serializer, const mip_sensor_raw_mag_data* self) +void insert_mip_sensor_raw_mag_data(microstrain_serializer* serializer, const mip_sensor_raw_mag_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->raw_mag[i]); } -void extract_mip_sensor_raw_mag_data(mip_serializer* serializer, mip_sensor_raw_mag_data* self) +void extract_mip_sensor_raw_mag_data(microstrain_serializer* serializer, mip_sensor_raw_mag_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->raw_mag[i]); @@ -87,18 +87,18 @@ bool extract_mip_sensor_raw_mag_data_from_field(const mip_field* field, void* pt { assert(ptr); mip_sensor_raw_mag_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_mag_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_raw_pressure_data(mip_serializer* serializer, const mip_sensor_raw_pressure_data* self) +void insert_mip_sensor_raw_pressure_data(microstrain_serializer* serializer, const mip_sensor_raw_pressure_data* self) { microstrain_insert_float(serializer, self->raw_pressure); } -void extract_mip_sensor_raw_pressure_data(mip_serializer* serializer, mip_sensor_raw_pressure_data* self) +void extract_mip_sensor_raw_pressure_data(microstrain_serializer* serializer, mip_sensor_raw_pressure_data* self) { microstrain_extract_float(serializer, &self->raw_pressure); @@ -107,19 +107,19 @@ bool extract_mip_sensor_raw_pressure_data_from_field(const mip_field* field, voi { assert(ptr); mip_sensor_raw_pressure_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_pressure_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_scaled_accel_data(mip_serializer* serializer, const mip_sensor_scaled_accel_data* self) +void insert_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, const mip_sensor_scaled_accel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->scaled_accel[i]); } -void extract_mip_sensor_scaled_accel_data(mip_serializer* serializer, mip_sensor_scaled_accel_data* self) +void extract_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, mip_sensor_scaled_accel_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->scaled_accel[i]); @@ -129,19 +129,19 @@ bool extract_mip_sensor_scaled_accel_data_from_field(const mip_field* field, voi { assert(ptr); mip_sensor_scaled_accel_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_accel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_scaled_gyro_data(mip_serializer* serializer, const mip_sensor_scaled_gyro_data* self) +void insert_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, const mip_sensor_scaled_gyro_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->scaled_gyro[i]); } -void extract_mip_sensor_scaled_gyro_data(mip_serializer* serializer, mip_sensor_scaled_gyro_data* self) +void extract_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, mip_sensor_scaled_gyro_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->scaled_gyro[i]); @@ -151,19 +151,19 @@ bool extract_mip_sensor_scaled_gyro_data_from_field(const mip_field* field, void { assert(ptr); mip_sensor_scaled_gyro_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_gyro_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_scaled_mag_data(mip_serializer* serializer, const mip_sensor_scaled_mag_data* self) +void insert_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, const mip_sensor_scaled_mag_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->scaled_mag[i]); } -void extract_mip_sensor_scaled_mag_data(mip_serializer* serializer, mip_sensor_scaled_mag_data* self) +void extract_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, mip_sensor_scaled_mag_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->scaled_mag[i]); @@ -173,18 +173,18 @@ bool extract_mip_sensor_scaled_mag_data_from_field(const mip_field* field, void* { assert(ptr); mip_sensor_scaled_mag_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_mag_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_scaled_pressure_data(mip_serializer* serializer, const mip_sensor_scaled_pressure_data* self) +void insert_mip_sensor_scaled_pressure_data(microstrain_serializer* serializer, const mip_sensor_scaled_pressure_data* self) { microstrain_insert_float(serializer, self->scaled_pressure); } -void extract_mip_sensor_scaled_pressure_data(mip_serializer* serializer, mip_sensor_scaled_pressure_data* self) +void extract_mip_sensor_scaled_pressure_data(microstrain_serializer* serializer, mip_sensor_scaled_pressure_data* self) { microstrain_extract_float(serializer, &self->scaled_pressure); @@ -193,19 +193,19 @@ bool extract_mip_sensor_scaled_pressure_data_from_field(const mip_field* field, { assert(ptr); mip_sensor_scaled_pressure_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_pressure_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_delta_theta_data(mip_serializer* serializer, const mip_sensor_delta_theta_data* self) +void insert_mip_sensor_delta_theta_data(microstrain_serializer* serializer, const mip_sensor_delta_theta_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->delta_theta[i]); } -void extract_mip_sensor_delta_theta_data(mip_serializer* serializer, mip_sensor_delta_theta_data* self) +void extract_mip_sensor_delta_theta_data(microstrain_serializer* serializer, mip_sensor_delta_theta_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->delta_theta[i]); @@ -215,19 +215,19 @@ bool extract_mip_sensor_delta_theta_data_from_field(const mip_field* field, void { assert(ptr); mip_sensor_delta_theta_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_delta_theta_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_delta_velocity_data(mip_serializer* serializer, const mip_sensor_delta_velocity_data* self) +void insert_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, const mip_sensor_delta_velocity_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->delta_velocity[i]); } -void extract_mip_sensor_delta_velocity_data(mip_serializer* serializer, mip_sensor_delta_velocity_data* self) +void extract_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, mip_sensor_delta_velocity_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->delta_velocity[i]); @@ -237,19 +237,19 @@ bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field* field, v { assert(ptr); mip_sensor_delta_velocity_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_delta_velocity_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_comp_orientation_matrix_data(mip_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self) +void insert_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->m[i]); } -void extract_mip_sensor_comp_orientation_matrix_data(mip_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self) +void extract_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->m[i]); @@ -259,19 +259,19 @@ bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const mip_field* { assert(ptr); mip_sensor_comp_orientation_matrix_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_orientation_matrix_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_comp_quaternion_data(mip_serializer* serializer, const mip_sensor_comp_quaternion_data* self) +void insert_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, const mip_sensor_comp_quaternion_data* self) { for(unsigned int i=0; i < 4; i++) microstrain_insert_float(serializer, self->q[i]); } -void extract_mip_sensor_comp_quaternion_data(mip_serializer* serializer, mip_sensor_comp_quaternion_data* self) +void extract_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, mip_sensor_comp_quaternion_data* self) { for(unsigned int i=0; i < 4; i++) microstrain_extract_float(serializer, &self->q[i]); @@ -281,13 +281,13 @@ bool extract_mip_sensor_comp_quaternion_data_from_field(const mip_field* field, { assert(ptr); mip_sensor_comp_quaternion_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_quaternion_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_comp_euler_angles_data(mip_serializer* serializer, const mip_sensor_comp_euler_angles_data* self) +void insert_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, const mip_sensor_comp_euler_angles_data* self) { microstrain_insert_float(serializer, self->roll); @@ -296,7 +296,7 @@ void insert_mip_sensor_comp_euler_angles_data(mip_serializer* serializer, const microstrain_insert_float(serializer, self->yaw); } -void extract_mip_sensor_comp_euler_angles_data(mip_serializer* serializer, mip_sensor_comp_euler_angles_data* self) +void extract_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, mip_sensor_comp_euler_angles_data* self) { microstrain_extract_float(serializer, &self->roll); @@ -309,19 +309,19 @@ bool extract_mip_sensor_comp_euler_angles_data_from_field(const mip_field* field { assert(ptr); mip_sensor_comp_euler_angles_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_euler_angles_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_comp_orientation_update_matrix_data(mip_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self) +void insert_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_insert_float(serializer, self->m[i]); } -void extract_mip_sensor_comp_orientation_update_matrix_data(mip_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self) +void extract_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self) { for(unsigned int i=0; i < 9; i++) microstrain_extract_float(serializer, &self->m[i]); @@ -331,19 +331,19 @@ bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const mip { assert(ptr); mip_sensor_comp_orientation_update_matrix_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_orientation_update_matrix_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_orientation_raw_temp_data(mip_serializer* serializer, const mip_sensor_orientation_raw_temp_data* self) +void insert_mip_sensor_orientation_raw_temp_data(microstrain_serializer* serializer, const mip_sensor_orientation_raw_temp_data* self) { for(unsigned int i=0; i < 4; i++) microstrain_insert_u16(serializer, self->raw_temp[i]); } -void extract_mip_sensor_orientation_raw_temp_data(mip_serializer* serializer, mip_sensor_orientation_raw_temp_data* self) +void extract_mip_sensor_orientation_raw_temp_data(microstrain_serializer* serializer, mip_sensor_orientation_raw_temp_data* self) { for(unsigned int i=0; i < 4; i++) microstrain_extract_u16(serializer, &self->raw_temp[i]); @@ -353,18 +353,18 @@ bool extract_mip_sensor_orientation_raw_temp_data_from_field(const mip_field* fi { assert(ptr); mip_sensor_orientation_raw_temp_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_orientation_raw_temp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_internal_timestamp_data(mip_serializer* serializer, const mip_sensor_internal_timestamp_data* self) +void insert_mip_sensor_internal_timestamp_data(microstrain_serializer* serializer, const mip_sensor_internal_timestamp_data* self) { microstrain_insert_u32(serializer, self->counts); } -void extract_mip_sensor_internal_timestamp_data(mip_serializer* serializer, mip_sensor_internal_timestamp_data* self) +void extract_mip_sensor_internal_timestamp_data(microstrain_serializer* serializer, mip_sensor_internal_timestamp_data* self) { microstrain_extract_u32(serializer, &self->counts); @@ -373,20 +373,20 @@ bool extract_mip_sensor_internal_timestamp_data_from_field(const mip_field* fiel { assert(ptr); mip_sensor_internal_timestamp_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_internal_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_pps_timestamp_data(mip_serializer* serializer, const mip_sensor_pps_timestamp_data* self) +void insert_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_pps_timestamp_data* self) { microstrain_insert_u32(serializer, self->seconds); microstrain_insert_u32(serializer, self->useconds); } -void extract_mip_sensor_pps_timestamp_data(mip_serializer* serializer, mip_sensor_pps_timestamp_data* self) +void extract_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, mip_sensor_pps_timestamp_data* self) { microstrain_extract_u32(serializer, &self->seconds); @@ -397,13 +397,13 @@ bool extract_mip_sensor_pps_timestamp_data_from_field(const mip_field* field, vo { assert(ptr); mip_sensor_pps_timestamp_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_pps_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_gps_timestamp_data(mip_serializer* serializer, const mip_sensor_gps_timestamp_data* self) +void insert_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data* self) { microstrain_insert_double(serializer, self->tow); @@ -412,7 +412,7 @@ void insert_mip_sensor_gps_timestamp_data(mip_serializer* serializer, const mip_ insert_mip_sensor_gps_timestamp_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_sensor_gps_timestamp_data(mip_serializer* serializer, mip_sensor_gps_timestamp_data* self) +void extract_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data* self) { microstrain_extract_double(serializer, &self->tow); @@ -425,24 +425,24 @@ bool extract_mip_sensor_gps_timestamp_data_from_field(const mip_field* field, vo { assert(ptr); mip_sensor_gps_timestamp_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_gps_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self) +void insert_mip_sensor_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_sensor_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self) +void extract_mip_sensor_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_sensor_temperature_abs_data(mip_serializer* serializer, const mip_sensor_temperature_abs_data* self) +void insert_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, const mip_sensor_temperature_abs_data* self) { microstrain_insert_float(serializer, self->min_temp); @@ -451,7 +451,7 @@ void insert_mip_sensor_temperature_abs_data(mip_serializer* serializer, const mi microstrain_insert_float(serializer, self->mean_temp); } -void extract_mip_sensor_temperature_abs_data(mip_serializer* serializer, mip_sensor_temperature_abs_data* self) +void extract_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, mip_sensor_temperature_abs_data* self) { microstrain_extract_float(serializer, &self->min_temp); @@ -464,19 +464,19 @@ bool extract_mip_sensor_temperature_abs_data_from_field(const mip_field* field, { assert(ptr); mip_sensor_temperature_abs_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_temperature_abs_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_up_vector_data(mip_serializer* serializer, const mip_sensor_up_vector_data* self) +void insert_mip_sensor_up_vector_data(microstrain_serializer* serializer, const mip_sensor_up_vector_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->up[i]); } -void extract_mip_sensor_up_vector_data(mip_serializer* serializer, mip_sensor_up_vector_data* self) +void extract_mip_sensor_up_vector_data(microstrain_serializer* serializer, mip_sensor_up_vector_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->up[i]); @@ -486,19 +486,19 @@ bool extract_mip_sensor_up_vector_data_from_field(const mip_field* field, void* { assert(ptr); mip_sensor_up_vector_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_up_vector_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_north_vector_data(mip_serializer* serializer, const mip_sensor_north_vector_data* self) +void insert_mip_sensor_north_vector_data(microstrain_serializer* serializer, const mip_sensor_north_vector_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_insert_float(serializer, self->north[i]); } -void extract_mip_sensor_north_vector_data(mip_serializer* serializer, mip_sensor_north_vector_data* self) +void extract_mip_sensor_north_vector_data(microstrain_serializer* serializer, mip_sensor_north_vector_data* self) { for(unsigned int i=0; i < 3; i++) microstrain_extract_float(serializer, &self->north[i]); @@ -508,18 +508,18 @@ bool extract_mip_sensor_north_vector_data_from_field(const mip_field* field, voi { assert(ptr); mip_sensor_north_vector_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_north_vector_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_overrange_status_data(mip_serializer* serializer, const mip_sensor_overrange_status_data* self) +void insert_mip_sensor_overrange_status_data(microstrain_serializer* serializer, const mip_sensor_overrange_status_data* self) { insert_mip_sensor_overrange_status_data_status(serializer, self->status); } -void extract_mip_sensor_overrange_status_data(mip_serializer* serializer, mip_sensor_overrange_status_data* self) +void extract_mip_sensor_overrange_status_data(microstrain_serializer* serializer, mip_sensor_overrange_status_data* self) { extract_mip_sensor_overrange_status_data_status(serializer, &self->status); @@ -528,24 +528,24 @@ bool extract_mip_sensor_overrange_status_data_from_field(const mip_field* field, { assert(ptr); mip_sensor_overrange_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_overrange_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_overrange_status_data_status(struct mip_serializer* serializer, const mip_sensor_overrange_status_data_status self) +void insert_mip_sensor_overrange_status_data_status(struct microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_sensor_overrange_status_data_status(struct mip_serializer* serializer, mip_sensor_overrange_status_data_status* self) +void extract_mip_sensor_overrange_status_data_status(struct microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_sensor_odometer_data_data(mip_serializer* serializer, const mip_sensor_odometer_data_data* self) +void insert_mip_sensor_odometer_data_data(microstrain_serializer* serializer, const mip_sensor_odometer_data_data* self) { microstrain_insert_float(serializer, self->speed); @@ -554,7 +554,7 @@ void insert_mip_sensor_odometer_data_data(mip_serializer* serializer, const mip_ microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_sensor_odometer_data_data(mip_serializer* serializer, mip_sensor_odometer_data_data* self) +void extract_mip_sensor_odometer_data_data(microstrain_serializer* serializer, mip_sensor_odometer_data_data* self) { microstrain_extract_float(serializer, &self->speed); @@ -567,8 +567,8 @@ bool extract_mip_sensor_odometer_data_data_from_field(const mip_field* field, vo { assert(ptr); mip_sensor_odometer_data_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_odometer_data_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } diff --git a/src/mip/definitions/data_sensor.h b/src/mip/definitions/data_sensor.h index bae38d0a0..c280064d2 100644 --- a/src/mip/definitions/data_sensor.h +++ b/src/mip/definitions/data_sensor.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -84,8 +84,8 @@ struct mip_sensor_raw_accel_data }; typedef struct mip_sensor_raw_accel_data mip_sensor_raw_accel_data; -void insert_mip_sensor_raw_accel_data(struct mip_serializer* serializer, const mip_sensor_raw_accel_data* self); -void extract_mip_sensor_raw_accel_data(struct mip_serializer* serializer, mip_sensor_raw_accel_data* self); +void insert_mip_sensor_raw_accel_data(struct microstrain_serializer* serializer, const mip_sensor_raw_accel_data* self); +void extract_mip_sensor_raw_accel_data(struct microstrain_serializer* serializer, mip_sensor_raw_accel_data* self); bool extract_mip_sensor_raw_accel_data_from_field(const struct mip_field* field, void* ptr); @@ -104,8 +104,8 @@ struct mip_sensor_raw_gyro_data }; typedef struct mip_sensor_raw_gyro_data mip_sensor_raw_gyro_data; -void insert_mip_sensor_raw_gyro_data(struct mip_serializer* serializer, const mip_sensor_raw_gyro_data* self); -void extract_mip_sensor_raw_gyro_data(struct mip_serializer* serializer, mip_sensor_raw_gyro_data* self); +void insert_mip_sensor_raw_gyro_data(struct microstrain_serializer* serializer, const mip_sensor_raw_gyro_data* self); +void extract_mip_sensor_raw_gyro_data(struct microstrain_serializer* serializer, mip_sensor_raw_gyro_data* self); bool extract_mip_sensor_raw_gyro_data_from_field(const struct mip_field* field, void* ptr); @@ -124,8 +124,8 @@ struct mip_sensor_raw_mag_data }; typedef struct mip_sensor_raw_mag_data mip_sensor_raw_mag_data; -void insert_mip_sensor_raw_mag_data(struct mip_serializer* serializer, const mip_sensor_raw_mag_data* self); -void extract_mip_sensor_raw_mag_data(struct mip_serializer* serializer, mip_sensor_raw_mag_data* self); +void insert_mip_sensor_raw_mag_data(struct microstrain_serializer* serializer, const mip_sensor_raw_mag_data* self); +void extract_mip_sensor_raw_mag_data(struct microstrain_serializer* serializer, mip_sensor_raw_mag_data* self); bool extract_mip_sensor_raw_mag_data_from_field(const struct mip_field* field, void* ptr); @@ -144,8 +144,8 @@ struct mip_sensor_raw_pressure_data }; typedef struct mip_sensor_raw_pressure_data mip_sensor_raw_pressure_data; -void insert_mip_sensor_raw_pressure_data(struct mip_serializer* serializer, const mip_sensor_raw_pressure_data* self); -void extract_mip_sensor_raw_pressure_data(struct mip_serializer* serializer, mip_sensor_raw_pressure_data* self); +void insert_mip_sensor_raw_pressure_data(struct microstrain_serializer* serializer, const mip_sensor_raw_pressure_data* self); +void extract_mip_sensor_raw_pressure_data(struct microstrain_serializer* serializer, mip_sensor_raw_pressure_data* self); bool extract_mip_sensor_raw_pressure_data_from_field(const struct mip_field* field, void* ptr); @@ -164,8 +164,8 @@ struct mip_sensor_scaled_accel_data }; typedef struct mip_sensor_scaled_accel_data mip_sensor_scaled_accel_data; -void insert_mip_sensor_scaled_accel_data(struct mip_serializer* serializer, const mip_sensor_scaled_accel_data* self); -void extract_mip_sensor_scaled_accel_data(struct mip_serializer* serializer, mip_sensor_scaled_accel_data* self); +void insert_mip_sensor_scaled_accel_data(struct microstrain_serializer* serializer, const mip_sensor_scaled_accel_data* self); +void extract_mip_sensor_scaled_accel_data(struct microstrain_serializer* serializer, mip_sensor_scaled_accel_data* self); bool extract_mip_sensor_scaled_accel_data_from_field(const struct mip_field* field, void* ptr); @@ -184,8 +184,8 @@ struct mip_sensor_scaled_gyro_data }; typedef struct mip_sensor_scaled_gyro_data mip_sensor_scaled_gyro_data; -void insert_mip_sensor_scaled_gyro_data(struct mip_serializer* serializer, const mip_sensor_scaled_gyro_data* self); -void extract_mip_sensor_scaled_gyro_data(struct mip_serializer* serializer, mip_sensor_scaled_gyro_data* self); +void insert_mip_sensor_scaled_gyro_data(struct microstrain_serializer* serializer, const mip_sensor_scaled_gyro_data* self); +void extract_mip_sensor_scaled_gyro_data(struct microstrain_serializer* serializer, mip_sensor_scaled_gyro_data* self); bool extract_mip_sensor_scaled_gyro_data_from_field(const struct mip_field* field, void* ptr); @@ -204,8 +204,8 @@ struct mip_sensor_scaled_mag_data }; typedef struct mip_sensor_scaled_mag_data mip_sensor_scaled_mag_data; -void insert_mip_sensor_scaled_mag_data(struct mip_serializer* serializer, const mip_sensor_scaled_mag_data* self); -void extract_mip_sensor_scaled_mag_data(struct mip_serializer* serializer, mip_sensor_scaled_mag_data* self); +void insert_mip_sensor_scaled_mag_data(struct microstrain_serializer* serializer, const mip_sensor_scaled_mag_data* self); +void extract_mip_sensor_scaled_mag_data(struct microstrain_serializer* serializer, mip_sensor_scaled_mag_data* self); bool extract_mip_sensor_scaled_mag_data_from_field(const struct mip_field* field, void* ptr); @@ -223,8 +223,8 @@ struct mip_sensor_scaled_pressure_data }; typedef struct mip_sensor_scaled_pressure_data mip_sensor_scaled_pressure_data; -void insert_mip_sensor_scaled_pressure_data(struct mip_serializer* serializer, const mip_sensor_scaled_pressure_data* self); -void extract_mip_sensor_scaled_pressure_data(struct mip_serializer* serializer, mip_sensor_scaled_pressure_data* self); +void insert_mip_sensor_scaled_pressure_data(struct microstrain_serializer* serializer, const mip_sensor_scaled_pressure_data* self); +void extract_mip_sensor_scaled_pressure_data(struct microstrain_serializer* serializer, mip_sensor_scaled_pressure_data* self); bool extract_mip_sensor_scaled_pressure_data_from_field(const struct mip_field* field, void* ptr); @@ -243,8 +243,8 @@ struct mip_sensor_delta_theta_data }; typedef struct mip_sensor_delta_theta_data mip_sensor_delta_theta_data; -void insert_mip_sensor_delta_theta_data(struct mip_serializer* serializer, const mip_sensor_delta_theta_data* self); -void extract_mip_sensor_delta_theta_data(struct mip_serializer* serializer, mip_sensor_delta_theta_data* self); +void insert_mip_sensor_delta_theta_data(struct microstrain_serializer* serializer, const mip_sensor_delta_theta_data* self); +void extract_mip_sensor_delta_theta_data(struct microstrain_serializer* serializer, mip_sensor_delta_theta_data* self); bool extract_mip_sensor_delta_theta_data_from_field(const struct mip_field* field, void* ptr); @@ -263,8 +263,8 @@ struct mip_sensor_delta_velocity_data }; typedef struct mip_sensor_delta_velocity_data mip_sensor_delta_velocity_data; -void insert_mip_sensor_delta_velocity_data(struct mip_serializer* serializer, const mip_sensor_delta_velocity_data* self); -void extract_mip_sensor_delta_velocity_data(struct mip_serializer* serializer, mip_sensor_delta_velocity_data* self); +void insert_mip_sensor_delta_velocity_data(struct microstrain_serializer* serializer, const mip_sensor_delta_velocity_data* self); +void extract_mip_sensor_delta_velocity_data(struct microstrain_serializer* serializer, mip_sensor_delta_velocity_data* self); bool extract_mip_sensor_delta_velocity_data_from_field(const struct mip_field* field, void* ptr); @@ -292,8 +292,8 @@ struct mip_sensor_comp_orientation_matrix_data }; typedef struct mip_sensor_comp_orientation_matrix_data mip_sensor_comp_orientation_matrix_data; -void insert_mip_sensor_comp_orientation_matrix_data(struct mip_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self); -void extract_mip_sensor_comp_orientation_matrix_data(struct mip_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self); +void insert_mip_sensor_comp_orientation_matrix_data(struct microstrain_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self); +void extract_mip_sensor_comp_orientation_matrix_data(struct microstrain_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self); bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const struct mip_field* field, void* ptr); @@ -319,8 +319,8 @@ struct mip_sensor_comp_quaternion_data }; typedef struct mip_sensor_comp_quaternion_data mip_sensor_comp_quaternion_data; -void insert_mip_sensor_comp_quaternion_data(struct mip_serializer* serializer, const mip_sensor_comp_quaternion_data* self); -void extract_mip_sensor_comp_quaternion_data(struct mip_serializer* serializer, mip_sensor_comp_quaternion_data* self); +void insert_mip_sensor_comp_quaternion_data(struct microstrain_serializer* serializer, const mip_sensor_comp_quaternion_data* self); +void extract_mip_sensor_comp_quaternion_data(struct microstrain_serializer* serializer, mip_sensor_comp_quaternion_data* self); bool extract_mip_sensor_comp_quaternion_data_from_field(const struct mip_field* field, void* ptr); @@ -341,8 +341,8 @@ struct mip_sensor_comp_euler_angles_data }; typedef struct mip_sensor_comp_euler_angles_data mip_sensor_comp_euler_angles_data; -void insert_mip_sensor_comp_euler_angles_data(struct mip_serializer* serializer, const mip_sensor_comp_euler_angles_data* self); -void extract_mip_sensor_comp_euler_angles_data(struct mip_serializer* serializer, mip_sensor_comp_euler_angles_data* self); +void insert_mip_sensor_comp_euler_angles_data(struct microstrain_serializer* serializer, const mip_sensor_comp_euler_angles_data* self); +void extract_mip_sensor_comp_euler_angles_data(struct microstrain_serializer* serializer, mip_sensor_comp_euler_angles_data* self); bool extract_mip_sensor_comp_euler_angles_data_from_field(const struct mip_field* field, void* ptr); @@ -360,8 +360,8 @@ struct mip_sensor_comp_orientation_update_matrix_data }; typedef struct mip_sensor_comp_orientation_update_matrix_data mip_sensor_comp_orientation_update_matrix_data; -void insert_mip_sensor_comp_orientation_update_matrix_data(struct mip_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self); -void extract_mip_sensor_comp_orientation_update_matrix_data(struct mip_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self); +void insert_mip_sensor_comp_orientation_update_matrix_data(struct microstrain_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self); +void extract_mip_sensor_comp_orientation_update_matrix_data(struct microstrain_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self); bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const struct mip_field* field, void* ptr); @@ -379,8 +379,8 @@ struct mip_sensor_orientation_raw_temp_data }; typedef struct mip_sensor_orientation_raw_temp_data mip_sensor_orientation_raw_temp_data; -void insert_mip_sensor_orientation_raw_temp_data(struct mip_serializer* serializer, const mip_sensor_orientation_raw_temp_data* self); -void extract_mip_sensor_orientation_raw_temp_data(struct mip_serializer* serializer, mip_sensor_orientation_raw_temp_data* self); +void insert_mip_sensor_orientation_raw_temp_data(struct microstrain_serializer* serializer, const mip_sensor_orientation_raw_temp_data* self); +void extract_mip_sensor_orientation_raw_temp_data(struct microstrain_serializer* serializer, mip_sensor_orientation_raw_temp_data* self); bool extract_mip_sensor_orientation_raw_temp_data_from_field(const struct mip_field* field, void* ptr); @@ -398,8 +398,8 @@ struct mip_sensor_internal_timestamp_data }; typedef struct mip_sensor_internal_timestamp_data mip_sensor_internal_timestamp_data; -void insert_mip_sensor_internal_timestamp_data(struct mip_serializer* serializer, const mip_sensor_internal_timestamp_data* self); -void extract_mip_sensor_internal_timestamp_data(struct mip_serializer* serializer, mip_sensor_internal_timestamp_data* self); +void insert_mip_sensor_internal_timestamp_data(struct microstrain_serializer* serializer, const mip_sensor_internal_timestamp_data* self); +void extract_mip_sensor_internal_timestamp_data(struct microstrain_serializer* serializer, mip_sensor_internal_timestamp_data* self); bool extract_mip_sensor_internal_timestamp_data_from_field(const struct mip_field* field, void* ptr); @@ -418,8 +418,8 @@ struct mip_sensor_pps_timestamp_data }; typedef struct mip_sensor_pps_timestamp_data mip_sensor_pps_timestamp_data; -void insert_mip_sensor_pps_timestamp_data(struct mip_serializer* serializer, const mip_sensor_pps_timestamp_data* self); -void extract_mip_sensor_pps_timestamp_data(struct mip_serializer* serializer, mip_sensor_pps_timestamp_data* self); +void insert_mip_sensor_pps_timestamp_data(struct microstrain_serializer* serializer, const mip_sensor_pps_timestamp_data* self); +void extract_mip_sensor_pps_timestamp_data(struct microstrain_serializer* serializer, mip_sensor_pps_timestamp_data* self); bool extract_mip_sensor_pps_timestamp_data_from_field(const struct mip_field* field, void* ptr); @@ -454,12 +454,12 @@ struct mip_sensor_gps_timestamp_data }; typedef struct mip_sensor_gps_timestamp_data mip_sensor_gps_timestamp_data; -void insert_mip_sensor_gps_timestamp_data(struct mip_serializer* serializer, const mip_sensor_gps_timestamp_data* self); -void extract_mip_sensor_gps_timestamp_data(struct mip_serializer* serializer, mip_sensor_gps_timestamp_data* self); +void insert_mip_sensor_gps_timestamp_data(struct microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data* self); +void extract_mip_sensor_gps_timestamp_data(struct microstrain_serializer* serializer, mip_sensor_gps_timestamp_data* self); bool extract_mip_sensor_gps_timestamp_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_sensor_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self); -void extract_mip_sensor_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self); +void insert_mip_sensor_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self); +void extract_mip_sensor_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self); ///@} @@ -482,8 +482,8 @@ struct mip_sensor_temperature_abs_data }; typedef struct mip_sensor_temperature_abs_data mip_sensor_temperature_abs_data; -void insert_mip_sensor_temperature_abs_data(struct mip_serializer* serializer, const mip_sensor_temperature_abs_data* self); -void extract_mip_sensor_temperature_abs_data(struct mip_serializer* serializer, mip_sensor_temperature_abs_data* self); +void insert_mip_sensor_temperature_abs_data(struct microstrain_serializer* serializer, const mip_sensor_temperature_abs_data* self); +void extract_mip_sensor_temperature_abs_data(struct microstrain_serializer* serializer, mip_sensor_temperature_abs_data* self); bool extract_mip_sensor_temperature_abs_data_from_field(const struct mip_field* field, void* ptr); @@ -507,8 +507,8 @@ struct mip_sensor_up_vector_data }; typedef struct mip_sensor_up_vector_data mip_sensor_up_vector_data; -void insert_mip_sensor_up_vector_data(struct mip_serializer* serializer, const mip_sensor_up_vector_data* self); -void extract_mip_sensor_up_vector_data(struct mip_serializer* serializer, mip_sensor_up_vector_data* self); +void insert_mip_sensor_up_vector_data(struct microstrain_serializer* serializer, const mip_sensor_up_vector_data* self); +void extract_mip_sensor_up_vector_data(struct microstrain_serializer* serializer, mip_sensor_up_vector_data* self); bool extract_mip_sensor_up_vector_data_from_field(const struct mip_field* field, void* ptr); @@ -529,8 +529,8 @@ struct mip_sensor_north_vector_data }; typedef struct mip_sensor_north_vector_data mip_sensor_north_vector_data; -void insert_mip_sensor_north_vector_data(struct mip_serializer* serializer, const mip_sensor_north_vector_data* self); -void extract_mip_sensor_north_vector_data(struct mip_serializer* serializer, mip_sensor_north_vector_data* self); +void insert_mip_sensor_north_vector_data(struct microstrain_serializer* serializer, const mip_sensor_north_vector_data* self); +void extract_mip_sensor_north_vector_data(struct microstrain_serializer* serializer, mip_sensor_north_vector_data* self); bool extract_mip_sensor_north_vector_data_from_field(const struct mip_field* field, void* ptr); @@ -561,12 +561,12 @@ struct mip_sensor_overrange_status_data }; typedef struct mip_sensor_overrange_status_data mip_sensor_overrange_status_data; -void insert_mip_sensor_overrange_status_data(struct mip_serializer* serializer, const mip_sensor_overrange_status_data* self); -void extract_mip_sensor_overrange_status_data(struct mip_serializer* serializer, mip_sensor_overrange_status_data* self); +void insert_mip_sensor_overrange_status_data(struct microstrain_serializer* serializer, const mip_sensor_overrange_status_data* self); +void extract_mip_sensor_overrange_status_data(struct microstrain_serializer* serializer, mip_sensor_overrange_status_data* self); bool extract_mip_sensor_overrange_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_sensor_overrange_status_data_status(struct mip_serializer* serializer, const mip_sensor_overrange_status_data_status self); -void extract_mip_sensor_overrange_status_data_status(struct mip_serializer* serializer, mip_sensor_overrange_status_data_status* self); +void insert_mip_sensor_overrange_status_data_status(struct microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self); +void extract_mip_sensor_overrange_status_data_status(struct microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self); ///@} @@ -584,8 +584,8 @@ struct mip_sensor_odometer_data_data }; typedef struct mip_sensor_odometer_data_data mip_sensor_odometer_data_data; -void insert_mip_sensor_odometer_data_data(struct mip_serializer* serializer, const mip_sensor_odometer_data_data* self); -void extract_mip_sensor_odometer_data_data(struct mip_serializer* serializer, mip_sensor_odometer_data_data* self); +void insert_mip_sensor_odometer_data_data(struct microstrain_serializer* serializer, const mip_sensor_odometer_data_data* self); +void extract_mip_sensor_odometer_data_data(struct microstrain_serializer* serializer, mip_sensor_odometer_data_data* self); bool extract_mip_sensor_odometer_data_data_from_field(const struct mip_field* field, void* ptr); diff --git a/src/mip/definitions/data_shared.c b/src/mip/definitions/data_shared.c index 03b335e94..fcc5d97a1 100644 --- a/src/mip/definitions/data_shared.c +++ b/src/mip/definitions/data_shared.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -27,12 +27,12 @@ struct mip_field; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_shared_event_source_data(mip_serializer* serializer, const mip_shared_event_source_data* self) +void insert_mip_shared_event_source_data(microstrain_serializer* serializer, const mip_shared_event_source_data* self) { microstrain_insert_u8(serializer, self->trigger_id); } -void extract_mip_shared_event_source_data(mip_serializer* serializer, mip_shared_event_source_data* self) +void extract_mip_shared_event_source_data(microstrain_serializer* serializer, mip_shared_event_source_data* self) { microstrain_extract_u8(serializer, &self->trigger_id); @@ -41,18 +41,18 @@ bool extract_mip_shared_event_source_data_from_field(const mip_field* field, voi { assert(ptr); mip_shared_event_source_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_event_source_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_ticks_data(mip_serializer* serializer, const mip_shared_ticks_data* self) +void insert_mip_shared_ticks_data(microstrain_serializer* serializer, const mip_shared_ticks_data* self) { microstrain_insert_u32(serializer, self->ticks); } -void extract_mip_shared_ticks_data(mip_serializer* serializer, mip_shared_ticks_data* self) +void extract_mip_shared_ticks_data(microstrain_serializer* serializer, mip_shared_ticks_data* self) { microstrain_extract_u32(serializer, &self->ticks); @@ -61,18 +61,18 @@ bool extract_mip_shared_ticks_data_from_field(const mip_field* field, void* ptr) { assert(ptr); mip_shared_ticks_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_ticks_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_delta_ticks_data(mip_serializer* serializer, const mip_shared_delta_ticks_data* self) +void insert_mip_shared_delta_ticks_data(microstrain_serializer* serializer, const mip_shared_delta_ticks_data* self) { microstrain_insert_u32(serializer, self->ticks); } -void extract_mip_shared_delta_ticks_data(mip_serializer* serializer, mip_shared_delta_ticks_data* self) +void extract_mip_shared_delta_ticks_data(microstrain_serializer* serializer, mip_shared_delta_ticks_data* self) { microstrain_extract_u32(serializer, &self->ticks); @@ -81,13 +81,13 @@ bool extract_mip_shared_delta_ticks_data_from_field(const mip_field* field, void { assert(ptr); mip_shared_delta_ticks_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_delta_ticks_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_gps_timestamp_data(mip_serializer* serializer, const mip_shared_gps_timestamp_data* self) +void insert_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data* self) { microstrain_insert_double(serializer, self->tow); @@ -96,7 +96,7 @@ void insert_mip_shared_gps_timestamp_data(mip_serializer* serializer, const mip_ insert_mip_shared_gps_timestamp_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_shared_gps_timestamp_data(mip_serializer* serializer, mip_shared_gps_timestamp_data* self) +void extract_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, mip_shared_gps_timestamp_data* self) { microstrain_extract_double(serializer, &self->tow); @@ -109,29 +109,29 @@ bool extract_mip_shared_gps_timestamp_data_from_field(const mip_field* field, vo { assert(ptr); mip_shared_gps_timestamp_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_gps_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self) +void insert_mip_shared_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_shared_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self) +void extract_mip_shared_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_shared_delta_time_data(mip_serializer* serializer, const mip_shared_delta_time_data* self) +void insert_mip_shared_delta_time_data(microstrain_serializer* serializer, const mip_shared_delta_time_data* self) { microstrain_insert_double(serializer, self->seconds); } -void extract_mip_shared_delta_time_data(mip_serializer* serializer, mip_shared_delta_time_data* self) +void extract_mip_shared_delta_time_data(microstrain_serializer* serializer, mip_shared_delta_time_data* self) { microstrain_extract_double(serializer, &self->seconds); @@ -140,18 +140,18 @@ bool extract_mip_shared_delta_time_data_from_field(const mip_field* field, void* { assert(ptr); mip_shared_delta_time_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_delta_time_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_reference_timestamp_data(mip_serializer* serializer, const mip_shared_reference_timestamp_data* self) +void insert_mip_shared_reference_timestamp_data(microstrain_serializer* serializer, const mip_shared_reference_timestamp_data* self) { microstrain_insert_u64(serializer, self->nanoseconds); } -void extract_mip_shared_reference_timestamp_data(mip_serializer* serializer, mip_shared_reference_timestamp_data* self) +void extract_mip_shared_reference_timestamp_data(microstrain_serializer* serializer, mip_shared_reference_timestamp_data* self) { microstrain_extract_u64(serializer, &self->nanoseconds); @@ -160,18 +160,18 @@ bool extract_mip_shared_reference_timestamp_data_from_field(const mip_field* fie { assert(ptr); mip_shared_reference_timestamp_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_reference_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_reference_time_delta_data(mip_serializer* serializer, const mip_shared_reference_time_delta_data* self) +void insert_mip_shared_reference_time_delta_data(microstrain_serializer* serializer, const mip_shared_reference_time_delta_data* self) { microstrain_insert_u64(serializer, self->dt_nanos); } -void extract_mip_shared_reference_time_delta_data(mip_serializer* serializer, mip_shared_reference_time_delta_data* self) +void extract_mip_shared_reference_time_delta_data(microstrain_serializer* serializer, mip_shared_reference_time_delta_data* self) { microstrain_extract_u64(serializer, &self->dt_nanos); @@ -180,20 +180,20 @@ bool extract_mip_shared_reference_time_delta_data_from_field(const mip_field* fi { assert(ptr); mip_shared_reference_time_delta_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_reference_time_delta_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_external_timestamp_data(mip_serializer* serializer, const mip_shared_external_timestamp_data* self) +void insert_mip_shared_external_timestamp_data(microstrain_serializer* serializer, const mip_shared_external_timestamp_data* self) { microstrain_insert_u64(serializer, self->nanoseconds); insert_mip_shared_external_timestamp_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_shared_external_timestamp_data(mip_serializer* serializer, mip_shared_external_timestamp_data* self) +void extract_mip_shared_external_timestamp_data(microstrain_serializer* serializer, mip_shared_external_timestamp_data* self) { microstrain_extract_u64(serializer, &self->nanoseconds); @@ -204,31 +204,31 @@ bool extract_mip_shared_external_timestamp_data_from_field(const mip_field* fiel { assert(ptr); mip_shared_external_timestamp_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_external_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_external_timestamp_data_valid_flags(struct mip_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self) +void insert_mip_shared_external_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_shared_external_timestamp_data_valid_flags(struct mip_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self) +void extract_mip_shared_external_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_shared_external_time_delta_data(mip_serializer* serializer, const mip_shared_external_time_delta_data* self) +void insert_mip_shared_external_time_delta_data(microstrain_serializer* serializer, const mip_shared_external_time_delta_data* self) { microstrain_insert_u64(serializer, self->dt_nanos); insert_mip_shared_external_time_delta_data_valid_flags(serializer, self->valid_flags); } -void extract_mip_shared_external_time_delta_data(mip_serializer* serializer, mip_shared_external_time_delta_data* self) +void extract_mip_shared_external_time_delta_data(microstrain_serializer* serializer, mip_shared_external_time_delta_data* self) { microstrain_extract_u64(serializer, &self->dt_nanos); @@ -239,17 +239,17 @@ bool extract_mip_shared_external_time_delta_data_from_field(const mip_field* fie { assert(ptr); mip_shared_external_time_delta_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_external_time_delta_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_external_time_delta_data_valid_flags(struct mip_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self) +void insert_mip_shared_external_time_delta_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_shared_external_time_delta_data_valid_flags(struct mip_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self) +void extract_mip_shared_external_time_delta_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/mip/definitions/data_shared.h b/src/mip/definitions/data_shared.h index 6c4a0f404..9e7cf172a 100644 --- a/src/mip/definitions/data_shared.h +++ b/src/mip/definitions/data_shared.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -71,8 +71,8 @@ struct mip_shared_event_source_data }; typedef struct mip_shared_event_source_data mip_shared_event_source_data; -void insert_mip_shared_event_source_data(struct mip_serializer* serializer, const mip_shared_event_source_data* self); -void extract_mip_shared_event_source_data(struct mip_serializer* serializer, mip_shared_event_source_data* self); +void insert_mip_shared_event_source_data(struct microstrain_serializer* serializer, const mip_shared_event_source_data* self); +void extract_mip_shared_event_source_data(struct microstrain_serializer* serializer, mip_shared_event_source_data* self); bool extract_mip_shared_event_source_data_from_field(const struct mip_field* field, void* ptr); @@ -93,8 +93,8 @@ struct mip_shared_ticks_data }; typedef struct mip_shared_ticks_data mip_shared_ticks_data; -void insert_mip_shared_ticks_data(struct mip_serializer* serializer, const mip_shared_ticks_data* self); -void extract_mip_shared_ticks_data(struct mip_serializer* serializer, mip_shared_ticks_data* self); +void insert_mip_shared_ticks_data(struct microstrain_serializer* serializer, const mip_shared_ticks_data* self); +void extract_mip_shared_ticks_data(struct microstrain_serializer* serializer, mip_shared_ticks_data* self); bool extract_mip_shared_ticks_data_from_field(const struct mip_field* field, void* ptr); @@ -116,8 +116,8 @@ struct mip_shared_delta_ticks_data }; typedef struct mip_shared_delta_ticks_data mip_shared_delta_ticks_data; -void insert_mip_shared_delta_ticks_data(struct mip_serializer* serializer, const mip_shared_delta_ticks_data* self); -void extract_mip_shared_delta_ticks_data(struct mip_serializer* serializer, mip_shared_delta_ticks_data* self); +void insert_mip_shared_delta_ticks_data(struct microstrain_serializer* serializer, const mip_shared_delta_ticks_data* self); +void extract_mip_shared_delta_ticks_data(struct microstrain_serializer* serializer, mip_shared_delta_ticks_data* self); bool extract_mip_shared_delta_ticks_data_from_field(const struct mip_field* field, void* ptr); @@ -147,12 +147,12 @@ struct mip_shared_gps_timestamp_data }; typedef struct mip_shared_gps_timestamp_data mip_shared_gps_timestamp_data; -void insert_mip_shared_gps_timestamp_data(struct mip_serializer* serializer, const mip_shared_gps_timestamp_data* self); -void extract_mip_shared_gps_timestamp_data(struct mip_serializer* serializer, mip_shared_gps_timestamp_data* self); +void insert_mip_shared_gps_timestamp_data(struct microstrain_serializer* serializer, const mip_shared_gps_timestamp_data* self); +void extract_mip_shared_gps_timestamp_data(struct microstrain_serializer* serializer, mip_shared_gps_timestamp_data* self); bool extract_mip_shared_gps_timestamp_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_shared_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self); -void extract_mip_shared_gps_timestamp_data_valid_flags(struct mip_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self); +void insert_mip_shared_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self); +void extract_mip_shared_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self); ///@} @@ -178,8 +178,8 @@ struct mip_shared_delta_time_data }; typedef struct mip_shared_delta_time_data mip_shared_delta_time_data; -void insert_mip_shared_delta_time_data(struct mip_serializer* serializer, const mip_shared_delta_time_data* self); -void extract_mip_shared_delta_time_data(struct mip_serializer* serializer, mip_shared_delta_time_data* self); +void insert_mip_shared_delta_time_data(struct microstrain_serializer* serializer, const mip_shared_delta_time_data* self); +void extract_mip_shared_delta_time_data(struct microstrain_serializer* serializer, mip_shared_delta_time_data* self); bool extract_mip_shared_delta_time_data_from_field(const struct mip_field* field, void* ptr); @@ -204,8 +204,8 @@ struct mip_shared_reference_timestamp_data }; typedef struct mip_shared_reference_timestamp_data mip_shared_reference_timestamp_data; -void insert_mip_shared_reference_timestamp_data(struct mip_serializer* serializer, const mip_shared_reference_timestamp_data* self); -void extract_mip_shared_reference_timestamp_data(struct mip_serializer* serializer, mip_shared_reference_timestamp_data* self); +void insert_mip_shared_reference_timestamp_data(struct microstrain_serializer* serializer, const mip_shared_reference_timestamp_data* self); +void extract_mip_shared_reference_timestamp_data(struct microstrain_serializer* serializer, mip_shared_reference_timestamp_data* self); bool extract_mip_shared_reference_timestamp_data_from_field(const struct mip_field* field, void* ptr); @@ -232,8 +232,8 @@ struct mip_shared_reference_time_delta_data }; typedef struct mip_shared_reference_time_delta_data mip_shared_reference_time_delta_data; -void insert_mip_shared_reference_time_delta_data(struct mip_serializer* serializer, const mip_shared_reference_time_delta_data* self); -void extract_mip_shared_reference_time_delta_data(struct mip_serializer* serializer, mip_shared_reference_time_delta_data* self); +void insert_mip_shared_reference_time_delta_data(struct microstrain_serializer* serializer, const mip_shared_reference_time_delta_data* self); +void extract_mip_shared_reference_time_delta_data(struct microstrain_serializer* serializer, mip_shared_reference_time_delta_data* self); bool extract_mip_shared_reference_time_delta_data_from_field(const struct mip_field* field, void* ptr); @@ -265,12 +265,12 @@ struct mip_shared_external_timestamp_data }; typedef struct mip_shared_external_timestamp_data mip_shared_external_timestamp_data; -void insert_mip_shared_external_timestamp_data(struct mip_serializer* serializer, const mip_shared_external_timestamp_data* self); -void extract_mip_shared_external_timestamp_data(struct mip_serializer* serializer, mip_shared_external_timestamp_data* self); +void insert_mip_shared_external_timestamp_data(struct microstrain_serializer* serializer, const mip_shared_external_timestamp_data* self); +void extract_mip_shared_external_timestamp_data(struct microstrain_serializer* serializer, mip_shared_external_timestamp_data* self); bool extract_mip_shared_external_timestamp_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_shared_external_timestamp_data_valid_flags(struct mip_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self); -void extract_mip_shared_external_timestamp_data_valid_flags(struct mip_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self); +void insert_mip_shared_external_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self); +void extract_mip_shared_external_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self); ///@} @@ -305,12 +305,12 @@ struct mip_shared_external_time_delta_data }; typedef struct mip_shared_external_time_delta_data mip_shared_external_time_delta_data; -void insert_mip_shared_external_time_delta_data(struct mip_serializer* serializer, const mip_shared_external_time_delta_data* self); -void extract_mip_shared_external_time_delta_data(struct mip_serializer* serializer, mip_shared_external_time_delta_data* self); +void insert_mip_shared_external_time_delta_data(struct microstrain_serializer* serializer, const mip_shared_external_time_delta_data* self); +void extract_mip_shared_external_time_delta_data(struct microstrain_serializer* serializer, mip_shared_external_time_delta_data* self); bool extract_mip_shared_external_time_delta_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_shared_external_time_delta_data_valid_flags(struct mip_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self); -void extract_mip_shared_external_time_delta_data_valid_flags(struct mip_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self); +void insert_mip_shared_external_time_delta_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self); +void extract_mip_shared_external_time_delta_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self); ///@} diff --git a/src/mip/definitions/data_system.c b/src/mip/definitions/data_system.c index b0c736bc9..b37350e0a 100644 --- a/src/mip/definitions/data_system.c +++ b/src/mip/definitions/data_system.c @@ -14,7 +14,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; @@ -27,13 +27,13 @@ struct mip_field; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_system_built_in_test_data(mip_serializer* serializer, const mip_system_built_in_test_data* self) +void insert_mip_system_built_in_test_data(microstrain_serializer* serializer, const mip_system_built_in_test_data* self) { for(unsigned int i=0; i < 16; i++) microstrain_insert_u8(serializer, self->result[i]); } -void extract_mip_system_built_in_test_data(mip_serializer* serializer, mip_system_built_in_test_data* self) +void extract_mip_system_built_in_test_data(microstrain_serializer* serializer, mip_system_built_in_test_data* self) { for(unsigned int i=0; i < 16; i++) microstrain_extract_u8(serializer, &self->result[i]); @@ -43,20 +43,20 @@ bool extract_mip_system_built_in_test_data_from_field(const mip_field* field, vo { assert(ptr); mip_system_built_in_test_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_system_built_in_test_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_system_time_sync_status_data(mip_serializer* serializer, const mip_system_time_sync_status_data* self) +void insert_mip_system_time_sync_status_data(microstrain_serializer* serializer, const mip_system_time_sync_status_data* self) { microstrain_insert_bool(serializer, self->time_sync); microstrain_insert_u8(serializer, self->last_pps_rcvd); } -void extract_mip_system_time_sync_status_data(mip_serializer* serializer, mip_system_time_sync_status_data* self) +void extract_mip_system_time_sync_status_data(microstrain_serializer* serializer, mip_system_time_sync_status_data* self) { microstrain_extract_bool(serializer, &self->time_sync); @@ -67,18 +67,18 @@ bool extract_mip_system_time_sync_status_data_from_field(const mip_field* field, { assert(ptr); mip_system_time_sync_status_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_system_time_sync_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_system_gpio_state_data(mip_serializer* serializer, const mip_system_gpio_state_data* self) +void insert_mip_system_gpio_state_data(microstrain_serializer* serializer, const mip_system_gpio_state_data* self) { microstrain_insert_u8(serializer, self->states); } -void extract_mip_system_gpio_state_data(mip_serializer* serializer, mip_system_gpio_state_data* self) +void extract_mip_system_gpio_state_data(microstrain_serializer* serializer, mip_system_gpio_state_data* self) { microstrain_extract_u8(serializer, &self->states); @@ -87,20 +87,20 @@ bool extract_mip_system_gpio_state_data_from_field(const mip_field* field, void* { assert(ptr); mip_system_gpio_state_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_system_gpio_state_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_system_gpio_analog_value_data(mip_serializer* serializer, const mip_system_gpio_analog_value_data* self) +void insert_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, const mip_system_gpio_analog_value_data* self) { microstrain_insert_u8(serializer, self->gpio_id); microstrain_insert_float(serializer, self->value); } -void extract_mip_system_gpio_analog_value_data(mip_serializer* serializer, mip_system_gpio_analog_value_data* self) +void extract_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, mip_system_gpio_analog_value_data* self) { microstrain_extract_u8(serializer, &self->gpio_id); @@ -111,8 +111,8 @@ bool extract_mip_system_gpio_analog_value_data_from_field(const mip_field* field { assert(ptr); mip_system_gpio_analog_value_data* self = ptr; - struct mip_serializer serializer; - mip_serializer_init_from_field(&serializer, field); + struct microstrain_serializer serializer; + microstrain_serializer_init_from_field(&serializer, field); extract_mip_system_gpio_analog_value_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } diff --git a/src/mip/definitions/data_system.h b/src/mip/definitions/data_system.h index e55e0b8bb..0fe41b46e 100644 --- a/src/mip/definitions/data_system.h +++ b/src/mip/definitions/data_system.h @@ -15,7 +15,7 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct mip_serializer; +struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -79,8 +79,8 @@ struct mip_system_built_in_test_data }; typedef struct mip_system_built_in_test_data mip_system_built_in_test_data; -void insert_mip_system_built_in_test_data(struct mip_serializer* serializer, const mip_system_built_in_test_data* self); -void extract_mip_system_built_in_test_data(struct mip_serializer* serializer, mip_system_built_in_test_data* self); +void insert_mip_system_built_in_test_data(struct microstrain_serializer* serializer, const mip_system_built_in_test_data* self); +void extract_mip_system_built_in_test_data(struct microstrain_serializer* serializer, mip_system_built_in_test_data* self); bool extract_mip_system_built_in_test_data_from_field(const struct mip_field* field, void* ptr); @@ -99,8 +99,8 @@ struct mip_system_time_sync_status_data }; typedef struct mip_system_time_sync_status_data mip_system_time_sync_status_data; -void insert_mip_system_time_sync_status_data(struct mip_serializer* serializer, const mip_system_time_sync_status_data* self); -void extract_mip_system_time_sync_status_data(struct mip_serializer* serializer, mip_system_time_sync_status_data* self); +void insert_mip_system_time_sync_status_data(struct microstrain_serializer* serializer, const mip_system_time_sync_status_data* self); +void extract_mip_system_time_sync_status_data(struct microstrain_serializer* serializer, mip_system_time_sync_status_data* self); bool extract_mip_system_time_sync_status_data_from_field(const struct mip_field* field, void* ptr); @@ -136,8 +136,8 @@ struct mip_system_gpio_state_data }; typedef struct mip_system_gpio_state_data mip_system_gpio_state_data; -void insert_mip_system_gpio_state_data(struct mip_serializer* serializer, const mip_system_gpio_state_data* self); -void extract_mip_system_gpio_state_data(struct mip_serializer* serializer, mip_system_gpio_state_data* self); +void insert_mip_system_gpio_state_data(struct microstrain_serializer* serializer, const mip_system_gpio_state_data* self); +void extract_mip_system_gpio_state_data(struct microstrain_serializer* serializer, mip_system_gpio_state_data* self); bool extract_mip_system_gpio_state_data_from_field(const struct mip_field* field, void* ptr); @@ -157,8 +157,8 @@ struct mip_system_gpio_analog_value_data }; typedef struct mip_system_gpio_analog_value_data mip_system_gpio_analog_value_data; -void insert_mip_system_gpio_analog_value_data(struct mip_serializer* serializer, const mip_system_gpio_analog_value_data* self); -void extract_mip_system_gpio_analog_value_data(struct mip_serializer* serializer, mip_system_gpio_analog_value_data* self); +void insert_mip_system_gpio_analog_value_data(struct microstrain_serializer* serializer, const mip_system_gpio_analog_value_data* self); +void extract_mip_system_gpio_analog_value_data(struct microstrain_serializer* serializer, mip_system_gpio_analog_value_data* self); bool extract_mip_system_gpio_analog_value_data_from_field(const struct mip_field* field, void* ptr); diff --git a/src/mip/definitions/descriptors.c b/src/mip/definitions/descriptors.c index 83677f4dd..8547f195d 100644 --- a/src/mip/definitions/descriptors.c +++ b/src/mip/definitions/descriptors.c @@ -151,12 +151,12 @@ bool mip_is_shared_data_field_descriptor(uint8_t field_descriptor) } -void insert_mip_function_selector(mip_serializer* serializer, enum mip_function_selector self) +void insert_mip_function_selector(microstrain_serializer* serializer, enum mip_function_selector self) { microstrain_insert_u8(serializer, self); } -void extract_mip_function_selector(mip_serializer* serializer, enum mip_function_selector* self) +void extract_mip_function_selector(microstrain_serializer* serializer, enum mip_function_selector* self) { uint8_t tmp; microstrain_extract_u8(serializer, &tmp); diff --git a/src/mip/definitions/descriptors.h b/src/mip/definitions/descriptors.h index 91d643797..1bb90cf39 100644 --- a/src/mip/definitions/descriptors.h +++ b/src/mip/definitions/descriptors.h @@ -52,8 +52,8 @@ enum mip_function_selector MIP_FUNCTION_RESET = 0x05, }; typedef enum mip_function_selector mip_function_selector; -void insert_mip_function_selector(mip_serializer* serializer, enum mip_function_selector self); -void extract_mip_function_selector(mip_serializer* serializer, enum mip_function_selector* self); +void insert_mip_function_selector(microstrain_serializer* serializer, enum mip_function_selector self); +void extract_mip_function_selector(microstrain_serializer* serializer, enum mip_function_selector* self); #ifdef __cplusplus @@ -89,8 +89,8 @@ struct CompositeDescriptor /// template struct Bitfield {}; -template void insert (Serializer& serializer, const Bitfield& bitfield) { insert(serializer, static_cast(bitfield).value); } -template void extract(Serializer& serializer, Bitfield& bitfield) { extract(serializer, static_cast(bitfield).value); } +template void insert (microstrain::Serializer& serializer, const Bitfield& bitfield) { insert(serializer, static_cast(bitfield).value); } +template void extract(microstrain::Serializer& serializer, Bitfield& bitfield) { extract(serializer, static_cast(bitfield).value); } enum class FunctionSelector : uint8_t diff --git a/src/mip/mip.hpp b/src/mip/mip.hpp index 637fe2168..336bc31b3 100644 --- a/src/mip/mip.hpp +++ b/src/mip/mip.hpp @@ -229,9 +229,9 @@ class PacketRef : public C::mip_packet { if( fieldDescriptor == INVALID_FIELD_DESCRIPTOR ) fieldDescriptor = FieldType::FIELD_DESCRIPTOR; - Serializer serializer(*this, fieldDescriptor); + microstrain::Serializer serializer(*this, fieldDescriptor); insert(serializer, field); - C::mip_serializer_finish_new_field(&serializer, this); + C::microstrain_serializer_finish_new_field(&serializer, this); return serializer.isOk(); } diff --git a/src/mip/mip_field.c b/src/mip/mip_field.c index de7548430..16a58bc93 100644 --- a/src/mip/mip_field.c +++ b/src/mip/mip_field.c @@ -5,6 +5,8 @@ #include "mip_offsets.h" #include "definitions/descriptors.h" +#include + #include @@ -233,3 +235,66 @@ bool mip_field_next_in_packet(mip_field* field, const mip_packet* packet) return mip_field_is_valid(field); } + + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Initializer a serialization struct for creation of a new field at the +/// end of the packet. +/// +///@note Call microstrain_serializer_finiish_new_field after the data has been serialized. +/// +///@note Only one new field per packet can be in progress at a time. +/// +///@param serializer +///@param packet +/// Allocate the new field on the end of this packet. +///@param field_descriptor +/// Field descriptor of the new field. +/// +void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor) +{ + assert(packet); + + serializer->_buffer = NULL; + serializer->_buffer_size = 0; + serializer->_offset = 0; + + const int length = mip_packet_alloc_field(packet, field_descriptor, 0, &serializer->_buffer); + + if( length >= 0 ) + serializer->_buffer_size = length; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Call this after a new field allocated by microstrain_serializer_init_new_field +/// has been written. +/// +/// This will either finish the field, or abort it if the serializer failed. +/// +///@param serializer Must be created from microstrain_serializer_init_new_field. +///@param packet Must be the original packet. +/// +void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet* packet) +{ + assert(packet); + + if(microstrain_serializer_is_ok(serializer) ) + { + assert(serializer->_offset <= MIP_FIELD_LENGTH_MAX); // Payload too long! + mip_packet_realloc_last_field(packet, serializer->_buffer, (uint8_t) serializer->_offset); + } + else if( serializer->_buffer ) + mip_packet_cancel_last_field(packet, serializer->_buffer); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Initialize a serialization struct from a microstrain field payload. +/// +///@param serializer +///@param field +/// +void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field* field) +{ + microstrain_serializer_init_extraction(serializer, mip_field_payload(field), mip_field_payload_length(field)); +} diff --git a/src/mip/mip_field.h b/src/mip/mip_field.h index 919d54246..9aba6af82 100644 --- a/src/mip/mip_field.h +++ b/src/mip/mip_field.h @@ -118,6 +118,8 @@ bool mip_field_next_in_packet(mip_field* field, const mip_packet* packet); //////////////////////////////////////////////////////////////////////////////// /// +void microstrain_serializer_init_from_field(struct microstrain_serializer* serializer, const mip_field* field); + #ifdef __cplusplus } // namespace mip } // namespace C diff --git a/src/mip/mip_packet.c b/src/mip/mip_packet.c index d5f6496af..59927bf10 100644 --- a/src/mip/mip_packet.c +++ b/src/mip/mip_packet.c @@ -4,6 +4,8 @@ #include "definitions/descriptors.h" +#include + #include #include diff --git a/src/mip/mip_packet.h b/src/mip/mip_packet.h index e98287fcb..f53203bd5 100644 --- a/src/mip/mip_packet.h +++ b/src/mip/mip_packet.h @@ -3,7 +3,7 @@ #include "mip_types.h" #ifdef __cplusplus -namespace mip{ +namespace mip { namespace C { extern "C" { #endif @@ -101,6 +101,16 @@ int mip_packet_remaining_space(const mip_packet* packet); bool mip_packet_is_data(const mip_packet* packet); +///@} +//////////////////////////////////////////////////////////////////////////////// +///@defgroup Serialization Accessors - Functions for serializing a MIP packet. +/// +///@{ +struct microstrain_serializer; + +void microstrain_serializer_init_new_field(struct microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor); +void microstrain_serializer_finish_new_field(const struct microstrain_serializer* serializer, mip_packet* packet); + ///@} ///@} ///@} From 72e55bf65e1196c549ba4a1032e9bb144549de9a Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 15 May 2024 14:15:28 -0400 Subject: [PATCH 008/147] WIP rename serializer (namespace problem, abort and resume later). --- src/microstrain/connections/connection.hpp | 2 +- src/mip/definitions/commands_3dm.c | 84 ++-- src/mip/definitions/commands_3dm.hpp | 5 +- src/mip/definitions/commands_aiding.c | 36 +- src/mip/definitions/commands_aiding.h | 92 ++--- src/mip/definitions/commands_base.c | 18 +- src/mip/definitions/commands_base.h | 48 +-- src/mip/definitions/commands_filter.c | 56 +-- src/mip/definitions/commands_filter.h | 421 ++++++++++----------- src/mip/definitions/commands_gnss.h | 31 +- src/mip/definitions/commands_rtk.c | 24 +- src/mip/definitions/commands_rtk.h | 76 ++-- src/mip/definitions/commands_system.h | 8 +- src/mip/definitions/common.h | 3 +- src/mip/definitions/data_filter.c | 40 +- src/mip/definitions/data_filter.h | 268 ++++++------- src/mip/definitions/data_gnss.c | 172 ++++----- src/mip/definitions/data_gnss.h | 280 +++++++------- src/mip/definitions/data_sensor.c | 8 +- src/mip/definitions/data_sensor.h | 100 ++--- src/mip/definitions/data_shared.c | 12 +- src/mip/definitions/data_shared.h | 48 +-- src/mip/definitions/data_system.h | 16 +- src/mip/mip_field.h | 2 +- src/mip/mip_packet.h | 14 +- 25 files changed, 937 insertions(+), 927 deletions(-) diff --git a/src/microstrain/connections/connection.hpp b/src/microstrain/connections/connection.hpp index 3164a43ab..5d81c6cf0 100644 --- a/src/microstrain/connections/connection.hpp +++ b/src/microstrain/connections/connection.hpp @@ -35,7 +35,7 @@ class Connection #if __cpp_lib_span >= 202002L bool sendToDevice(std::span data) { return sendToDevice(data.data(), data.size()); } - bool recvFromDevice(std::span& buffer, unsigned int wait_time_ms, Timestamp* timestamp_out) { + bool recvFromDevice(std::span& buffer, unsigned int wait_time_ms, EmbeddedTimestamp* timestamp_out) { size_t length = 0; if(!recvFromDevice(buffer.data(), buffer.size(), wait_time_ms, &length, timestamp_out)) return false; diff --git a/src/mip/definitions/commands_3dm.c b/src/mip/definitions/commands_3dm.c index 7efbbe808..31ff47976 100644 --- a/src/mip/definitions/commands_3dm.c +++ b/src/mip/definitions/commands_3dm.c @@ -45,33 +45,33 @@ void extract_mip_nmea_message(microstrain_serializer* serializer, mip_nmea_messa } -void insert_mip_nmea_message_message_id(struct microstrain_serializer* serializer, const mip_nmea_message_message_id self) +void insert_mip_nmea_message_message_id(microstrain_serializer* serializer, const mip_nmea_message_message_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_nmea_message_message_id(struct microstrain_serializer* serializer, mip_nmea_message_message_id* self) +void extract_mip_nmea_message_message_id(microstrain_serializer* serializer, mip_nmea_message_message_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_nmea_message_talker_id(struct microstrain_serializer* serializer, const mip_nmea_message_talker_id self) +void insert_mip_nmea_message_talker_id(microstrain_serializer* serializer, const mip_nmea_message_talker_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_nmea_message_talker_id(struct microstrain_serializer* serializer, mip_nmea_message_talker_id* self) +void extract_mip_nmea_message_talker_id(microstrain_serializer* serializer, mip_nmea_message_talker_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_sensor_range_type(struct microstrain_serializer* serializer, const mip_sensor_range_type self) +void insert_mip_sensor_range_type(microstrain_serializer* serializer, const mip_sensor_range_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_sensor_range_type(struct microstrain_serializer* serializer, mip_sensor_range_type* self) +void extract_mip_sensor_range_type(microstrain_serializer* serializer, mip_sensor_range_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1310,11 +1310,11 @@ void extract_mip_3dm_factory_streaming_command(microstrain_serializer* serialize } -void insert_mip_3dm_factory_streaming_command_action(struct microstrain_serializer* serializer, const mip_3dm_factory_streaming_command_action self) +void insert_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command_action self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_factory_streaming_command_action(struct microstrain_serializer* serializer, mip_3dm_factory_streaming_command_action* self) +void extract_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, mip_3dm_factory_streaming_command_action* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1529,22 +1529,22 @@ void extract_mip_3dm_constellation_settings_response(microstrain_serializer* ser } -void insert_mip_3dm_constellation_settings_command_constellation_id(struct microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self) +void insert_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_constellation_settings_command_constellation_id(struct microstrain_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self) +void extract_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_constellation_settings_command_option_flags(struct microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self) +void insert_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_3dm_constellation_settings_command_option_flags(struct microstrain_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self) +void extract_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1741,11 +1741,11 @@ void extract_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* seriali } -void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self) +void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(struct microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self) +void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1891,11 +1891,11 @@ void extract_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializ } -void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self) +void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(struct microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self) +void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2292,11 +2292,11 @@ void extract_mip_3dm_pps_source_response(microstrain_serializer* serializer, mip } -void insert_mip_3dm_pps_source_command_source(struct microstrain_serializer* serializer, const mip_3dm_pps_source_command_source self) +void insert_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, const mip_3dm_pps_source_command_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_pps_source_command_source(struct microstrain_serializer* serializer, mip_3dm_pps_source_command_source* self) +void extract_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, mip_3dm_pps_source_command_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2440,33 +2440,33 @@ void extract_mip_3dm_gpio_config_response(microstrain_serializer* serializer, mi } -void insert_mip_3dm_gpio_config_command_feature(struct microstrain_serializer* serializer, const mip_3dm_gpio_config_command_feature self) +void insert_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_feature self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_gpio_config_command_feature(struct microstrain_serializer* serializer, mip_3dm_gpio_config_command_feature* self) +void extract_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, mip_3dm_gpio_config_command_feature* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_gpio_config_command_behavior(struct microstrain_serializer* serializer, const mip_3dm_gpio_config_command_behavior self) +void insert_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_behavior self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_gpio_config_command_behavior(struct microstrain_serializer* serializer, mip_3dm_gpio_config_command_behavior* self) +void extract_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, mip_3dm_gpio_config_command_behavior* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_3dm_gpio_config_command_pin_mode(struct microstrain_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self) +void insert_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_gpio_config_command_pin_mode(struct microstrain_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self) +void extract_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2718,11 +2718,11 @@ void extract_mip_3dm_odometer_response(microstrain_serializer* serializer, mip_3 } -void insert_mip_3dm_odometer_command_mode(struct microstrain_serializer* serializer, const mip_3dm_odometer_command_mode self) +void insert_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, const mip_3dm_odometer_command_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_odometer_command_mode(struct microstrain_serializer* serializer, mip_3dm_odometer_command_mode* self) +void extract_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, mip_3dm_odometer_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2858,11 +2858,11 @@ void extract_mip_3dm_get_event_support_response(microstrain_serializer* serializ } -void insert_mip_3dm_get_event_support_command_query(struct microstrain_serializer* serializer, const mip_3dm_get_event_support_command_query self) +void insert_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_query self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_get_event_support_command_query(struct microstrain_serializer* serializer, mip_3dm_get_event_support_command_query* self) +void extract_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, mip_3dm_get_event_support_command_query* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2960,11 +2960,11 @@ void extract_mip_3dm_event_control_response(microstrain_serializer* serializer, } -void insert_mip_3dm_event_control_command_mode(struct microstrain_serializer* serializer, const mip_3dm_event_control_command_mode self) +void insert_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, const mip_3dm_event_control_command_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_control_command_mode(struct microstrain_serializer* serializer, mip_3dm_event_control_command_mode* self) +void extract_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, mip_3dm_event_control_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -3103,11 +3103,11 @@ void extract_mip_3dm_get_event_trigger_status_response(microstrain_serializer* s } -void insert_mip_3dm_get_event_trigger_status_command_status(struct microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self) +void insert_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_get_event_trigger_status_command_status(struct microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self) +void extract_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -3368,11 +3368,11 @@ void extract_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* s } -void insert_mip_3dm_event_trigger_command_gpio_params_mode(struct microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self) +void insert_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_trigger_command_gpio_params_mode(struct microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self) +void extract_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -3442,11 +3442,11 @@ void extract_mip_3dm_event_trigger_command_threshold_params(microstrain_serializ } } -void insert_mip_3dm_event_trigger_command_threshold_params_type(struct microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self) +void insert_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_trigger_command_threshold_params_type(struct microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self) +void extract_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -3470,11 +3470,11 @@ void extract_mip_3dm_event_trigger_command_combination_params(microstrain_serial } -void insert_mip_3dm_event_trigger_command_type(struct microstrain_serializer* serializer, const mip_3dm_event_trigger_command_type self) +void insert_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_trigger_command_type(struct microstrain_serializer* serializer, mip_3dm_event_trigger_command_type* self) +void extract_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -3707,11 +3707,11 @@ void extract_mip_3dm_event_action_command_gpio_params(microstrain_serializer* se } -void insert_mip_3dm_event_action_command_gpio_params_mode(struct microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self) +void insert_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_action_command_gpio_params_mode(struct microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self) +void extract_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -3745,11 +3745,11 @@ void extract_mip_3dm_event_action_command_message_params(microstrain_serializer* } -void insert_mip_3dm_event_action_command_type(struct microstrain_serializer* serializer, const mip_3dm_event_action_command_type self) +void insert_mip_3dm_event_action_command_type(microstrain_serializer* serializer, const mip_3dm_event_action_command_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_3dm_event_action_command_type(struct microstrain_serializer* serializer, mip_3dm_event_action_command_type* self) +void extract_mip_3dm_event_action_command_type(microstrain_serializer* serializer, mip_3dm_event_action_command_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); diff --git a/src/mip/definitions/commands_3dm.hpp b/src/mip/definitions/commands_3dm.hpp index 28987157f..a9da22541 100644 --- a/src/mip/definitions/commands_3dm.hpp +++ b/src/mip/definitions/commands_3dm.hpp @@ -8,9 +8,12 @@ #include #include -namespace mip { +namespace microstrain +{ class Serializer; +} +namespace mip { namespace C { struct mip_interface; } // namespace C diff --git a/src/mip/definitions/commands_aiding.c b/src/mip/definitions/commands_aiding.c index d2750c518..0f797dc99 100644 --- a/src/mip/definitions/commands_aiding.c +++ b/src/mip/definitions/commands_aiding.c @@ -41,11 +41,11 @@ void extract_mip_time(microstrain_serializer* serializer, mip_time* self) } -void insert_mip_time_timebase(struct microstrain_serializer* serializer, const mip_time_timebase self) +void insert_mip_time_timebase(microstrain_serializer* serializer, const mip_time_timebase self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_time_timebase(struct microstrain_serializer* serializer, mip_time_timebase* self) +void extract_mip_time_timebase(microstrain_serializer* serializer, mip_time_timebase* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -163,11 +163,11 @@ void extract_mip_aiding_frame_config_response(microstrain_serializer* serializer } } -void insert_mip_aiding_frame_config_command_format(struct microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self) +void insert_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_aiding_frame_config_command_format(struct microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self) +void extract_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -333,11 +333,11 @@ void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* ser } -void insert_mip_aiding_aiding_echo_control_command_mode(struct microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) +void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_aiding_aiding_echo_control_command_mode(struct microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) +void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -456,11 +456,11 @@ void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip } -void insert_mip_aiding_ecef_pos_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) +void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_ecef_pos_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) +void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -530,11 +530,11 @@ void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_ } -void insert_mip_aiding_llh_pos_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) +void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_llh_pos_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) +void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -649,11 +649,11 @@ void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip } -void insert_mip_aiding_ecef_vel_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) +void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_ecef_vel_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) +void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -717,11 +717,11 @@ void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_ } -void insert_mip_aiding_ned_vel_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) +void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_ned_vel_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) +void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -785,11 +785,11 @@ void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_seriali } -void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) +void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) +void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -902,11 +902,11 @@ void extract_mip_aiding_magnetic_field_command(microstrain_serializer* serialize } -void insert_mip_aiding_magnetic_field_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self) +void insert_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_aiding_magnetic_field_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self) +void extract_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/mip/definitions/commands_aiding.h b/src/mip/definitions/commands_aiding.h index f4e01476a..c207411b1 100644 --- a/src/mip/definitions/commands_aiding.h +++ b/src/mip/definitions/commands_aiding.h @@ -73,11 +73,11 @@ struct mip_time }; typedef struct mip_time mip_time; -void insert_mip_time(struct microstrain_serializer* serializer, const mip_time* self); -void extract_mip_time(struct microstrain_serializer* serializer, mip_time* self); +void insert_mip_time(microstrain_serializer* serializer, const mip_time* self); +void extract_mip_time(microstrain_serializer* serializer, mip_time* self); -void insert_mip_time_timebase(struct microstrain_serializer* serializer, const mip_time_timebase self); -void extract_mip_time_timebase(struct microstrain_serializer* serializer, mip_time_timebase* self); +void insert_mip_time_timebase(microstrain_serializer* serializer, const mip_time_timebase self); +void extract_mip_time_timebase(microstrain_serializer* serializer, mip_time_timebase* self); //////////////////////////////////////////////////////////////////////////////// @@ -135,11 +135,11 @@ struct mip_aiding_frame_config_command }; typedef struct mip_aiding_frame_config_command mip_aiding_frame_config_command; -void insert_mip_aiding_frame_config_command(struct microstrain_serializer* serializer, const mip_aiding_frame_config_command* self); -void extract_mip_aiding_frame_config_command(struct microstrain_serializer* serializer, mip_aiding_frame_config_command* self); +void insert_mip_aiding_frame_config_command(microstrain_serializer* serializer, const mip_aiding_frame_config_command* self); +void extract_mip_aiding_frame_config_command(microstrain_serializer* serializer, mip_aiding_frame_config_command* self); -void insert_mip_aiding_frame_config_command_format(struct microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self); -void extract_mip_aiding_frame_config_command_format(struct microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self); +void insert_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self); +void extract_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self); struct mip_aiding_frame_config_response { @@ -151,8 +151,8 @@ struct mip_aiding_frame_config_response }; typedef struct mip_aiding_frame_config_response mip_aiding_frame_config_response; -void insert_mip_aiding_frame_config_response(struct microstrain_serializer* serializer, const mip_aiding_frame_config_response* self); -void extract_mip_aiding_frame_config_response(struct microstrain_serializer* serializer, mip_aiding_frame_config_response* self); +void insert_mip_aiding_frame_config_response(microstrain_serializer* serializer, const mip_aiding_frame_config_response* self); +void extract_mip_aiding_frame_config_response(microstrain_serializer* serializer, mip_aiding_frame_config_response* self); mip_cmd_result mip_aiding_write_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool tracking_enabled, const float* translation, const mip_aiding_frame_config_command_rotation* rotation); mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool* tracking_enabled_out, float* translation_out, mip_aiding_frame_config_command_rotation* rotation_out); @@ -180,11 +180,11 @@ struct mip_aiding_aiding_echo_control_command }; typedef struct mip_aiding_aiding_echo_control_command mip_aiding_aiding_echo_control_command; -void insert_mip_aiding_aiding_echo_control_command(struct microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self); -void extract_mip_aiding_aiding_echo_control_command(struct microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self); +void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self); +void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self); -void insert_mip_aiding_aiding_echo_control_command_mode(struct microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self); -void extract_mip_aiding_aiding_echo_control_command_mode(struct microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self); +void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self); +void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self); struct mip_aiding_aiding_echo_control_response { @@ -192,8 +192,8 @@ struct mip_aiding_aiding_echo_control_response }; typedef struct mip_aiding_aiding_echo_control_response mip_aiding_aiding_echo_control_response; -void insert_mip_aiding_aiding_echo_control_response(struct microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self); -void extract_mip_aiding_aiding_echo_control_response(struct microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self); +void insert_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self); +void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self); mip_cmd_result mip_aiding_write_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode); mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out); @@ -226,11 +226,11 @@ struct mip_aiding_ecef_pos_command }; typedef struct mip_aiding_ecef_pos_command mip_aiding_ecef_pos_command; -void insert_mip_aiding_ecef_pos_command(struct microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self); -void extract_mip_aiding_ecef_pos_command(struct microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self); +void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self); +void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self); -void insert_mip_aiding_ecef_pos_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self); -void extract_mip_aiding_ecef_pos_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self); +void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self); +void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self); mip_cmd_result mip_aiding_ecef_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags); @@ -262,11 +262,11 @@ struct mip_aiding_llh_pos_command }; typedef struct mip_aiding_llh_pos_command mip_aiding_llh_pos_command; -void insert_mip_aiding_llh_pos_command(struct microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self); -void extract_mip_aiding_llh_pos_command(struct microstrain_serializer* serializer, mip_aiding_llh_pos_command* self); +void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self); +void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self); -void insert_mip_aiding_llh_pos_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self); -void extract_mip_aiding_llh_pos_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self); +void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self); +void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self); mip_cmd_result mip_aiding_llh_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags); @@ -288,8 +288,8 @@ struct mip_aiding_height_command }; typedef struct mip_aiding_height_command mip_aiding_height_command; -void insert_mip_aiding_height_command(struct microstrain_serializer* serializer, const mip_aiding_height_command* self); -void extract_mip_aiding_height_command(struct microstrain_serializer* serializer, mip_aiding_height_command* self); +void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self); +void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self); mip_cmd_result mip_aiding_height(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); @@ -318,11 +318,11 @@ struct mip_aiding_ecef_vel_command }; typedef struct mip_aiding_ecef_vel_command mip_aiding_ecef_vel_command; -void insert_mip_aiding_ecef_vel_command(struct microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self); -void extract_mip_aiding_ecef_vel_command(struct microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self); +void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self); +void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self); -void insert_mip_aiding_ecef_vel_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self); -void extract_mip_aiding_ecef_vel_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self); +void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self); +void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self); mip_cmd_result mip_aiding_ecef_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags); @@ -351,11 +351,11 @@ struct mip_aiding_ned_vel_command }; typedef struct mip_aiding_ned_vel_command mip_aiding_ned_vel_command; -void insert_mip_aiding_ned_vel_command(struct microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self); -void extract_mip_aiding_ned_vel_command(struct microstrain_serializer* serializer, mip_aiding_ned_vel_command* self); +void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self); +void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self); -void insert_mip_aiding_ned_vel_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self); -void extract_mip_aiding_ned_vel_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self); +void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self); +void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self); mip_cmd_result mip_aiding_ned_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags); @@ -385,11 +385,11 @@ struct mip_aiding_vehicle_fixed_frame_velocity_command }; typedef struct mip_aiding_vehicle_fixed_frame_velocity_command mip_aiding_vehicle_fixed_frame_velocity_command; -void insert_mip_aiding_vehicle_fixed_frame_velocity_command(struct microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self); -void extract_mip_aiding_vehicle_fixed_frame_velocity_command(struct microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self); +void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self); +void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self); -void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self); -void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self); +void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self); +void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self); mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags); @@ -410,8 +410,8 @@ struct mip_aiding_true_heading_command }; typedef struct mip_aiding_true_heading_command mip_aiding_true_heading_command; -void insert_mip_aiding_true_heading_command(struct microstrain_serializer* serializer, const mip_aiding_true_heading_command* self); -void extract_mip_aiding_true_heading_command(struct microstrain_serializer* serializer, mip_aiding_true_heading_command* self); +void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self); +void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self); mip_cmd_result mip_aiding_true_heading(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); @@ -440,11 +440,11 @@ struct mip_aiding_magnetic_field_command }; typedef struct mip_aiding_magnetic_field_command mip_aiding_magnetic_field_command; -void insert_mip_aiding_magnetic_field_command(struct microstrain_serializer* serializer, const mip_aiding_magnetic_field_command* self); -void extract_mip_aiding_magnetic_field_command(struct microstrain_serializer* serializer, mip_aiding_magnetic_field_command* self); +void insert_mip_aiding_magnetic_field_command(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command* self); +void extract_mip_aiding_magnetic_field_command(microstrain_serializer* serializer, mip_aiding_magnetic_field_command* self); -void insert_mip_aiding_magnetic_field_command_valid_flags(struct microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self); -void extract_mip_aiding_magnetic_field_command_valid_flags(struct microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self); +void insert_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self); +void extract_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self); mip_cmd_result mip_aiding_magnetic_field(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* magnetic_field, const float* uncertainty, mip_aiding_magnetic_field_command_valid_flags valid_flags); @@ -466,8 +466,8 @@ struct mip_aiding_pressure_command }; typedef struct mip_aiding_pressure_command mip_aiding_pressure_command; -void insert_mip_aiding_pressure_command(struct microstrain_serializer* serializer, const mip_aiding_pressure_command* self); -void extract_mip_aiding_pressure_command(struct microstrain_serializer* serializer, mip_aiding_pressure_command* self); +void insert_mip_aiding_pressure_command(microstrain_serializer* serializer, const mip_aiding_pressure_command* self); +void extract_mip_aiding_pressure_command(microstrain_serializer* serializer, mip_aiding_pressure_command* self); mip_cmd_result mip_aiding_pressure(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float pressure, float uncertainty, uint16_t valid_flags); diff --git a/src/mip/definitions/commands_base.c b/src/mip/definitions/commands_base.c index d31e3984c..f93efd25d 100644 --- a/src/mip/definitions/commands_base.c +++ b/src/mip/definitions/commands_base.c @@ -11,11 +11,7 @@ namespace mip { namespace C { extern "C" { - -#endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; +#endif // __cplusplus; //////////////////////////////////////////////////////////////////////////////// @@ -63,22 +59,22 @@ void extract_mip_base_device_info(microstrain_serializer* serializer, mip_base_d } -void insert_mip_time_format(struct microstrain_serializer* serializer, const mip_time_format self) +void insert_mip_time_format(microstrain_serializer* serializer, const mip_time_format self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_time_format(struct microstrain_serializer* serializer, mip_time_format* self) +void extract_mip_time_format(microstrain_serializer* serializer, mip_time_format* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_commanded_test_bits_gq7(struct microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self) +void insert_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self) { microstrain_insert_u32(serializer, (uint32_t) (self)); } -void extract_mip_commanded_test_bits_gq7(struct microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self) +void extract_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self) { uint32_t tmp = 0; microstrain_extract_u32(serializer, &tmp); @@ -363,11 +359,11 @@ void extract_mip_base_gps_time_update_command(microstrain_serializer* serializer } } -void insert_mip_base_gps_time_update_command_field_id(struct microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self) +void insert_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_base_gps_time_update_command_field_id(struct microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self) +void extract_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); diff --git a/src/mip/definitions/commands_base.h b/src/mip/definitions/commands_base.h index 14959e835..2e43634ec 100644 --- a/src/mip/definitions/commands_base.h +++ b/src/mip/definitions/commands_base.h @@ -70,14 +70,14 @@ struct mip_base_device_info }; typedef struct mip_base_device_info mip_base_device_info; -void insert_mip_base_device_info(struct microstrain_serializer* serializer, const mip_base_device_info* self); -void extract_mip_base_device_info(struct microstrain_serializer* serializer, mip_base_device_info* self); +void insert_mip_base_device_info(microstrain_serializer* serializer, const mip_base_device_info* self); +void extract_mip_base_device_info(microstrain_serializer* serializer, mip_base_device_info* self); typedef uint8_t mip_time_format; static const mip_time_format MIP_TIME_FORMAT_GPS = 1; ///< GPS time, a = week number since 1980, b = time of week in milliseconds. -void insert_mip_time_format(struct microstrain_serializer* serializer, const mip_time_format self); -void extract_mip_time_format(struct microstrain_serializer* serializer, mip_time_format* self); +void insert_mip_time_format(microstrain_serializer* serializer, const mip_time_format self); +void extract_mip_time_format(microstrain_serializer* serializer, mip_time_format* self); typedef uint32_t mip_commanded_test_bits_gq7; static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_NONE = 0x00000000; @@ -110,8 +110,8 @@ static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_SOLUTI static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_GENERAL_FAULT = 0x80000000; ///< static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_ALL = 0xFFFFFFFF; -void insert_mip_commanded_test_bits_gq7(struct microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self); -void extract_mip_commanded_test_bits_gq7(struct microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self); +void insert_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self); +void extract_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self); //////////////////////////////////////////////////////////////////////////////// @@ -158,8 +158,8 @@ struct mip_base_get_device_info_response }; typedef struct mip_base_get_device_info_response mip_base_get_device_info_response; -void insert_mip_base_get_device_info_response(struct microstrain_serializer* serializer, const mip_base_get_device_info_response* self); -void extract_mip_base_get_device_info_response(struct microstrain_serializer* serializer, mip_base_get_device_info_response* self); +void insert_mip_base_get_device_info_response(microstrain_serializer* serializer, const mip_base_get_device_info_response* self); +void extract_mip_base_get_device_info_response(microstrain_serializer* serializer, mip_base_get_device_info_response* self); mip_cmd_result mip_base_get_device_info(struct mip_interface* device, mip_base_device_info* device_info_out); @@ -181,8 +181,8 @@ struct mip_base_get_device_descriptors_response }; typedef struct mip_base_get_device_descriptors_response mip_base_get_device_descriptors_response; -void insert_mip_base_get_device_descriptors_response(struct microstrain_serializer* serializer, const mip_base_get_device_descriptors_response* self); -void extract_mip_base_get_device_descriptors_response(struct microstrain_serializer* serializer, mip_base_get_device_descriptors_response* self); +void insert_mip_base_get_device_descriptors_response(microstrain_serializer* serializer, const mip_base_get_device_descriptors_response* self); +void extract_mip_base_get_device_descriptors_response(microstrain_serializer* serializer, mip_base_get_device_descriptors_response* self); mip_cmd_result mip_base_get_device_descriptors(struct mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count); @@ -205,8 +205,8 @@ struct mip_base_built_in_test_response }; typedef struct mip_base_built_in_test_response mip_base_built_in_test_response; -void insert_mip_base_built_in_test_response(struct microstrain_serializer* serializer, const mip_base_built_in_test_response* self); -void extract_mip_base_built_in_test_response(struct microstrain_serializer* serializer, mip_base_built_in_test_response* self); +void insert_mip_base_built_in_test_response(microstrain_serializer* serializer, const mip_base_built_in_test_response* self); +void extract_mip_base_built_in_test_response(microstrain_serializer* serializer, mip_base_built_in_test_response* self); mip_cmd_result mip_base_built_in_test(struct mip_interface* device, uint32_t* result_out); @@ -240,8 +240,8 @@ struct mip_base_get_extended_descriptors_response }; typedef struct mip_base_get_extended_descriptors_response mip_base_get_extended_descriptors_response; -void insert_mip_base_get_extended_descriptors_response(struct microstrain_serializer* serializer, const mip_base_get_extended_descriptors_response* self); -void extract_mip_base_get_extended_descriptors_response(struct microstrain_serializer* serializer, mip_base_get_extended_descriptors_response* self); +void insert_mip_base_get_extended_descriptors_response(microstrain_serializer* serializer, const mip_base_get_extended_descriptors_response* self); +void extract_mip_base_get_extended_descriptors_response(microstrain_serializer* serializer, mip_base_get_extended_descriptors_response* self); mip_cmd_result mip_base_get_extended_descriptors(struct mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count); @@ -261,8 +261,8 @@ struct mip_base_continuous_bit_response }; typedef struct mip_base_continuous_bit_response mip_base_continuous_bit_response; -void insert_mip_base_continuous_bit_response(struct microstrain_serializer* serializer, const mip_base_continuous_bit_response* self); -void extract_mip_base_continuous_bit_response(struct microstrain_serializer* serializer, mip_base_continuous_bit_response* self); +void insert_mip_base_continuous_bit_response(microstrain_serializer* serializer, const mip_base_continuous_bit_response* self); +void extract_mip_base_continuous_bit_response(microstrain_serializer* serializer, mip_base_continuous_bit_response* self); mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* result_out); @@ -296,8 +296,8 @@ struct mip_base_comm_speed_command }; typedef struct mip_base_comm_speed_command mip_base_comm_speed_command; -void insert_mip_base_comm_speed_command(struct microstrain_serializer* serializer, const mip_base_comm_speed_command* self); -void extract_mip_base_comm_speed_command(struct microstrain_serializer* serializer, mip_base_comm_speed_command* self); +void insert_mip_base_comm_speed_command(microstrain_serializer* serializer, const mip_base_comm_speed_command* self); +void extract_mip_base_comm_speed_command(microstrain_serializer* serializer, mip_base_comm_speed_command* self); struct mip_base_comm_speed_response { @@ -306,8 +306,8 @@ struct mip_base_comm_speed_response }; typedef struct mip_base_comm_speed_response mip_base_comm_speed_response; -void insert_mip_base_comm_speed_response(struct microstrain_serializer* serializer, const mip_base_comm_speed_response* self); -void extract_mip_base_comm_speed_response(struct microstrain_serializer* serializer, mip_base_comm_speed_response* self); +void insert_mip_base_comm_speed_response(microstrain_serializer* serializer, const mip_base_comm_speed_response* self); +void extract_mip_base_comm_speed_response(microstrain_serializer* serializer, mip_base_comm_speed_response* self); mip_cmd_result mip_base_write_comm_speed(struct mip_interface* device, uint8_t port, uint32_t baud); mip_cmd_result mip_base_read_comm_speed(struct mip_interface* device, uint8_t port, uint32_t* baud_out); @@ -338,11 +338,11 @@ struct mip_base_gps_time_update_command }; typedef struct mip_base_gps_time_update_command mip_base_gps_time_update_command; -void insert_mip_base_gps_time_update_command(struct microstrain_serializer* serializer, const mip_base_gps_time_update_command* self); -void extract_mip_base_gps_time_update_command(struct microstrain_serializer* serializer, mip_base_gps_time_update_command* self); +void insert_mip_base_gps_time_update_command(microstrain_serializer* serializer, const mip_base_gps_time_update_command* self); +void extract_mip_base_gps_time_update_command(microstrain_serializer* serializer, mip_base_gps_time_update_command* self); -void insert_mip_base_gps_time_update_command_field_id(struct microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self); -void extract_mip_base_gps_time_update_command_field_id(struct microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self); +void insert_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self); +void extract_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self); mip_cmd_result mip_base_write_gps_time_update(struct mip_interface* device, mip_base_gps_time_update_command_field_id field_id, uint32_t value); diff --git a/src/mip/definitions/commands_filter.c b/src/mip/definitions/commands_filter.c index f3d95d7ed..2cf4ebf68 100644 --- a/src/mip/definitions/commands_filter.c +++ b/src/mip/definitions/commands_filter.c @@ -22,33 +22,33 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_filter_reference_frame(struct microstrain_serializer* serializer, const mip_filter_reference_frame self) +void insert_mip_filter_reference_frame(microstrain_serializer* serializer, const mip_filter_reference_frame self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_reference_frame(struct microstrain_serializer* serializer, mip_filter_reference_frame* self) +void extract_mip_filter_reference_frame(microstrain_serializer* serializer, mip_filter_reference_frame* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_mag_param_source(struct microstrain_serializer* serializer, const mip_filter_mag_param_source self) +void insert_mip_filter_mag_param_source(microstrain_serializer* serializer, const mip_filter_mag_param_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_mag_param_source(struct microstrain_serializer* serializer, mip_filter_mag_param_source* self) +void extract_mip_filter_mag_param_source(microstrain_serializer* serializer, mip_filter_mag_param_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_adaptive_measurement(struct microstrain_serializer* serializer, const mip_filter_adaptive_measurement self) +void insert_mip_filter_adaptive_measurement(microstrain_serializer* serializer, const mip_filter_adaptive_measurement self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_adaptive_measurement(struct microstrain_serializer* serializer, mip_filter_adaptive_measurement* self) +void extract_mip_filter_adaptive_measurement(microstrain_serializer* serializer, mip_filter_adaptive_measurement* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -132,11 +132,11 @@ void extract_mip_filter_estimation_control_response(microstrain_serializer* seri } -void insert_mip_filter_estimation_control_command_enable_flags(struct microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self) +void insert_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_estimation_control_command_enable_flags(struct microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self) +void extract_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -418,11 +418,11 @@ void extract_mip_filter_tare_orientation_response(microstrain_serializer* serial } -void insert_mip_filter_tare_orientation_command_mip_tare_axes(struct microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self) +void insert_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_tare_orientation_command_mip_tare_axes(struct microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self) +void extract_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -542,11 +542,11 @@ void extract_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* s } -void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self) +void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self) +void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1285,11 +1285,11 @@ void extract_mip_filter_gnss_source_response(microstrain_serializer* serializer, } -void insert_mip_filter_gnss_source_command_source(struct microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self) +void insert_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_gnss_source_command_source(struct microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self) +void extract_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1409,11 +1409,11 @@ void extract_mip_filter_heading_source_response(microstrain_serializer* serializ } -void insert_mip_filter_heading_source_command_source(struct microstrain_serializer* serializer, const mip_filter_heading_source_command_source self) +void insert_mip_filter_heading_source_command_source(microstrain_serializer* serializer, const mip_filter_heading_source_command_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_heading_source_command_source(struct microstrain_serializer* serializer, mip_filter_heading_source_command_source* self) +void extract_mip_filter_heading_source_command_source(microstrain_serializer* serializer, mip_filter_heading_source_command_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2166,11 +2166,11 @@ void extract_mip_filter_altitude_aiding_response(microstrain_serializer* seriali } -void insert_mip_filter_altitude_aiding_command_aiding_selector(struct microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self) +void insert_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_altitude_aiding_command_aiding_selector(struct microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self) +void extract_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2290,11 +2290,11 @@ void extract_mip_filter_pitch_roll_aiding_response(microstrain_serializer* seria } -void insert_mip_filter_pitch_roll_aiding_command_aiding_source(struct microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self) +void insert_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_pitch_roll_aiding_command_aiding_source(struct microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self) +void extract_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -4389,11 +4389,11 @@ void extract_mip_filter_aiding_measurement_enable_response(microstrain_serialize } -void insert_mip_filter_aiding_measurement_enable_command_aiding_source(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self) +void insert_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_aiding_measurement_enable_command_aiding_source(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self) +void extract_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -4740,22 +4740,22 @@ void extract_mip_filter_initialization_configuration_response(microstrain_serial } -void insert_mip_filter_initialization_configuration_command_alignment_selector(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self) +void insert_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_initialization_configuration_command_alignment_selector(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self) +void extract_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_initialization_configuration_command_initial_condition_source(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self) +void insert_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_initialization_configuration_command_initial_condition_source(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self) +void extract_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -5345,11 +5345,11 @@ void extract_mip_filter_ref_point_lever_arm_response(microstrain_serializer* ser } -void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self) +void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self) +void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); diff --git a/src/mip/definitions/commands_filter.h b/src/mip/definitions/commands_filter.h index 57eda7e63..778acc061 100644 --- a/src/mip/definitions/commands_filter.h +++ b/src/mip/definitions/commands_filter.h @@ -15,7 +15,6 @@ extern "C" { #endif // __cplusplus struct mip_interface; -struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -160,24 +159,24 @@ typedef uint8_t mip_filter_reference_frame; static const mip_filter_reference_frame MIP_FILTER_REFERENCE_FRAME_ECEF = 1; ///< WGS84 Earth-fixed, earth centered coordinates static const mip_filter_reference_frame MIP_FILTER_REFERENCE_FRAME_LLH = 2; ///< WGS84 Latitude, longitude, and height above ellipsoid -void insert_mip_filter_reference_frame(struct microstrain_serializer* serializer, const mip_filter_reference_frame self); -void extract_mip_filter_reference_frame(struct microstrain_serializer* serializer, mip_filter_reference_frame* self); +void insert_mip_filter_reference_frame(microstrain_serializer* serializer, const mip_filter_reference_frame self); +void extract_mip_filter_reference_frame(microstrain_serializer* serializer, mip_filter_reference_frame* self); typedef uint8_t mip_filter_mag_param_source; static const mip_filter_mag_param_source MIP_FILTER_MAG_PARAM_SOURCE_NONE = 1; ///< No source. See command documentation for default behavior static const mip_filter_mag_param_source MIP_FILTER_MAG_PARAM_SOURCE_WMM = 2; ///< Magnetic field is assumed to conform to the World Magnetic Model, calculated using current location estimate as an input to the model. static const mip_filter_mag_param_source MIP_FILTER_MAG_PARAM_SOURCE_MANUAL = 3; ///< Magnetic field is assumed to have the parameter specified by the user. -void insert_mip_filter_mag_param_source(struct microstrain_serializer* serializer, const mip_filter_mag_param_source self); -void extract_mip_filter_mag_param_source(struct microstrain_serializer* serializer, mip_filter_mag_param_source* self); +void insert_mip_filter_mag_param_source(microstrain_serializer* serializer, const mip_filter_mag_param_source self); +void extract_mip_filter_mag_param_source(microstrain_serializer* serializer, mip_filter_mag_param_source* self); typedef uint8_t mip_filter_adaptive_measurement; static const mip_filter_adaptive_measurement MIP_FILTER_ADAPTIVE_MEASUREMENT_DISABLED = 0; ///< No adaptive measurement static const mip_filter_adaptive_measurement MIP_FILTER_ADAPTIVE_MEASUREMENT_FIXED = 1; ///< Enable fixed adaptive measurement (use specified limits) static const mip_filter_adaptive_measurement MIP_FILTER_ADAPTIVE_MEASUREMENT_AUTO = 2; ///< Enable auto adaptive measurement -void insert_mip_filter_adaptive_measurement(struct microstrain_serializer* serializer, const mip_filter_adaptive_measurement self); -void extract_mip_filter_adaptive_measurement(struct microstrain_serializer* serializer, mip_filter_adaptive_measurement* self); +void insert_mip_filter_adaptive_measurement(microstrain_serializer* serializer, const mip_filter_adaptive_measurement self); +void extract_mip_filter_adaptive_measurement(microstrain_serializer* serializer, mip_filter_adaptive_measurement* self); //////////////////////////////////////////////////////////////////////////////// @@ -222,8 +221,8 @@ struct mip_filter_set_initial_attitude_command }; typedef struct mip_filter_set_initial_attitude_command mip_filter_set_initial_attitude_command; -void insert_mip_filter_set_initial_attitude_command(struct microstrain_serializer* serializer, const mip_filter_set_initial_attitude_command* self); -void extract_mip_filter_set_initial_attitude_command(struct microstrain_serializer* serializer, mip_filter_set_initial_attitude_command* self); +void insert_mip_filter_set_initial_attitude_command(microstrain_serializer* serializer, const mip_filter_set_initial_attitude_command* self); +void extract_mip_filter_set_initial_attitude_command(microstrain_serializer* serializer, mip_filter_set_initial_attitude_command* self); mip_cmd_result mip_filter_set_initial_attitude(struct mip_interface* device, float roll, float pitch, float heading); @@ -263,11 +262,11 @@ struct mip_filter_estimation_control_command }; typedef struct mip_filter_estimation_control_command mip_filter_estimation_control_command; -void insert_mip_filter_estimation_control_command(struct microstrain_serializer* serializer, const mip_filter_estimation_control_command* self); -void extract_mip_filter_estimation_control_command(struct microstrain_serializer* serializer, mip_filter_estimation_control_command* self); +void insert_mip_filter_estimation_control_command(microstrain_serializer* serializer, const mip_filter_estimation_control_command* self); +void extract_mip_filter_estimation_control_command(microstrain_serializer* serializer, mip_filter_estimation_control_command* self); -void insert_mip_filter_estimation_control_command_enable_flags(struct microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self); -void extract_mip_filter_estimation_control_command_enable_flags(struct microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self); +void insert_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self); +void extract_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self); struct mip_filter_estimation_control_response { @@ -275,8 +274,8 @@ struct mip_filter_estimation_control_response }; typedef struct mip_filter_estimation_control_response mip_filter_estimation_control_response; -void insert_mip_filter_estimation_control_response(struct microstrain_serializer* serializer, const mip_filter_estimation_control_response* self); -void extract_mip_filter_estimation_control_response(struct microstrain_serializer* serializer, mip_filter_estimation_control_response* self); +void insert_mip_filter_estimation_control_response(microstrain_serializer* serializer, const mip_filter_estimation_control_response* self); +void extract_mip_filter_estimation_control_response(microstrain_serializer* serializer, mip_filter_estimation_control_response* self); mip_cmd_result mip_filter_write_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags enable); mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags* enable_out); @@ -309,8 +308,8 @@ struct mip_filter_external_gnss_update_command }; typedef struct mip_filter_external_gnss_update_command mip_filter_external_gnss_update_command; -void insert_mip_filter_external_gnss_update_command(struct microstrain_serializer* serializer, const mip_filter_external_gnss_update_command* self); -void extract_mip_filter_external_gnss_update_command(struct microstrain_serializer* serializer, mip_filter_external_gnss_update_command* self); +void insert_mip_filter_external_gnss_update_command(microstrain_serializer* serializer, const mip_filter_external_gnss_update_command* self); +void extract_mip_filter_external_gnss_update_command(microstrain_serializer* serializer, mip_filter_external_gnss_update_command* self); mip_cmd_result mip_filter_external_gnss_update(struct mip_interface* device, double gps_time, uint16_t gps_week, double latitude, double longitude, double height, const float* velocity, const float* pos_uncertainty, const float* vel_uncertainty); @@ -342,8 +341,8 @@ struct mip_filter_external_heading_update_command }; typedef struct mip_filter_external_heading_update_command mip_filter_external_heading_update_command; -void insert_mip_filter_external_heading_update_command(struct microstrain_serializer* serializer, const mip_filter_external_heading_update_command* self); -void extract_mip_filter_external_heading_update_command(struct microstrain_serializer* serializer, mip_filter_external_heading_update_command* self); +void insert_mip_filter_external_heading_update_command(microstrain_serializer* serializer, const mip_filter_external_heading_update_command* self); +void extract_mip_filter_external_heading_update_command(microstrain_serializer* serializer, mip_filter_external_heading_update_command* self); mip_cmd_result mip_filter_external_heading_update(struct mip_interface* device, float heading, float heading_uncertainty, uint8_t type); @@ -381,8 +380,8 @@ struct mip_filter_external_heading_update_with_time_command }; typedef struct mip_filter_external_heading_update_with_time_command mip_filter_external_heading_update_with_time_command; -void insert_mip_filter_external_heading_update_with_time_command(struct microstrain_serializer* serializer, const mip_filter_external_heading_update_with_time_command* self); -void extract_mip_filter_external_heading_update_with_time_command(struct microstrain_serializer* serializer, mip_filter_external_heading_update_with_time_command* self); +void insert_mip_filter_external_heading_update_with_time_command(microstrain_serializer* serializer, const mip_filter_external_heading_update_with_time_command* self); +void extract_mip_filter_external_heading_update_with_time_command(microstrain_serializer* serializer, mip_filter_external_heading_update_with_time_command* self); mip_cmd_result mip_filter_external_heading_update_with_time(struct mip_interface* device, double gps_time, uint16_t gps_week, float heading, float heading_uncertainty, uint8_t type); @@ -412,11 +411,11 @@ struct mip_filter_tare_orientation_command }; typedef struct mip_filter_tare_orientation_command mip_filter_tare_orientation_command; -void insert_mip_filter_tare_orientation_command(struct microstrain_serializer* serializer, const mip_filter_tare_orientation_command* self); -void extract_mip_filter_tare_orientation_command(struct microstrain_serializer* serializer, mip_filter_tare_orientation_command* self); +void insert_mip_filter_tare_orientation_command(microstrain_serializer* serializer, const mip_filter_tare_orientation_command* self); +void extract_mip_filter_tare_orientation_command(microstrain_serializer* serializer, mip_filter_tare_orientation_command* self); -void insert_mip_filter_tare_orientation_command_mip_tare_axes(struct microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self); -void extract_mip_filter_tare_orientation_command_mip_tare_axes(struct microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self); +void insert_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self); +void extract_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self); struct mip_filter_tare_orientation_response { @@ -424,8 +423,8 @@ struct mip_filter_tare_orientation_response }; typedef struct mip_filter_tare_orientation_response mip_filter_tare_orientation_response; -void insert_mip_filter_tare_orientation_response(struct microstrain_serializer* serializer, const mip_filter_tare_orientation_response* self); -void extract_mip_filter_tare_orientation_response(struct microstrain_serializer* serializer, mip_filter_tare_orientation_response* self); +void insert_mip_filter_tare_orientation_response(microstrain_serializer* serializer, const mip_filter_tare_orientation_response* self); +void extract_mip_filter_tare_orientation_response(microstrain_serializer* serializer, mip_filter_tare_orientation_response* self); mip_cmd_result mip_filter_write_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes axes); mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes* axes_out); @@ -454,11 +453,11 @@ struct mip_filter_vehicle_dynamics_mode_command }; typedef struct mip_filter_vehicle_dynamics_mode_command mip_filter_vehicle_dynamics_mode_command; -void insert_mip_filter_vehicle_dynamics_mode_command(struct microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self); -void extract_mip_filter_vehicle_dynamics_mode_command(struct microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command* self); +void insert_mip_filter_vehicle_dynamics_mode_command(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self); +void extract_mip_filter_vehicle_dynamics_mode_command(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command* self); -void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self); -void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(struct microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self); +void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self); +void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self); struct mip_filter_vehicle_dynamics_mode_response { @@ -466,8 +465,8 @@ struct mip_filter_vehicle_dynamics_mode_response }; typedef struct mip_filter_vehicle_dynamics_mode_response mip_filter_vehicle_dynamics_mode_response; -void insert_mip_filter_vehicle_dynamics_mode_response(struct microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_response* self); -void extract_mip_filter_vehicle_dynamics_mode_response(struct microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_response* self); +void insert_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_response* self); +void extract_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_response* self); mip_cmd_result mip_filter_write_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode); mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* mode_out); @@ -514,8 +513,8 @@ struct mip_filter_sensor_to_vehicle_rotation_euler_command }; typedef struct mip_filter_sensor_to_vehicle_rotation_euler_command mip_filter_sensor_to_vehicle_rotation_euler_command; -void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self); -void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_command* self); +void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self); +void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_command* self); struct mip_filter_sensor_to_vehicle_rotation_euler_response { @@ -525,8 +524,8 @@ struct mip_filter_sensor_to_vehicle_rotation_euler_response }; typedef struct mip_filter_sensor_to_vehicle_rotation_euler_response mip_filter_sensor_to_vehicle_rotation_euler_response; -void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self); -void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self); +void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self); +void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self); mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float roll, float pitch, float yaw); mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out); @@ -577,8 +576,8 @@ struct mip_filter_sensor_to_vehicle_rotation_dcm_command }; typedef struct mip_filter_sensor_to_vehicle_rotation_dcm_command mip_filter_sensor_to_vehicle_rotation_dcm_command; -void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_command* self); -void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_command* self); +void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_command* self); +void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_command* self); struct mip_filter_sensor_to_vehicle_rotation_dcm_response { @@ -586,8 +585,8 @@ struct mip_filter_sensor_to_vehicle_rotation_dcm_response }; typedef struct mip_filter_sensor_to_vehicle_rotation_dcm_response mip_filter_sensor_to_vehicle_rotation_dcm_response; -void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self); -void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self); +void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self); +void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self); mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, const float* dcm); mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, float* dcm_out); @@ -637,8 +636,8 @@ struct mip_filter_sensor_to_vehicle_rotation_quaternion_command }; typedef struct mip_filter_sensor_to_vehicle_rotation_quaternion_command mip_filter_sensor_to_vehicle_rotation_quaternion_command; -void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); -void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); +void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); +void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); struct mip_filter_sensor_to_vehicle_rotation_quaternion_response { @@ -646,8 +645,8 @@ struct mip_filter_sensor_to_vehicle_rotation_quaternion_response }; typedef struct mip_filter_sensor_to_vehicle_rotation_quaternion_response mip_filter_sensor_to_vehicle_rotation_quaternion_response; -void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); -void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); +void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); +void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, const float* quat); mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, float* quat_out); @@ -678,8 +677,8 @@ struct mip_filter_sensor_to_vehicle_offset_command }; typedef struct mip_filter_sensor_to_vehicle_offset_command mip_filter_sensor_to_vehicle_offset_command; -void insert_mip_filter_sensor_to_vehicle_offset_command(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_command* self); -void extract_mip_filter_sensor_to_vehicle_offset_command(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_command* self); +void insert_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_command* self); +void extract_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_command* self); struct mip_filter_sensor_to_vehicle_offset_response { @@ -687,8 +686,8 @@ struct mip_filter_sensor_to_vehicle_offset_response }; typedef struct mip_filter_sensor_to_vehicle_offset_response mip_filter_sensor_to_vehicle_offset_response; -void insert_mip_filter_sensor_to_vehicle_offset_response(struct microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self); -void extract_mip_filter_sensor_to_vehicle_offset_response(struct microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self); +void insert_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self); +void extract_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self); mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(struct mip_interface* device, const float* offset); mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* device, float* offset_out); @@ -716,8 +715,8 @@ struct mip_filter_antenna_offset_command }; typedef struct mip_filter_antenna_offset_command mip_filter_antenna_offset_command; -void insert_mip_filter_antenna_offset_command(struct microstrain_serializer* serializer, const mip_filter_antenna_offset_command* self); -void extract_mip_filter_antenna_offset_command(struct microstrain_serializer* serializer, mip_filter_antenna_offset_command* self); +void insert_mip_filter_antenna_offset_command(microstrain_serializer* serializer, const mip_filter_antenna_offset_command* self); +void extract_mip_filter_antenna_offset_command(microstrain_serializer* serializer, mip_filter_antenna_offset_command* self); struct mip_filter_antenna_offset_response { @@ -725,8 +724,8 @@ struct mip_filter_antenna_offset_response }; typedef struct mip_filter_antenna_offset_response mip_filter_antenna_offset_response; -void insert_mip_filter_antenna_offset_response(struct microstrain_serializer* serializer, const mip_filter_antenna_offset_response* self); -void extract_mip_filter_antenna_offset_response(struct microstrain_serializer* serializer, mip_filter_antenna_offset_response* self); +void insert_mip_filter_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_antenna_offset_response* self); +void extract_mip_filter_antenna_offset_response(microstrain_serializer* serializer, mip_filter_antenna_offset_response* self); mip_cmd_result mip_filter_write_antenna_offset(struct mip_interface* device, const float* offset); mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, float* offset_out); @@ -759,11 +758,11 @@ struct mip_filter_gnss_source_command }; typedef struct mip_filter_gnss_source_command mip_filter_gnss_source_command; -void insert_mip_filter_gnss_source_command(struct microstrain_serializer* serializer, const mip_filter_gnss_source_command* self); -void extract_mip_filter_gnss_source_command(struct microstrain_serializer* serializer, mip_filter_gnss_source_command* self); +void insert_mip_filter_gnss_source_command(microstrain_serializer* serializer, const mip_filter_gnss_source_command* self); +void extract_mip_filter_gnss_source_command(microstrain_serializer* serializer, mip_filter_gnss_source_command* self); -void insert_mip_filter_gnss_source_command_source(struct microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self); -void extract_mip_filter_gnss_source_command_source(struct microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self); +void insert_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self); +void extract_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self); struct mip_filter_gnss_source_response { @@ -771,8 +770,8 @@ struct mip_filter_gnss_source_response }; typedef struct mip_filter_gnss_source_response mip_filter_gnss_source_response; -void insert_mip_filter_gnss_source_response(struct microstrain_serializer* serializer, const mip_filter_gnss_source_response* self); -void extract_mip_filter_gnss_source_response(struct microstrain_serializer* serializer, mip_filter_gnss_source_response* self); +void insert_mip_filter_gnss_source_response(microstrain_serializer* serializer, const mip_filter_gnss_source_response* self); +void extract_mip_filter_gnss_source_response(microstrain_serializer* serializer, mip_filter_gnss_source_response* self); mip_cmd_result mip_filter_write_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source source); mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source* source_out); @@ -816,11 +815,11 @@ struct mip_filter_heading_source_command }; typedef struct mip_filter_heading_source_command mip_filter_heading_source_command; -void insert_mip_filter_heading_source_command(struct microstrain_serializer* serializer, const mip_filter_heading_source_command* self); -void extract_mip_filter_heading_source_command(struct microstrain_serializer* serializer, mip_filter_heading_source_command* self); +void insert_mip_filter_heading_source_command(microstrain_serializer* serializer, const mip_filter_heading_source_command* self); +void extract_mip_filter_heading_source_command(microstrain_serializer* serializer, mip_filter_heading_source_command* self); -void insert_mip_filter_heading_source_command_source(struct microstrain_serializer* serializer, const mip_filter_heading_source_command_source self); -void extract_mip_filter_heading_source_command_source(struct microstrain_serializer* serializer, mip_filter_heading_source_command_source* self); +void insert_mip_filter_heading_source_command_source(microstrain_serializer* serializer, const mip_filter_heading_source_command_source self); +void extract_mip_filter_heading_source_command_source(microstrain_serializer* serializer, mip_filter_heading_source_command_source* self); struct mip_filter_heading_source_response { @@ -828,8 +827,8 @@ struct mip_filter_heading_source_response }; typedef struct mip_filter_heading_source_response mip_filter_heading_source_response; -void insert_mip_filter_heading_source_response(struct microstrain_serializer* serializer, const mip_filter_heading_source_response* self); -void extract_mip_filter_heading_source_response(struct microstrain_serializer* serializer, mip_filter_heading_source_response* self); +void insert_mip_filter_heading_source_response(microstrain_serializer* serializer, const mip_filter_heading_source_response* self); +void extract_mip_filter_heading_source_response(microstrain_serializer* serializer, mip_filter_heading_source_response* self); mip_cmd_result mip_filter_write_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source source); mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source* source_out); @@ -860,8 +859,8 @@ struct mip_filter_auto_init_control_command }; typedef struct mip_filter_auto_init_control_command mip_filter_auto_init_control_command; -void insert_mip_filter_auto_init_control_command(struct microstrain_serializer* serializer, const mip_filter_auto_init_control_command* self); -void extract_mip_filter_auto_init_control_command(struct microstrain_serializer* serializer, mip_filter_auto_init_control_command* self); +void insert_mip_filter_auto_init_control_command(microstrain_serializer* serializer, const mip_filter_auto_init_control_command* self); +void extract_mip_filter_auto_init_control_command(microstrain_serializer* serializer, mip_filter_auto_init_control_command* self); struct mip_filter_auto_init_control_response { @@ -869,8 +868,8 @@ struct mip_filter_auto_init_control_response }; typedef struct mip_filter_auto_init_control_response mip_filter_auto_init_control_response; -void insert_mip_filter_auto_init_control_response(struct microstrain_serializer* serializer, const mip_filter_auto_init_control_response* self); -void extract_mip_filter_auto_init_control_response(struct microstrain_serializer* serializer, mip_filter_auto_init_control_response* self); +void insert_mip_filter_auto_init_control_response(microstrain_serializer* serializer, const mip_filter_auto_init_control_response* self); +void extract_mip_filter_auto_init_control_response(microstrain_serializer* serializer, mip_filter_auto_init_control_response* self); mip_cmd_result mip_filter_write_auto_init_control(struct mip_interface* device, uint8_t enable); mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, uint8_t* enable_out); @@ -899,8 +898,8 @@ struct mip_filter_accel_noise_command }; typedef struct mip_filter_accel_noise_command mip_filter_accel_noise_command; -void insert_mip_filter_accel_noise_command(struct microstrain_serializer* serializer, const mip_filter_accel_noise_command* self); -void extract_mip_filter_accel_noise_command(struct microstrain_serializer* serializer, mip_filter_accel_noise_command* self); +void insert_mip_filter_accel_noise_command(microstrain_serializer* serializer, const mip_filter_accel_noise_command* self); +void extract_mip_filter_accel_noise_command(microstrain_serializer* serializer, mip_filter_accel_noise_command* self); struct mip_filter_accel_noise_response { @@ -908,8 +907,8 @@ struct mip_filter_accel_noise_response }; typedef struct mip_filter_accel_noise_response mip_filter_accel_noise_response; -void insert_mip_filter_accel_noise_response(struct microstrain_serializer* serializer, const mip_filter_accel_noise_response* self); -void extract_mip_filter_accel_noise_response(struct microstrain_serializer* serializer, mip_filter_accel_noise_response* self); +void insert_mip_filter_accel_noise_response(microstrain_serializer* serializer, const mip_filter_accel_noise_response* self); +void extract_mip_filter_accel_noise_response(microstrain_serializer* serializer, mip_filter_accel_noise_response* self); mip_cmd_result mip_filter_write_accel_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* noise_out); @@ -938,8 +937,8 @@ struct mip_filter_gyro_noise_command }; typedef struct mip_filter_gyro_noise_command mip_filter_gyro_noise_command; -void insert_mip_filter_gyro_noise_command(struct microstrain_serializer* serializer, const mip_filter_gyro_noise_command* self); -void extract_mip_filter_gyro_noise_command(struct microstrain_serializer* serializer, mip_filter_gyro_noise_command* self); +void insert_mip_filter_gyro_noise_command(microstrain_serializer* serializer, const mip_filter_gyro_noise_command* self); +void extract_mip_filter_gyro_noise_command(microstrain_serializer* serializer, mip_filter_gyro_noise_command* self); struct mip_filter_gyro_noise_response { @@ -947,8 +946,8 @@ struct mip_filter_gyro_noise_response }; typedef struct mip_filter_gyro_noise_response mip_filter_gyro_noise_response; -void insert_mip_filter_gyro_noise_response(struct microstrain_serializer* serializer, const mip_filter_gyro_noise_response* self); -void extract_mip_filter_gyro_noise_response(struct microstrain_serializer* serializer, mip_filter_gyro_noise_response* self); +void insert_mip_filter_gyro_noise_response(microstrain_serializer* serializer, const mip_filter_gyro_noise_response* self); +void extract_mip_filter_gyro_noise_response(microstrain_serializer* serializer, mip_filter_gyro_noise_response* self); mip_cmd_result mip_filter_write_gyro_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* noise_out); @@ -975,8 +974,8 @@ struct mip_filter_accel_bias_model_command }; typedef struct mip_filter_accel_bias_model_command mip_filter_accel_bias_model_command; -void insert_mip_filter_accel_bias_model_command(struct microstrain_serializer* serializer, const mip_filter_accel_bias_model_command* self); -void extract_mip_filter_accel_bias_model_command(struct microstrain_serializer* serializer, mip_filter_accel_bias_model_command* self); +void insert_mip_filter_accel_bias_model_command(microstrain_serializer* serializer, const mip_filter_accel_bias_model_command* self); +void extract_mip_filter_accel_bias_model_command(microstrain_serializer* serializer, mip_filter_accel_bias_model_command* self); struct mip_filter_accel_bias_model_response { @@ -985,8 +984,8 @@ struct mip_filter_accel_bias_model_response }; typedef struct mip_filter_accel_bias_model_response mip_filter_accel_bias_model_response; -void insert_mip_filter_accel_bias_model_response(struct microstrain_serializer* serializer, const mip_filter_accel_bias_model_response* self); -void extract_mip_filter_accel_bias_model_response(struct microstrain_serializer* serializer, mip_filter_accel_bias_model_response* self); +void insert_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, const mip_filter_accel_bias_model_response* self); +void extract_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, mip_filter_accel_bias_model_response* self); mip_cmd_result mip_filter_write_accel_bias_model(struct mip_interface* device, const float* beta, const float* noise); mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, float* beta_out, float* noise_out); @@ -1013,8 +1012,8 @@ struct mip_filter_gyro_bias_model_command }; typedef struct mip_filter_gyro_bias_model_command mip_filter_gyro_bias_model_command; -void insert_mip_filter_gyro_bias_model_command(struct microstrain_serializer* serializer, const mip_filter_gyro_bias_model_command* self); -void extract_mip_filter_gyro_bias_model_command(struct microstrain_serializer* serializer, mip_filter_gyro_bias_model_command* self); +void insert_mip_filter_gyro_bias_model_command(microstrain_serializer* serializer, const mip_filter_gyro_bias_model_command* self); +void extract_mip_filter_gyro_bias_model_command(microstrain_serializer* serializer, mip_filter_gyro_bias_model_command* self); struct mip_filter_gyro_bias_model_response { @@ -1023,8 +1022,8 @@ struct mip_filter_gyro_bias_model_response }; typedef struct mip_filter_gyro_bias_model_response mip_filter_gyro_bias_model_response; -void insert_mip_filter_gyro_bias_model_response(struct microstrain_serializer* serializer, const mip_filter_gyro_bias_model_response* self); -void extract_mip_filter_gyro_bias_model_response(struct microstrain_serializer* serializer, mip_filter_gyro_bias_model_response* self); +void insert_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, const mip_filter_gyro_bias_model_response* self); +void extract_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, mip_filter_gyro_bias_model_response* self); mip_cmd_result mip_filter_write_gyro_bias_model(struct mip_interface* device, const float* beta, const float* noise); mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, float* beta_out, float* noise_out); @@ -1055,11 +1054,11 @@ struct mip_filter_altitude_aiding_command }; typedef struct mip_filter_altitude_aiding_command mip_filter_altitude_aiding_command; -void insert_mip_filter_altitude_aiding_command(struct microstrain_serializer* serializer, const mip_filter_altitude_aiding_command* self); -void extract_mip_filter_altitude_aiding_command(struct microstrain_serializer* serializer, mip_filter_altitude_aiding_command* self); +void insert_mip_filter_altitude_aiding_command(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command* self); +void extract_mip_filter_altitude_aiding_command(microstrain_serializer* serializer, mip_filter_altitude_aiding_command* self); -void insert_mip_filter_altitude_aiding_command_aiding_selector(struct microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self); -void extract_mip_filter_altitude_aiding_command_aiding_selector(struct microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self); +void insert_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self); +void extract_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self); struct mip_filter_altitude_aiding_response { @@ -1067,8 +1066,8 @@ struct mip_filter_altitude_aiding_response }; typedef struct mip_filter_altitude_aiding_response mip_filter_altitude_aiding_response; -void insert_mip_filter_altitude_aiding_response(struct microstrain_serializer* serializer, const mip_filter_altitude_aiding_response* self); -void extract_mip_filter_altitude_aiding_response(struct microstrain_serializer* serializer, mip_filter_altitude_aiding_response* self); +void insert_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, const mip_filter_altitude_aiding_response* self); +void extract_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, mip_filter_altitude_aiding_response* self); mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector selector); mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector* selector_out); @@ -1096,11 +1095,11 @@ struct mip_filter_pitch_roll_aiding_command }; typedef struct mip_filter_pitch_roll_aiding_command mip_filter_pitch_roll_aiding_command; -void insert_mip_filter_pitch_roll_aiding_command(struct microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self); -void extract_mip_filter_pitch_roll_aiding_command(struct microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command* self); +void insert_mip_filter_pitch_roll_aiding_command(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self); +void extract_mip_filter_pitch_roll_aiding_command(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command* self); -void insert_mip_filter_pitch_roll_aiding_command_aiding_source(struct microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self); -void extract_mip_filter_pitch_roll_aiding_command_aiding_source(struct microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self); +void insert_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self); +void extract_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self); struct mip_filter_pitch_roll_aiding_response { @@ -1108,8 +1107,8 @@ struct mip_filter_pitch_roll_aiding_response }; typedef struct mip_filter_pitch_roll_aiding_response mip_filter_pitch_roll_aiding_response; -void insert_mip_filter_pitch_roll_aiding_response(struct microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_response* self); -void extract_mip_filter_pitch_roll_aiding_response(struct microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_response* self); +void insert_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_response* self); +void extract_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_response* self); mip_cmd_result mip_filter_write_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source source); mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source* source_out); @@ -1134,8 +1133,8 @@ struct mip_filter_auto_zupt_command }; typedef struct mip_filter_auto_zupt_command mip_filter_auto_zupt_command; -void insert_mip_filter_auto_zupt_command(struct microstrain_serializer* serializer, const mip_filter_auto_zupt_command* self); -void extract_mip_filter_auto_zupt_command(struct microstrain_serializer* serializer, mip_filter_auto_zupt_command* self); +void insert_mip_filter_auto_zupt_command(microstrain_serializer* serializer, const mip_filter_auto_zupt_command* self); +void extract_mip_filter_auto_zupt_command(microstrain_serializer* serializer, mip_filter_auto_zupt_command* self); struct mip_filter_auto_zupt_response { @@ -1144,8 +1143,8 @@ struct mip_filter_auto_zupt_response }; typedef struct mip_filter_auto_zupt_response mip_filter_auto_zupt_response; -void insert_mip_filter_auto_zupt_response(struct microstrain_serializer* serializer, const mip_filter_auto_zupt_response* self); -void extract_mip_filter_auto_zupt_response(struct microstrain_serializer* serializer, mip_filter_auto_zupt_response* self); +void insert_mip_filter_auto_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_zupt_response* self); +void extract_mip_filter_auto_zupt_response(microstrain_serializer* serializer, mip_filter_auto_zupt_response* self); mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t enable, float threshold); mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out); @@ -1171,8 +1170,8 @@ struct mip_filter_auto_angular_zupt_command }; typedef struct mip_filter_auto_angular_zupt_command mip_filter_auto_angular_zupt_command; -void insert_mip_filter_auto_angular_zupt_command(struct microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_command* self); -void extract_mip_filter_auto_angular_zupt_command(struct microstrain_serializer* serializer, mip_filter_auto_angular_zupt_command* self); +void insert_mip_filter_auto_angular_zupt_command(microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_command* self); +void extract_mip_filter_auto_angular_zupt_command(microstrain_serializer* serializer, mip_filter_auto_angular_zupt_command* self); struct mip_filter_auto_angular_zupt_response { @@ -1181,8 +1180,8 @@ struct mip_filter_auto_angular_zupt_response }; typedef struct mip_filter_auto_angular_zupt_response mip_filter_auto_angular_zupt_response; -void insert_mip_filter_auto_angular_zupt_response(struct microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_response* self); -void extract_mip_filter_auto_angular_zupt_response(struct microstrain_serializer* serializer, mip_filter_auto_angular_zupt_response* self); +void insert_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_response* self); +void extract_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, mip_filter_auto_angular_zupt_response* self); mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, uint8_t enable, float threshold); mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out); @@ -1226,8 +1225,8 @@ struct mip_filter_mag_capture_auto_cal_command }; typedef struct mip_filter_mag_capture_auto_cal_command mip_filter_mag_capture_auto_cal_command; -void insert_mip_filter_mag_capture_auto_cal_command(struct microstrain_serializer* serializer, const mip_filter_mag_capture_auto_cal_command* self); -void extract_mip_filter_mag_capture_auto_cal_command(struct microstrain_serializer* serializer, mip_filter_mag_capture_auto_cal_command* self); +void insert_mip_filter_mag_capture_auto_cal_command(microstrain_serializer* serializer, const mip_filter_mag_capture_auto_cal_command* self); +void extract_mip_filter_mag_capture_auto_cal_command(microstrain_serializer* serializer, mip_filter_mag_capture_auto_cal_command* self); mip_cmd_result mip_filter_write_mag_capture_auto_cal(struct mip_interface* device); mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device); @@ -1252,8 +1251,8 @@ struct mip_filter_gravity_noise_command }; typedef struct mip_filter_gravity_noise_command mip_filter_gravity_noise_command; -void insert_mip_filter_gravity_noise_command(struct microstrain_serializer* serializer, const mip_filter_gravity_noise_command* self); -void extract_mip_filter_gravity_noise_command(struct microstrain_serializer* serializer, mip_filter_gravity_noise_command* self); +void insert_mip_filter_gravity_noise_command(microstrain_serializer* serializer, const mip_filter_gravity_noise_command* self); +void extract_mip_filter_gravity_noise_command(microstrain_serializer* serializer, mip_filter_gravity_noise_command* self); struct mip_filter_gravity_noise_response { @@ -1261,8 +1260,8 @@ struct mip_filter_gravity_noise_response }; typedef struct mip_filter_gravity_noise_response mip_filter_gravity_noise_response; -void insert_mip_filter_gravity_noise_response(struct microstrain_serializer* serializer, const mip_filter_gravity_noise_response* self); -void extract_mip_filter_gravity_noise_response(struct microstrain_serializer* serializer, mip_filter_gravity_noise_response* self); +void insert_mip_filter_gravity_noise_response(microstrain_serializer* serializer, const mip_filter_gravity_noise_response* self); +void extract_mip_filter_gravity_noise_response(microstrain_serializer* serializer, mip_filter_gravity_noise_response* self); mip_cmd_result mip_filter_write_gravity_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float* noise_out); @@ -1290,8 +1289,8 @@ struct mip_filter_pressure_altitude_noise_command }; typedef struct mip_filter_pressure_altitude_noise_command mip_filter_pressure_altitude_noise_command; -void insert_mip_filter_pressure_altitude_noise_command(struct microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self); -void extract_mip_filter_pressure_altitude_noise_command(struct microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_command* self); +void insert_mip_filter_pressure_altitude_noise_command(microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self); +void extract_mip_filter_pressure_altitude_noise_command(microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_command* self); struct mip_filter_pressure_altitude_noise_response { @@ -1299,8 +1298,8 @@ struct mip_filter_pressure_altitude_noise_response }; typedef struct mip_filter_pressure_altitude_noise_response mip_filter_pressure_altitude_noise_response; -void insert_mip_filter_pressure_altitude_noise_response(struct microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self); -void extract_mip_filter_pressure_altitude_noise_response(struct microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_response* self); +void insert_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self); +void extract_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_response* self); mip_cmd_result mip_filter_write_pressure_altitude_noise(struct mip_interface* device, float noise); mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* device, float* noise_out); @@ -1330,8 +1329,8 @@ struct mip_filter_hard_iron_offset_noise_command }; typedef struct mip_filter_hard_iron_offset_noise_command mip_filter_hard_iron_offset_noise_command; -void insert_mip_filter_hard_iron_offset_noise_command(struct microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self); -void extract_mip_filter_hard_iron_offset_noise_command(struct microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_command* self); +void insert_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self); +void extract_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_command* self); struct mip_filter_hard_iron_offset_noise_response { @@ -1339,8 +1338,8 @@ struct mip_filter_hard_iron_offset_noise_response }; typedef struct mip_filter_hard_iron_offset_noise_response mip_filter_hard_iron_offset_noise_response; -void insert_mip_filter_hard_iron_offset_noise_response(struct microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self); -void extract_mip_filter_hard_iron_offset_noise_response(struct microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self); +void insert_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self); +void extract_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self); mip_cmd_result mip_filter_write_hard_iron_offset_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* device, float* noise_out); @@ -1369,8 +1368,8 @@ struct mip_filter_soft_iron_matrix_noise_command }; typedef struct mip_filter_soft_iron_matrix_noise_command mip_filter_soft_iron_matrix_noise_command; -void insert_mip_filter_soft_iron_matrix_noise_command(struct microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self); -void extract_mip_filter_soft_iron_matrix_noise_command(struct microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_command* self); +void insert_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self); +void extract_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_command* self); struct mip_filter_soft_iron_matrix_noise_response { @@ -1378,8 +1377,8 @@ struct mip_filter_soft_iron_matrix_noise_response }; typedef struct mip_filter_soft_iron_matrix_noise_response mip_filter_soft_iron_matrix_noise_response; -void insert_mip_filter_soft_iron_matrix_noise_response(struct microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self); -void extract_mip_filter_soft_iron_matrix_noise_response(struct microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self); +void insert_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self); +void extract_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self); mip_cmd_result mip_filter_write_soft_iron_matrix_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* device, float* noise_out); @@ -1408,8 +1407,8 @@ struct mip_filter_mag_noise_command }; typedef struct mip_filter_mag_noise_command mip_filter_mag_noise_command; -void insert_mip_filter_mag_noise_command(struct microstrain_serializer* serializer, const mip_filter_mag_noise_command* self); -void extract_mip_filter_mag_noise_command(struct microstrain_serializer* serializer, mip_filter_mag_noise_command* self); +void insert_mip_filter_mag_noise_command(microstrain_serializer* serializer, const mip_filter_mag_noise_command* self); +void extract_mip_filter_mag_noise_command(microstrain_serializer* serializer, mip_filter_mag_noise_command* self); struct mip_filter_mag_noise_response { @@ -1417,8 +1416,8 @@ struct mip_filter_mag_noise_response }; typedef struct mip_filter_mag_noise_response mip_filter_mag_noise_response; -void insert_mip_filter_mag_noise_response(struct microstrain_serializer* serializer, const mip_filter_mag_noise_response* self); -void extract_mip_filter_mag_noise_response(struct microstrain_serializer* serializer, mip_filter_mag_noise_response* self); +void insert_mip_filter_mag_noise_response(microstrain_serializer* serializer, const mip_filter_mag_noise_response* self); +void extract_mip_filter_mag_noise_response(microstrain_serializer* serializer, mip_filter_mag_noise_response* self); mip_cmd_result mip_filter_write_mag_noise(struct mip_interface* device, const float* noise); mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* noise_out); @@ -1446,8 +1445,8 @@ struct mip_filter_inclination_source_command }; typedef struct mip_filter_inclination_source_command mip_filter_inclination_source_command; -void insert_mip_filter_inclination_source_command(struct microstrain_serializer* serializer, const mip_filter_inclination_source_command* self); -void extract_mip_filter_inclination_source_command(struct microstrain_serializer* serializer, mip_filter_inclination_source_command* self); +void insert_mip_filter_inclination_source_command(microstrain_serializer* serializer, const mip_filter_inclination_source_command* self); +void extract_mip_filter_inclination_source_command(microstrain_serializer* serializer, mip_filter_inclination_source_command* self); struct mip_filter_inclination_source_response { @@ -1456,8 +1455,8 @@ struct mip_filter_inclination_source_response }; typedef struct mip_filter_inclination_source_response mip_filter_inclination_source_response; -void insert_mip_filter_inclination_source_response(struct microstrain_serializer* serializer, const mip_filter_inclination_source_response* self); -void extract_mip_filter_inclination_source_response(struct microstrain_serializer* serializer, mip_filter_inclination_source_response* self); +void insert_mip_filter_inclination_source_response(microstrain_serializer* serializer, const mip_filter_inclination_source_response* self); +void extract_mip_filter_inclination_source_response(microstrain_serializer* serializer, mip_filter_inclination_source_response* self); mip_cmd_result mip_filter_write_inclination_source(struct mip_interface* device, mip_filter_mag_param_source source, float inclination); mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* inclination_out); @@ -1485,8 +1484,8 @@ struct mip_filter_magnetic_declination_source_command }; typedef struct mip_filter_magnetic_declination_source_command mip_filter_magnetic_declination_source_command; -void insert_mip_filter_magnetic_declination_source_command(struct microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_command* self); -void extract_mip_filter_magnetic_declination_source_command(struct microstrain_serializer* serializer, mip_filter_magnetic_declination_source_command* self); +void insert_mip_filter_magnetic_declination_source_command(microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_command* self); +void extract_mip_filter_magnetic_declination_source_command(microstrain_serializer* serializer, mip_filter_magnetic_declination_source_command* self); struct mip_filter_magnetic_declination_source_response { @@ -1495,8 +1494,8 @@ struct mip_filter_magnetic_declination_source_response }; typedef struct mip_filter_magnetic_declination_source_response mip_filter_magnetic_declination_source_response; -void insert_mip_filter_magnetic_declination_source_response(struct microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_response* self); -void extract_mip_filter_magnetic_declination_source_response(struct microstrain_serializer* serializer, mip_filter_magnetic_declination_source_response* self); +void insert_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_response* self); +void extract_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, mip_filter_magnetic_declination_source_response* self); mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source source, float declination); mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* declination_out); @@ -1523,8 +1522,8 @@ struct mip_filter_mag_field_magnitude_source_command }; typedef struct mip_filter_mag_field_magnitude_source_command mip_filter_mag_field_magnitude_source_command; -void insert_mip_filter_mag_field_magnitude_source_command(struct microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self); -void extract_mip_filter_mag_field_magnitude_source_command(struct microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_command* self); +void insert_mip_filter_mag_field_magnitude_source_command(microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self); +void extract_mip_filter_mag_field_magnitude_source_command(microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_command* self); struct mip_filter_mag_field_magnitude_source_response { @@ -1533,8 +1532,8 @@ struct mip_filter_mag_field_magnitude_source_response }; typedef struct mip_filter_mag_field_magnitude_source_response mip_filter_mag_field_magnitude_source_response; -void insert_mip_filter_mag_field_magnitude_source_response(struct microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self); -void extract_mip_filter_mag_field_magnitude_source_response(struct microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self); +void insert_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self); +void extract_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self); mip_cmd_result mip_filter_write_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source source, float magnitude); mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* magnitude_out); @@ -1563,8 +1562,8 @@ struct mip_filter_reference_position_command }; typedef struct mip_filter_reference_position_command mip_filter_reference_position_command; -void insert_mip_filter_reference_position_command(struct microstrain_serializer* serializer, const mip_filter_reference_position_command* self); -void extract_mip_filter_reference_position_command(struct microstrain_serializer* serializer, mip_filter_reference_position_command* self); +void insert_mip_filter_reference_position_command(microstrain_serializer* serializer, const mip_filter_reference_position_command* self); +void extract_mip_filter_reference_position_command(microstrain_serializer* serializer, mip_filter_reference_position_command* self); struct mip_filter_reference_position_response { @@ -1575,8 +1574,8 @@ struct mip_filter_reference_position_response }; typedef struct mip_filter_reference_position_response mip_filter_reference_position_response; -void insert_mip_filter_reference_position_response(struct microstrain_serializer* serializer, const mip_filter_reference_position_response* self); -void extract_mip_filter_reference_position_response(struct microstrain_serializer* serializer, mip_filter_reference_position_response* self); +void insert_mip_filter_reference_position_response(microstrain_serializer* serializer, const mip_filter_reference_position_response* self); +void extract_mip_filter_reference_position_response(microstrain_serializer* serializer, mip_filter_reference_position_response* self); mip_cmd_result mip_filter_write_reference_position(struct mip_interface* device, bool enable, double latitude, double longitude, double altitude); mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, bool* enable_out, double* latitude_out, double* longitude_out, double* altitude_out); @@ -1618,8 +1617,8 @@ struct mip_filter_accel_magnitude_error_adaptive_measurement_command }; typedef struct mip_filter_accel_magnitude_error_adaptive_measurement_command mip_filter_accel_magnitude_error_adaptive_measurement_command; -void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(struct microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self); -void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(struct microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_command* self); +void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self); +void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_command* self); struct mip_filter_accel_magnitude_error_adaptive_measurement_response { @@ -1633,8 +1632,8 @@ struct mip_filter_accel_magnitude_error_adaptive_measurement_response }; typedef struct mip_filter_accel_magnitude_error_adaptive_measurement_response mip_filter_accel_magnitude_error_adaptive_measurement_response; -void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(struct microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self); -void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(struct microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self); +void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self); +void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self); mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty); mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); @@ -1671,8 +1670,8 @@ struct mip_filter_mag_magnitude_error_adaptive_measurement_command }; typedef struct mip_filter_mag_magnitude_error_adaptive_measurement_command mip_filter_mag_magnitude_error_adaptive_measurement_command; -void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(struct microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self); -void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(struct microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_command* self); +void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self); +void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_command* self); struct mip_filter_mag_magnitude_error_adaptive_measurement_response { @@ -1686,8 +1685,8 @@ struct mip_filter_mag_magnitude_error_adaptive_measurement_response }; typedef struct mip_filter_mag_magnitude_error_adaptive_measurement_response mip_filter_mag_magnitude_error_adaptive_measurement_response; -void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(struct microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self); -void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(struct microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self); +void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self); +void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self); mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty); mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); @@ -1724,8 +1723,8 @@ struct mip_filter_mag_dip_angle_error_adaptive_measurement_command }; typedef struct mip_filter_mag_dip_angle_error_adaptive_measurement_command mip_filter_mag_dip_angle_error_adaptive_measurement_command; -void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(struct microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); -void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(struct microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); +void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); +void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); struct mip_filter_mag_dip_angle_error_adaptive_measurement_response { @@ -1737,8 +1736,8 @@ struct mip_filter_mag_dip_angle_error_adaptive_measurement_response }; typedef struct mip_filter_mag_dip_angle_error_adaptive_measurement_response mip_filter_mag_dip_angle_error_adaptive_measurement_response; -void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(struct microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); -void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(struct microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); +void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); +void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool enable, float frequency, float high_limit, float high_limit_uncertainty, float minimum_uncertainty); mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool* enable_out, float* frequency_out, float* high_limit_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); @@ -1776,11 +1775,11 @@ struct mip_filter_aiding_measurement_enable_command }; typedef struct mip_filter_aiding_measurement_enable_command mip_filter_aiding_measurement_enable_command; -void insert_mip_filter_aiding_measurement_enable_command(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self); -void extract_mip_filter_aiding_measurement_enable_command(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command* self); +void insert_mip_filter_aiding_measurement_enable_command(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self); +void extract_mip_filter_aiding_measurement_enable_command(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command* self); -void insert_mip_filter_aiding_measurement_enable_command_aiding_source(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self); -void extract_mip_filter_aiding_measurement_enable_command_aiding_source(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self); +void insert_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self); +void extract_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self); struct mip_filter_aiding_measurement_enable_response { @@ -1789,8 +1788,8 @@ struct mip_filter_aiding_measurement_enable_response }; typedef struct mip_filter_aiding_measurement_enable_response mip_filter_aiding_measurement_enable_response; -void insert_mip_filter_aiding_measurement_enable_response(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self); -void extract_mip_filter_aiding_measurement_enable_response(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_response* self); +void insert_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self); +void extract_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_response* self); mip_cmd_result mip_filter_write_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool enable); mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool* enable_out); @@ -1829,8 +1828,8 @@ struct mip_filter_kinematic_constraint_command }; typedef struct mip_filter_kinematic_constraint_command mip_filter_kinematic_constraint_command; -void insert_mip_filter_kinematic_constraint_command(struct microstrain_serializer* serializer, const mip_filter_kinematic_constraint_command* self); -void extract_mip_filter_kinematic_constraint_command(struct microstrain_serializer* serializer, mip_filter_kinematic_constraint_command* self); +void insert_mip_filter_kinematic_constraint_command(microstrain_serializer* serializer, const mip_filter_kinematic_constraint_command* self); +void extract_mip_filter_kinematic_constraint_command(microstrain_serializer* serializer, mip_filter_kinematic_constraint_command* self); struct mip_filter_kinematic_constraint_response { @@ -1840,8 +1839,8 @@ struct mip_filter_kinematic_constraint_response }; typedef struct mip_filter_kinematic_constraint_response mip_filter_kinematic_constraint_response; -void insert_mip_filter_kinematic_constraint_response(struct microstrain_serializer* serializer, const mip_filter_kinematic_constraint_response* self); -void extract_mip_filter_kinematic_constraint_response(struct microstrain_serializer* serializer, mip_filter_kinematic_constraint_response* self); +void insert_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, const mip_filter_kinematic_constraint_response* self); +void extract_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, mip_filter_kinematic_constraint_response* self); mip_cmd_result mip_filter_write_kinematic_constraint(struct mip_interface* device, uint8_t acceleration_constraint_selection, uint8_t velocity_constraint_selection, uint8_t angular_constraint_selection); mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device, uint8_t* acceleration_constraint_selection_out, uint8_t* velocity_constraint_selection_out, uint8_t* angular_constraint_selection_out); @@ -1890,14 +1889,14 @@ struct mip_filter_initialization_configuration_command }; typedef struct mip_filter_initialization_configuration_command mip_filter_initialization_configuration_command; -void insert_mip_filter_initialization_configuration_command(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command* self); -void extract_mip_filter_initialization_configuration_command(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command* self); +void insert_mip_filter_initialization_configuration_command(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command* self); +void extract_mip_filter_initialization_configuration_command(microstrain_serializer* serializer, mip_filter_initialization_configuration_command* self); -void insert_mip_filter_initialization_configuration_command_alignment_selector(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self); -void extract_mip_filter_initialization_configuration_command_alignment_selector(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self); +void insert_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self); +void extract_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self); -void insert_mip_filter_initialization_configuration_command_initial_condition_source(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self); -void extract_mip_filter_initialization_configuration_command_initial_condition_source(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self); +void insert_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self); +void extract_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self); struct mip_filter_initialization_configuration_response { @@ -1913,8 +1912,8 @@ struct mip_filter_initialization_configuration_response }; typedef struct mip_filter_initialization_configuration_response mip_filter_initialization_configuration_response; -void insert_mip_filter_initialization_configuration_response(struct microstrain_serializer* serializer, const mip_filter_initialization_configuration_response* self); -void extract_mip_filter_initialization_configuration_response(struct microstrain_serializer* serializer, mip_filter_initialization_configuration_response* self); +void insert_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, const mip_filter_initialization_configuration_response* self); +void extract_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, mip_filter_initialization_configuration_response* self); mip_cmd_result mip_filter_write_initialization_configuration(struct mip_interface* device, uint8_t wait_for_run_command, mip_filter_initialization_configuration_command_initial_condition_source initial_cond_src, mip_filter_initialization_configuration_command_alignment_selector auto_heading_alignment_selector, float initial_heading, float initial_pitch, float initial_roll, const float* initial_position, const float* initial_velocity, mip_filter_reference_frame reference_frame_selector); mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface* device, uint8_t* wait_for_run_command_out, mip_filter_initialization_configuration_command_initial_condition_source* initial_cond_src_out, mip_filter_initialization_configuration_command_alignment_selector* auto_heading_alignment_selector_out, float* initial_heading_out, float* initial_pitch_out, float* initial_roll_out, float* initial_position_out, float* initial_velocity_out, mip_filter_reference_frame* reference_frame_selector_out); @@ -1938,8 +1937,8 @@ struct mip_filter_adaptive_filter_options_command }; typedef struct mip_filter_adaptive_filter_options_command mip_filter_adaptive_filter_options_command; -void insert_mip_filter_adaptive_filter_options_command(struct microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_command* self); -void extract_mip_filter_adaptive_filter_options_command(struct microstrain_serializer* serializer, mip_filter_adaptive_filter_options_command* self); +void insert_mip_filter_adaptive_filter_options_command(microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_command* self); +void extract_mip_filter_adaptive_filter_options_command(microstrain_serializer* serializer, mip_filter_adaptive_filter_options_command* self); struct mip_filter_adaptive_filter_options_response { @@ -1948,8 +1947,8 @@ struct mip_filter_adaptive_filter_options_response }; typedef struct mip_filter_adaptive_filter_options_response mip_filter_adaptive_filter_options_response; -void insert_mip_filter_adaptive_filter_options_response(struct microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_response* self); -void extract_mip_filter_adaptive_filter_options_response(struct microstrain_serializer* serializer, mip_filter_adaptive_filter_options_response* self); +void insert_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_response* self); +void extract_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, mip_filter_adaptive_filter_options_response* self); mip_cmd_result mip_filter_write_adaptive_filter_options(struct mip_interface* device, uint8_t level, uint16_t time_limit); mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* device, uint8_t* level_out, uint16_t* time_limit_out); @@ -1976,8 +1975,8 @@ struct mip_filter_multi_antenna_offset_command }; typedef struct mip_filter_multi_antenna_offset_command mip_filter_multi_antenna_offset_command; -void insert_mip_filter_multi_antenna_offset_command(struct microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_command* self); -void extract_mip_filter_multi_antenna_offset_command(struct microstrain_serializer* serializer, mip_filter_multi_antenna_offset_command* self); +void insert_mip_filter_multi_antenna_offset_command(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_command* self); +void extract_mip_filter_multi_antenna_offset_command(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_command* self); struct mip_filter_multi_antenna_offset_response { @@ -1986,8 +1985,8 @@ struct mip_filter_multi_antenna_offset_response }; typedef struct mip_filter_multi_antenna_offset_response mip_filter_multi_antenna_offset_response; -void insert_mip_filter_multi_antenna_offset_response(struct microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_response* self); -void extract_mip_filter_multi_antenna_offset_response(struct microstrain_serializer* serializer, mip_filter_multi_antenna_offset_response* self); +void insert_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_response* self); +void extract_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_response* self); mip_cmd_result mip_filter_write_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, const float* antenna_offset); mip_cmd_result mip_filter_read_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, float* antenna_offset_out); @@ -2012,8 +2011,8 @@ struct mip_filter_rel_pos_configuration_command }; typedef struct mip_filter_rel_pos_configuration_command mip_filter_rel_pos_configuration_command; -void insert_mip_filter_rel_pos_configuration_command(struct microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_command* self); -void extract_mip_filter_rel_pos_configuration_command(struct microstrain_serializer* serializer, mip_filter_rel_pos_configuration_command* self); +void insert_mip_filter_rel_pos_configuration_command(microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_command* self); +void extract_mip_filter_rel_pos_configuration_command(microstrain_serializer* serializer, mip_filter_rel_pos_configuration_command* self); struct mip_filter_rel_pos_configuration_response { @@ -2023,8 +2022,8 @@ struct mip_filter_rel_pos_configuration_response }; typedef struct mip_filter_rel_pos_configuration_response mip_filter_rel_pos_configuration_response; -void insert_mip_filter_rel_pos_configuration_response(struct microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_response* self); -void extract_mip_filter_rel_pos_configuration_response(struct microstrain_serializer* serializer, mip_filter_rel_pos_configuration_response* self); +void insert_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_response* self); +void extract_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, mip_filter_rel_pos_configuration_response* self); mip_cmd_result mip_filter_write_rel_pos_configuration(struct mip_interface* device, uint8_t source, mip_filter_reference_frame reference_frame_selector, const double* reference_coordinates); mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* device, uint8_t* source_out, mip_filter_reference_frame* reference_frame_selector_out, double* reference_coordinates_out); @@ -2058,11 +2057,11 @@ struct mip_filter_ref_point_lever_arm_command }; typedef struct mip_filter_ref_point_lever_arm_command mip_filter_ref_point_lever_arm_command; -void insert_mip_filter_ref_point_lever_arm_command(struct microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command* self); -void extract_mip_filter_ref_point_lever_arm_command(struct microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command* self); +void insert_mip_filter_ref_point_lever_arm_command(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command* self); +void extract_mip_filter_ref_point_lever_arm_command(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command* self); -void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self); -void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(struct microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self); +void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self); +void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self); struct mip_filter_ref_point_lever_arm_response { @@ -2071,8 +2070,8 @@ struct mip_filter_ref_point_lever_arm_response }; typedef struct mip_filter_ref_point_lever_arm_response mip_filter_ref_point_lever_arm_response; -void insert_mip_filter_ref_point_lever_arm_response(struct microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_response* self); -void extract_mip_filter_ref_point_lever_arm_response(struct microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_response* self); +void insert_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_response* self); +void extract_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_response* self); mip_cmd_result mip_filter_write_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel, const float* lever_arm_offset); mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector* ref_point_sel_out, float* lever_arm_offset_out); @@ -2099,8 +2098,8 @@ struct mip_filter_speed_measurement_command }; typedef struct mip_filter_speed_measurement_command mip_filter_speed_measurement_command; -void insert_mip_filter_speed_measurement_command(struct microstrain_serializer* serializer, const mip_filter_speed_measurement_command* self); -void extract_mip_filter_speed_measurement_command(struct microstrain_serializer* serializer, mip_filter_speed_measurement_command* self); +void insert_mip_filter_speed_measurement_command(microstrain_serializer* serializer, const mip_filter_speed_measurement_command* self); +void extract_mip_filter_speed_measurement_command(microstrain_serializer* serializer, mip_filter_speed_measurement_command* self); mip_cmd_result mip_filter_speed_measurement(struct mip_interface* device, uint8_t source, float time_of_week, float speed, float speed_uncertainty); @@ -2126,8 +2125,8 @@ struct mip_filter_speed_lever_arm_command }; typedef struct mip_filter_speed_lever_arm_command mip_filter_speed_lever_arm_command; -void insert_mip_filter_speed_lever_arm_command(struct microstrain_serializer* serializer, const mip_filter_speed_lever_arm_command* self); -void extract_mip_filter_speed_lever_arm_command(struct microstrain_serializer* serializer, mip_filter_speed_lever_arm_command* self); +void insert_mip_filter_speed_lever_arm_command(microstrain_serializer* serializer, const mip_filter_speed_lever_arm_command* self); +void extract_mip_filter_speed_lever_arm_command(microstrain_serializer* serializer, mip_filter_speed_lever_arm_command* self); struct mip_filter_speed_lever_arm_response { @@ -2136,8 +2135,8 @@ struct mip_filter_speed_lever_arm_response }; typedef struct mip_filter_speed_lever_arm_response mip_filter_speed_lever_arm_response; -void insert_mip_filter_speed_lever_arm_response(struct microstrain_serializer* serializer, const mip_filter_speed_lever_arm_response* self); -void extract_mip_filter_speed_lever_arm_response(struct microstrain_serializer* serializer, mip_filter_speed_lever_arm_response* self); +void insert_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, const mip_filter_speed_lever_arm_response* self); +void extract_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, mip_filter_speed_lever_arm_response* self); mip_cmd_result mip_filter_write_speed_lever_arm(struct mip_interface* device, uint8_t source, const float* lever_arm_offset); mip_cmd_result mip_filter_read_speed_lever_arm(struct mip_interface* device, uint8_t source, float* lever_arm_offset_out); @@ -2166,8 +2165,8 @@ struct mip_filter_wheeled_vehicle_constraint_control_command }; typedef struct mip_filter_wheeled_vehicle_constraint_control_command mip_filter_wheeled_vehicle_constraint_control_command; -void insert_mip_filter_wheeled_vehicle_constraint_control_command(struct microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_command* self); -void extract_mip_filter_wheeled_vehicle_constraint_control_command(struct microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_command* self); +void insert_mip_filter_wheeled_vehicle_constraint_control_command(microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_command* self); +void extract_mip_filter_wheeled_vehicle_constraint_control_command(microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_command* self); struct mip_filter_wheeled_vehicle_constraint_control_response { @@ -2175,8 +2174,8 @@ struct mip_filter_wheeled_vehicle_constraint_control_response }; typedef struct mip_filter_wheeled_vehicle_constraint_control_response mip_filter_wheeled_vehicle_constraint_control_response; -void insert_mip_filter_wheeled_vehicle_constraint_control_response(struct microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self); -void extract_mip_filter_wheeled_vehicle_constraint_control_response(struct microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self); +void insert_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self); +void extract_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self); mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t enable); mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t* enable_out); @@ -2203,8 +2202,8 @@ struct mip_filter_vertical_gyro_constraint_control_command }; typedef struct mip_filter_vertical_gyro_constraint_control_command mip_filter_vertical_gyro_constraint_control_command; -void insert_mip_filter_vertical_gyro_constraint_control_command(struct microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_command* self); -void extract_mip_filter_vertical_gyro_constraint_control_command(struct microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_command* self); +void insert_mip_filter_vertical_gyro_constraint_control_command(microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_command* self); +void extract_mip_filter_vertical_gyro_constraint_control_command(microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_command* self); struct mip_filter_vertical_gyro_constraint_control_response { @@ -2212,8 +2211,8 @@ struct mip_filter_vertical_gyro_constraint_control_response }; typedef struct mip_filter_vertical_gyro_constraint_control_response mip_filter_vertical_gyro_constraint_control_response; -void insert_mip_filter_vertical_gyro_constraint_control_response(struct microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self); -void extract_mip_filter_vertical_gyro_constraint_control_response(struct microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self); +void insert_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self); +void extract_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self); mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t enable); mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t* enable_out); @@ -2239,8 +2238,8 @@ struct mip_filter_gnss_antenna_cal_control_command }; typedef struct mip_filter_gnss_antenna_cal_control_command mip_filter_gnss_antenna_cal_control_command; -void insert_mip_filter_gnss_antenna_cal_control_command(struct microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_command* self); -void extract_mip_filter_gnss_antenna_cal_control_command(struct microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_command* self); +void insert_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_command* self); +void extract_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_command* self); struct mip_filter_gnss_antenna_cal_control_response { @@ -2249,8 +2248,8 @@ struct mip_filter_gnss_antenna_cal_control_response }; typedef struct mip_filter_gnss_antenna_cal_control_response mip_filter_gnss_antenna_cal_control_response; -void insert_mip_filter_gnss_antenna_cal_control_response(struct microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self); -void extract_mip_filter_gnss_antenna_cal_control_response(struct microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self); +void insert_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self); +void extract_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self); mip_cmd_result mip_filter_write_gnss_antenna_cal_control(struct mip_interface* device, uint8_t enable, float max_offset); mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* device, uint8_t* enable_out, float* max_offset_out); @@ -2275,8 +2274,8 @@ struct mip_filter_set_initial_heading_command }; typedef struct mip_filter_set_initial_heading_command mip_filter_set_initial_heading_command; -void insert_mip_filter_set_initial_heading_command(struct microstrain_serializer* serializer, const mip_filter_set_initial_heading_command* self); -void extract_mip_filter_set_initial_heading_command(struct microstrain_serializer* serializer, mip_filter_set_initial_heading_command* self); +void insert_mip_filter_set_initial_heading_command(microstrain_serializer* serializer, const mip_filter_set_initial_heading_command* self); +void extract_mip_filter_set_initial_heading_command(microstrain_serializer* serializer, mip_filter_set_initial_heading_command* self); mip_cmd_result mip_filter_set_initial_heading(struct mip_interface* device, float heading); diff --git a/src/mip/definitions/commands_gnss.h b/src/mip/definitions/commands_gnss.h index 401382890..9fd75a0ee 100644 --- a/src/mip/definitions/commands_gnss.h +++ b/src/mip/definitions/commands_gnss.h @@ -9,13 +9,16 @@ #include #ifdef __cplusplus +namespace microstrain { +struct microstrain_serializer; +} namespace mip { namespace C { extern "C" { - +#else +struct microstrain_serializer; #endif // __cplusplus struct mip_interface; -struct microstrain_serializer; struct mip_field; //////////////////////////////////////////////////////////////////////////////// @@ -74,8 +77,8 @@ struct mip_gnss_receiver_info_command_info }; typedef struct mip_gnss_receiver_info_command_info mip_gnss_receiver_info_command_info; -void insert_mip_gnss_receiver_info_command_info(struct microstrain_serializer* serializer, const mip_gnss_receiver_info_command_info* self); -void extract_mip_gnss_receiver_info_command_info(struct microstrain_serializer* serializer, mip_gnss_receiver_info_command_info* self); +void insert_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, const mip_gnss_receiver_info_command_info* self); +void extract_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, mip_gnss_receiver_info_command_info* self); struct mip_gnss_receiver_info_response { @@ -84,8 +87,8 @@ struct mip_gnss_receiver_info_response }; typedef struct mip_gnss_receiver_info_response mip_gnss_receiver_info_response; -void insert_mip_gnss_receiver_info_response(struct microstrain_serializer* serializer, const mip_gnss_receiver_info_response* self); -void extract_mip_gnss_receiver_info_response(struct microstrain_serializer* serializer, mip_gnss_receiver_info_response* self); +void insert_mip_gnss_receiver_info_response(microstrain_serializer* serializer, const mip_gnss_receiver_info_response* self); +void extract_mip_gnss_receiver_info_response(microstrain_serializer* serializer, mip_gnss_receiver_info_response* self); mip_cmd_result mip_gnss_receiver_info(struct mip_interface* device, uint8_t* num_receivers_out, uint8_t num_receivers_out_max, mip_gnss_receiver_info_command_info* receiver_info_out); @@ -109,8 +112,8 @@ struct mip_gnss_signal_configuration_command }; typedef struct mip_gnss_signal_configuration_command mip_gnss_signal_configuration_command; -void insert_mip_gnss_signal_configuration_command(struct microstrain_serializer* serializer, const mip_gnss_signal_configuration_command* self); -void extract_mip_gnss_signal_configuration_command(struct microstrain_serializer* serializer, mip_gnss_signal_configuration_command* self); +void insert_mip_gnss_signal_configuration_command(microstrain_serializer* serializer, const mip_gnss_signal_configuration_command* self); +void extract_mip_gnss_signal_configuration_command(microstrain_serializer* serializer, mip_gnss_signal_configuration_command* self); struct mip_gnss_signal_configuration_response { @@ -122,8 +125,8 @@ struct mip_gnss_signal_configuration_response }; typedef struct mip_gnss_signal_configuration_response mip_gnss_signal_configuration_response; -void insert_mip_gnss_signal_configuration_response(struct microstrain_serializer* serializer, const mip_gnss_signal_configuration_response* self); -void extract_mip_gnss_signal_configuration_response(struct microstrain_serializer* serializer, mip_gnss_signal_configuration_response* self); +void insert_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, const mip_gnss_signal_configuration_response* self); +void extract_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, mip_gnss_signal_configuration_response* self); mip_cmd_result mip_gnss_write_signal_configuration(struct mip_interface* device, uint8_t gps_enable, uint8_t glonass_enable, uint8_t galileo_enable, uint8_t beidou_enable, const uint8_t* reserved); mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, uint8_t* gps_enable_out, uint8_t* glonass_enable_out, uint8_t* galileo_enable_out, uint8_t* beidou_enable_out, uint8_t* reserved_out); @@ -148,8 +151,8 @@ struct mip_gnss_rtk_dongle_configuration_command }; typedef struct mip_gnss_rtk_dongle_configuration_command mip_gnss_rtk_dongle_configuration_command; -void insert_mip_gnss_rtk_dongle_configuration_command(struct microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_command* self); -void extract_mip_gnss_rtk_dongle_configuration_command(struct microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_command* self); +void insert_mip_gnss_rtk_dongle_configuration_command(microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_command* self); +void extract_mip_gnss_rtk_dongle_configuration_command(microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_command* self); struct mip_gnss_rtk_dongle_configuration_response { @@ -158,8 +161,8 @@ struct mip_gnss_rtk_dongle_configuration_response }; typedef struct mip_gnss_rtk_dongle_configuration_response mip_gnss_rtk_dongle_configuration_response; -void insert_mip_gnss_rtk_dongle_configuration_response(struct microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self); -void extract_mip_gnss_rtk_dongle_configuration_response(struct microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self); +void insert_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self); +void extract_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self); mip_cmd_result mip_gnss_write_rtk_dongle_configuration(struct mip_interface* device, uint8_t enable, const uint8_t* reserved); mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* device, uint8_t* enable_out, uint8_t* reserved_out); diff --git a/src/mip/definitions/commands_rtk.c b/src/mip/definitions/commands_rtk.c index 335ecd7f3..99225678c 100644 --- a/src/mip/definitions/commands_rtk.c +++ b/src/mip/definitions/commands_rtk.c @@ -22,22 +22,22 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_media_selector(struct microstrain_serializer* serializer, const mip_media_selector self) +void insert_mip_media_selector(microstrain_serializer* serializer, const mip_media_selector self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_media_selector(struct microstrain_serializer* serializer, mip_media_selector* self) +void extract_mip_media_selector(microstrain_serializer* serializer, mip_media_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_led_action(struct microstrain_serializer* serializer, const mip_led_action self) +void insert_mip_led_action(microstrain_serializer* serializer, const mip_led_action self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_led_action(struct microstrain_serializer* serializer, mip_led_action* self) +void extract_mip_led_action(microstrain_serializer* serializer, mip_led_action* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -49,22 +49,22 @@ void extract_mip_led_action(struct microstrain_serializer* serializer, mip_led_a // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_rtk_get_status_flags_command_status_flags_legacy(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self) +void insert_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self) { microstrain_insert_u32(serializer, (uint32_t) (self)); } -void extract_mip_rtk_get_status_flags_command_status_flags_legacy(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self) +void extract_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self) { uint32_t tmp = 0; microstrain_extract_u32(serializer, &tmp); *self = tmp; } -void insert_mip_rtk_get_status_flags_command_status_flags(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self) +void insert_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self) { microstrain_insert_u32(serializer, (uint32_t) (self)); } -void extract_mip_rtk_get_status_flags_command_status_flags(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self) +void extract_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self) { uint32_t tmp = 0; microstrain_extract_u32(serializer, &tmp); @@ -186,11 +186,11 @@ void extract_mip_rtk_connected_device_type_response(microstrain_serializer* seri } -void insert_mip_rtk_connected_device_type_command_type(struct microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self) +void insert_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_rtk_connected_device_type_command_type(struct microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self) +void extract_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -384,11 +384,11 @@ void extract_mip_rtk_service_status_response(microstrain_serializer* serializer, } -void insert_mip_rtk_service_status_command_service_flags(struct microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self) +void insert_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_rtk_service_status_command_service_flags(struct microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self) +void extract_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); diff --git a/src/mip/definitions/commands_rtk.h b/src/mip/definitions/commands_rtk.h index 41db0ab52..5c4b8e0e8 100644 --- a/src/mip/definitions/commands_rtk.h +++ b/src/mip/definitions/commands_rtk.h @@ -65,16 +65,16 @@ typedef uint8_t mip_media_selector; static const mip_media_selector MIP_MEDIA_SELECTOR_MEDIA_EXTERNALFLASH = 0; ///< static const mip_media_selector MIP_MEDIA_SELECTOR_MEDIA_SD = 1; ///< -void insert_mip_media_selector(struct microstrain_serializer* serializer, const mip_media_selector self); -void extract_mip_media_selector(struct microstrain_serializer* serializer, mip_media_selector* self); +void insert_mip_media_selector(microstrain_serializer* serializer, const mip_media_selector self); +void extract_mip_media_selector(microstrain_serializer* serializer, mip_media_selector* self); typedef uint8_t mip_led_action; static const mip_led_action MIP_LED_ACTION_LED_NONE = 0; ///< static const mip_led_action MIP_LED_ACTION_LED_FLASH = 1; ///< static const mip_led_action MIP_LED_ACTION_LED_PULSATE = 2; ///< -void insert_mip_led_action(struct microstrain_serializer* serializer, const mip_led_action self); -void extract_mip_led_action(struct microstrain_serializer* serializer, mip_led_action* self); +void insert_mip_led_action(microstrain_serializer* serializer, const mip_led_action self); +void extract_mip_led_action(microstrain_serializer* serializer, mip_led_action* self); //////////////////////////////////////////////////////////////////////////////// @@ -117,11 +117,11 @@ static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FL static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_VERSION = 0xC0000000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_ALL = 0xFFFFFFFF; -void insert_mip_rtk_get_status_flags_command_status_flags_legacy(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self); -void extract_mip_rtk_get_status_flags_command_status_flags_legacy(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self); +void insert_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self); +void extract_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self); -void insert_mip_rtk_get_status_flags_command_status_flags(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self); -void extract_mip_rtk_get_status_flags_command_status_flags(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self); +void insert_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self); +void extract_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self); struct mip_rtk_get_status_flags_response { @@ -129,8 +129,8 @@ struct mip_rtk_get_status_flags_response }; typedef struct mip_rtk_get_status_flags_response mip_rtk_get_status_flags_response; -void insert_mip_rtk_get_status_flags_response(struct microstrain_serializer* serializer, const mip_rtk_get_status_flags_response* self); -void extract_mip_rtk_get_status_flags_response(struct microstrain_serializer* serializer, mip_rtk_get_status_flags_response* self); +void insert_mip_rtk_get_status_flags_response(microstrain_serializer* serializer, const mip_rtk_get_status_flags_response* self); +void extract_mip_rtk_get_status_flags_response(microstrain_serializer* serializer, mip_rtk_get_status_flags_response* self); mip_cmd_result mip_rtk_get_status_flags(struct mip_interface* device, mip_rtk_get_status_flags_command_status_flags* flags_out); @@ -147,8 +147,8 @@ struct mip_rtk_get_imei_response }; typedef struct mip_rtk_get_imei_response mip_rtk_get_imei_response; -void insert_mip_rtk_get_imei_response(struct microstrain_serializer* serializer, const mip_rtk_get_imei_response* self); -void extract_mip_rtk_get_imei_response(struct microstrain_serializer* serializer, mip_rtk_get_imei_response* self); +void insert_mip_rtk_get_imei_response(microstrain_serializer* serializer, const mip_rtk_get_imei_response* self); +void extract_mip_rtk_get_imei_response(microstrain_serializer* serializer, mip_rtk_get_imei_response* self); mip_cmd_result mip_rtk_get_imei(struct mip_interface* device, char* imei_out); @@ -165,8 +165,8 @@ struct mip_rtk_get_imsi_response }; typedef struct mip_rtk_get_imsi_response mip_rtk_get_imsi_response; -void insert_mip_rtk_get_imsi_response(struct microstrain_serializer* serializer, const mip_rtk_get_imsi_response* self); -void extract_mip_rtk_get_imsi_response(struct microstrain_serializer* serializer, mip_rtk_get_imsi_response* self); +void insert_mip_rtk_get_imsi_response(microstrain_serializer* serializer, const mip_rtk_get_imsi_response* self); +void extract_mip_rtk_get_imsi_response(microstrain_serializer* serializer, mip_rtk_get_imsi_response* self); mip_cmd_result mip_rtk_get_imsi(struct mip_interface* device, char* imsi_out); @@ -183,8 +183,8 @@ struct mip_rtk_get_iccid_response }; typedef struct mip_rtk_get_iccid_response mip_rtk_get_iccid_response; -void insert_mip_rtk_get_iccid_response(struct microstrain_serializer* serializer, const mip_rtk_get_iccid_response* self); -void extract_mip_rtk_get_iccid_response(struct microstrain_serializer* serializer, mip_rtk_get_iccid_response* self); +void insert_mip_rtk_get_iccid_response(microstrain_serializer* serializer, const mip_rtk_get_iccid_response* self); +void extract_mip_rtk_get_iccid_response(microstrain_serializer* serializer, mip_rtk_get_iccid_response* self); mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out); @@ -206,11 +206,11 @@ struct mip_rtk_connected_device_type_command }; typedef struct mip_rtk_connected_device_type_command mip_rtk_connected_device_type_command; -void insert_mip_rtk_connected_device_type_command(struct microstrain_serializer* serializer, const mip_rtk_connected_device_type_command* self); -void extract_mip_rtk_connected_device_type_command(struct microstrain_serializer* serializer, mip_rtk_connected_device_type_command* self); +void insert_mip_rtk_connected_device_type_command(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command* self); +void extract_mip_rtk_connected_device_type_command(microstrain_serializer* serializer, mip_rtk_connected_device_type_command* self); -void insert_mip_rtk_connected_device_type_command_type(struct microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self); -void extract_mip_rtk_connected_device_type_command_type(struct microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self); +void insert_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self); +void extract_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self); struct mip_rtk_connected_device_type_response { @@ -218,8 +218,8 @@ struct mip_rtk_connected_device_type_response }; typedef struct mip_rtk_connected_device_type_response mip_rtk_connected_device_type_response; -void insert_mip_rtk_connected_device_type_response(struct microstrain_serializer* serializer, const mip_rtk_connected_device_type_response* self); -void extract_mip_rtk_connected_device_type_response(struct microstrain_serializer* serializer, mip_rtk_connected_device_type_response* self); +void insert_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, const mip_rtk_connected_device_type_response* self); +void extract_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, mip_rtk_connected_device_type_response* self); mip_cmd_result mip_rtk_write_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type dev_type); mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type* dev_type_out); @@ -240,8 +240,8 @@ struct mip_rtk_get_act_code_response }; typedef struct mip_rtk_get_act_code_response mip_rtk_get_act_code_response; -void insert_mip_rtk_get_act_code_response(struct microstrain_serializer* serializer, const mip_rtk_get_act_code_response* self); -void extract_mip_rtk_get_act_code_response(struct microstrain_serializer* serializer, mip_rtk_get_act_code_response* self); +void insert_mip_rtk_get_act_code_response(microstrain_serializer* serializer, const mip_rtk_get_act_code_response* self); +void extract_mip_rtk_get_act_code_response(microstrain_serializer* serializer, mip_rtk_get_act_code_response* self); mip_cmd_result mip_rtk_get_act_code(struct mip_interface* device, char* activation_code_out); @@ -258,8 +258,8 @@ struct mip_rtk_get_modem_firmware_version_response }; typedef struct mip_rtk_get_modem_firmware_version_response mip_rtk_get_modem_firmware_version_response; -void insert_mip_rtk_get_modem_firmware_version_response(struct microstrain_serializer* serializer, const mip_rtk_get_modem_firmware_version_response* self); -void extract_mip_rtk_get_modem_firmware_version_response(struct microstrain_serializer* serializer, mip_rtk_get_modem_firmware_version_response* self); +void insert_mip_rtk_get_modem_firmware_version_response(microstrain_serializer* serializer, const mip_rtk_get_modem_firmware_version_response* self); +void extract_mip_rtk_get_modem_firmware_version_response(microstrain_serializer* serializer, mip_rtk_get_modem_firmware_version_response* self); mip_cmd_result mip_rtk_get_modem_firmware_version(struct mip_interface* device, char* modem_firmware_version_out); @@ -279,8 +279,8 @@ struct mip_rtk_get_rssi_response }; typedef struct mip_rtk_get_rssi_response mip_rtk_get_rssi_response; -void insert_mip_rtk_get_rssi_response(struct microstrain_serializer* serializer, const mip_rtk_get_rssi_response* self); -void extract_mip_rtk_get_rssi_response(struct microstrain_serializer* serializer, mip_rtk_get_rssi_response* self); +void insert_mip_rtk_get_rssi_response(microstrain_serializer* serializer, const mip_rtk_get_rssi_response* self); +void extract_mip_rtk_get_rssi_response(microstrain_serializer* serializer, mip_rtk_get_rssi_response* self); mip_cmd_result mip_rtk_get_rssi(struct mip_interface* device, bool* valid_out, int32_t* rssi_out, int32_t* signal_quality_out); @@ -306,11 +306,11 @@ struct mip_rtk_service_status_command }; typedef struct mip_rtk_service_status_command mip_rtk_service_status_command; -void insert_mip_rtk_service_status_command(struct microstrain_serializer* serializer, const mip_rtk_service_status_command* self); -void extract_mip_rtk_service_status_command(struct microstrain_serializer* serializer, mip_rtk_service_status_command* self); +void insert_mip_rtk_service_status_command(microstrain_serializer* serializer, const mip_rtk_service_status_command* self); +void extract_mip_rtk_service_status_command(microstrain_serializer* serializer, mip_rtk_service_status_command* self); -void insert_mip_rtk_service_status_command_service_flags(struct microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self); -void extract_mip_rtk_service_status_command_service_flags(struct microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self); +void insert_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self); +void extract_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self); struct mip_rtk_service_status_response { @@ -321,8 +321,8 @@ struct mip_rtk_service_status_response }; typedef struct mip_rtk_service_status_response mip_rtk_service_status_response; -void insert_mip_rtk_service_status_response(struct microstrain_serializer* serializer, const mip_rtk_service_status_response* self); -void extract_mip_rtk_service_status_response(struct microstrain_serializer* serializer, mip_rtk_service_status_response* self); +void insert_mip_rtk_service_status_response(microstrain_serializer* serializer, const mip_rtk_service_status_response* self); +void extract_mip_rtk_service_status_response(microstrain_serializer* serializer, mip_rtk_service_status_response* self); mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t reserved1, uint32_t reserved2, mip_rtk_service_status_command_service_flags* flags_out, uint32_t* received_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out); @@ -341,8 +341,8 @@ struct mip_rtk_prod_erase_storage_command }; typedef struct mip_rtk_prod_erase_storage_command mip_rtk_prod_erase_storage_command; -void insert_mip_rtk_prod_erase_storage_command(struct microstrain_serializer* serializer, const mip_rtk_prod_erase_storage_command* self); -void extract_mip_rtk_prod_erase_storage_command(struct microstrain_serializer* serializer, mip_rtk_prod_erase_storage_command* self); +void insert_mip_rtk_prod_erase_storage_command(microstrain_serializer* serializer, const mip_rtk_prod_erase_storage_command* self); +void extract_mip_rtk_prod_erase_storage_command(microstrain_serializer* serializer, mip_rtk_prod_erase_storage_command* self); mip_cmd_result mip_rtk_prod_erase_storage(struct mip_interface* device, mip_media_selector media); @@ -363,8 +363,8 @@ struct mip_rtk_led_control_command }; typedef struct mip_rtk_led_control_command mip_rtk_led_control_command; -void insert_mip_rtk_led_control_command(struct microstrain_serializer* serializer, const mip_rtk_led_control_command* self); -void extract_mip_rtk_led_control_command(struct microstrain_serializer* serializer, mip_rtk_led_control_command* self); +void insert_mip_rtk_led_control_command(microstrain_serializer* serializer, const mip_rtk_led_control_command* self); +void extract_mip_rtk_led_control_command(microstrain_serializer* serializer, mip_rtk_led_control_command* self); mip_cmd_result mip_rtk_led_control(struct mip_interface* device, const uint8_t* primary_color, const uint8_t* alt_color, mip_led_action act, uint32_t period); diff --git a/src/mip/definitions/commands_system.h b/src/mip/definitions/commands_system.h index 34bec626a..0442a361e 100644 --- a/src/mip/definitions/commands_system.h +++ b/src/mip/definitions/commands_system.h @@ -77,8 +77,8 @@ struct mip_system_comm_mode_command }; typedef struct mip_system_comm_mode_command mip_system_comm_mode_command; -void insert_mip_system_comm_mode_command(struct microstrain_serializer* serializer, const mip_system_comm_mode_command* self); -void extract_mip_system_comm_mode_command(struct microstrain_serializer* serializer, mip_system_comm_mode_command* self); +void insert_mip_system_comm_mode_command(microstrain_serializer* serializer, const mip_system_comm_mode_command* self); +void extract_mip_system_comm_mode_command(microstrain_serializer* serializer, mip_system_comm_mode_command* self); struct mip_system_comm_mode_response { @@ -86,8 +86,8 @@ struct mip_system_comm_mode_response }; typedef struct mip_system_comm_mode_response mip_system_comm_mode_response; -void insert_mip_system_comm_mode_response(struct microstrain_serializer* serializer, const mip_system_comm_mode_response* self); -void extract_mip_system_comm_mode_response(struct microstrain_serializer* serializer, mip_system_comm_mode_response* self); +void insert_mip_system_comm_mode_response(microstrain_serializer* serializer, const mip_system_comm_mode_response* self); +void extract_mip_system_comm_mode_response(microstrain_serializer* serializer, mip_system_comm_mode_response* self); mip_cmd_result mip_system_write_comm_mode(struct mip_interface* device, uint8_t mode); mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* mode_out); diff --git a/src/mip/definitions/common.h b/src/mip/definitions/common.h index dc803a9e5..559ce2d9b 100644 --- a/src/mip/definitions/common.h +++ b/src/mip/definitions/common.h @@ -1,9 +1,10 @@ #pragma once +#include "microstrain/common/serialization.h" + #include #include #include -#include "microstrain/common/serialization.h" #ifdef __cplusplus diff --git a/src/mip/definitions/data_filter.c b/src/mip/definitions/data_filter.c index 2329587dc..9d7334c69 100644 --- a/src/mip/definitions/data_filter.c +++ b/src/mip/definitions/data_filter.c @@ -22,66 +22,66 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_filter_mode(struct microstrain_serializer* serializer, const mip_filter_mode self) +void insert_mip_filter_mode(microstrain_serializer* serializer, const mip_filter_mode self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_mode(struct microstrain_serializer* serializer, mip_filter_mode* self) +void extract_mip_filter_mode(microstrain_serializer* serializer, mip_filter_mode* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_filter_dynamics_mode(struct microstrain_serializer* serializer, const mip_filter_dynamics_mode self) +void insert_mip_filter_dynamics_mode(microstrain_serializer* serializer, const mip_filter_dynamics_mode self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_dynamics_mode(struct microstrain_serializer* serializer, mip_filter_dynamics_mode* self) +void extract_mip_filter_dynamics_mode(microstrain_serializer* serializer, mip_filter_dynamics_mode* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_filter_status_flags(struct microstrain_serializer* serializer, const mip_filter_status_flags self) +void insert_mip_filter_status_flags(microstrain_serializer* serializer, const mip_filter_status_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_status_flags(struct microstrain_serializer* serializer, mip_filter_status_flags* self) +void extract_mip_filter_status_flags(microstrain_serializer* serializer, mip_filter_status_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_filter_aiding_measurement_type(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self) +void insert_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_aiding_measurement_type(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self) +void extract_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_measurement_indicator(struct microstrain_serializer* serializer, const mip_filter_measurement_indicator self) +void insert_mip_filter_measurement_indicator(microstrain_serializer* serializer, const mip_filter_measurement_indicator self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_measurement_indicator(struct microstrain_serializer* serializer, mip_filter_measurement_indicator* self) +void extract_mip_filter_measurement_indicator(microstrain_serializer* serializer, mip_filter_measurement_indicator* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_aid_status_flags(struct microstrain_serializer* serializer, const mip_gnss_aid_status_flags self) +void insert_mip_gnss_aid_status_flags(microstrain_serializer* serializer, const mip_gnss_aid_status_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_aid_status_flags(struct microstrain_serializer* serializer, mip_gnss_aid_status_flags* self) +void extract_mip_gnss_aid_status_flags(microstrain_serializer* serializer, mip_gnss_aid_status_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -683,11 +683,11 @@ bool extract_mip_filter_heading_update_state_data_from_field(const mip_field* fi return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_heading_update_state_data_heading_source(struct microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self) +void insert_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_heading_update_state_data_heading_source(struct microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self) +void extract_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1404,11 +1404,11 @@ bool extract_mip_filter_head_aid_status_data_from_field(const mip_field* field, return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_head_aid_status_data_heading_aid_type(struct microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self) +void insert_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_head_aid_status_data_heading_aid_type(struct microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self) +void extract_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1665,22 +1665,22 @@ bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const mip_field return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self) +void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self) +void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self) +void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self) +void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/mip/definitions/data_filter.h b/src/mip/definitions/data_filter.h index fc251001f..556574764 100644 --- a/src/mip/definitions/data_filter.h +++ b/src/mip/definitions/data_filter.h @@ -112,8 +112,8 @@ static const mip_filter_mode MIP_FILTER_MODE_VERT_GYRO = 2; ///< static const mip_filter_mode MIP_FILTER_MODE_AHRS = 3; ///< static const mip_filter_mode MIP_FILTER_MODE_FULL_NAV = 4; ///< -void insert_mip_filter_mode(struct microstrain_serializer* serializer, const mip_filter_mode self); -void extract_mip_filter_mode(struct microstrain_serializer* serializer, mip_filter_mode* self); +void insert_mip_filter_mode(microstrain_serializer* serializer, const mip_filter_mode self); +void extract_mip_filter_mode(microstrain_serializer* serializer, mip_filter_mode* self); typedef uint16_t mip_filter_dynamics_mode; static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GX5_PORTABLE = 1; ///< @@ -121,8 +121,8 @@ static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GX5_AUTOMOTIVE = static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GX5_AIRBORNE = 3; ///< static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GQ7_DEFAULT = 1; ///< -void insert_mip_filter_dynamics_mode(struct microstrain_serializer* serializer, const mip_filter_dynamics_mode self); -void extract_mip_filter_dynamics_mode(struct microstrain_serializer* serializer, mip_filter_dynamics_mode* self); +void insert_mip_filter_dynamics_mode(microstrain_serializer* serializer, const mip_filter_dynamics_mode self); +void extract_mip_filter_dynamics_mode(microstrain_serializer* serializer, mip_filter_dynamics_mode* self); typedef uint16_t mip_filter_status_flags; static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_NONE = 0x0000; @@ -156,8 +156,8 @@ static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_TIME_SYNC_WARNI static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_SOLUTION_ERROR = 0xF000; ///< Filter computation warning flags. If any bits 12-15 are set, and all filter outputs will be invalid. static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_ALL = 0xFFFF; -void insert_mip_filter_status_flags(struct microstrain_serializer* serializer, const mip_filter_status_flags self); -void extract_mip_filter_status_flags(struct microstrain_serializer* serializer, mip_filter_status_flags* self); +void insert_mip_filter_status_flags(microstrain_serializer* serializer, const mip_filter_status_flags self); +void extract_mip_filter_status_flags(microstrain_serializer* serializer, mip_filter_status_flags* self); typedef uint8_t mip_filter_aiding_measurement_type; static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1; ///< @@ -173,8 +173,8 @@ static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TY static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_VEHICLE_FRAME = 42; ///< static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING_TRUE = 49; ///< -void insert_mip_filter_aiding_measurement_type(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self); -void extract_mip_filter_aiding_measurement_type(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self); +void insert_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self); +void extract_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self); typedef uint8_t mip_filter_measurement_indicator; static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_NONE = 0x00; @@ -186,8 +186,8 @@ static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_C static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_MAX_NUM_MEAS_EXCEEDED = 0x20; ///< static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_ALL = 0x3F; -void insert_mip_filter_measurement_indicator(struct microstrain_serializer* serializer, const mip_filter_measurement_indicator self); -void extract_mip_filter_measurement_indicator(struct microstrain_serializer* serializer, mip_filter_measurement_indicator* self); +void insert_mip_filter_measurement_indicator(microstrain_serializer* serializer, const mip_filter_measurement_indicator self); +void extract_mip_filter_measurement_indicator(microstrain_serializer* serializer, mip_filter_measurement_indicator* self); typedef uint16_t mip_gnss_aid_status_flags; static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_NONE = 0x0000; @@ -209,8 +209,8 @@ static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_NO_FIX static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_CONFIG_ERROR = 0x8000; ///< If 1, there is likely an issue with the antenna offset for this GNSS module static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_ALL = 0xFFFF; -void insert_mip_gnss_aid_status_flags(struct microstrain_serializer* serializer, const mip_gnss_aid_status_flags self); -void extract_mip_gnss_aid_status_flags(struct microstrain_serializer* serializer, mip_gnss_aid_status_flags* self); +void insert_mip_gnss_aid_status_flags(microstrain_serializer* serializer, const mip_gnss_aid_status_flags self); +void extract_mip_gnss_aid_status_flags(microstrain_serializer* serializer, mip_gnss_aid_status_flags* self); //////////////////////////////////////////////////////////////////////////////// @@ -232,8 +232,8 @@ struct mip_filter_position_llh_data }; typedef struct mip_filter_position_llh_data mip_filter_position_llh_data; -void insert_mip_filter_position_llh_data(struct microstrain_serializer* serializer, const mip_filter_position_llh_data* self); -void extract_mip_filter_position_llh_data(struct microstrain_serializer* serializer, mip_filter_position_llh_data* self); +void insert_mip_filter_position_llh_data(microstrain_serializer* serializer, const mip_filter_position_llh_data* self); +void extract_mip_filter_position_llh_data(microstrain_serializer* serializer, mip_filter_position_llh_data* self); bool extract_mip_filter_position_llh_data_from_field(const struct mip_field* field, void* ptr); @@ -254,8 +254,8 @@ struct mip_filter_velocity_ned_data }; typedef struct mip_filter_velocity_ned_data mip_filter_velocity_ned_data; -void insert_mip_filter_velocity_ned_data(struct microstrain_serializer* serializer, const mip_filter_velocity_ned_data* self); -void extract_mip_filter_velocity_ned_data(struct microstrain_serializer* serializer, mip_filter_velocity_ned_data* self); +void insert_mip_filter_velocity_ned_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_data* self); +void extract_mip_filter_velocity_ned_data(microstrain_serializer* serializer, mip_filter_velocity_ned_data* self); bool extract_mip_filter_velocity_ned_data_from_field(const struct mip_field* field, void* ptr); @@ -282,8 +282,8 @@ struct mip_filter_attitude_quaternion_data }; typedef struct mip_filter_attitude_quaternion_data mip_filter_attitude_quaternion_data; -void insert_mip_filter_attitude_quaternion_data(struct microstrain_serializer* serializer, const mip_filter_attitude_quaternion_data* self); -void extract_mip_filter_attitude_quaternion_data(struct microstrain_serializer* serializer, mip_filter_attitude_quaternion_data* self); +void insert_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, const mip_filter_attitude_quaternion_data* self); +void extract_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, mip_filter_attitude_quaternion_data* self); bool extract_mip_filter_attitude_quaternion_data_from_field(const struct mip_field* field, void* ptr); @@ -312,8 +312,8 @@ struct mip_filter_attitude_dcm_data }; typedef struct mip_filter_attitude_dcm_data mip_filter_attitude_dcm_data; -void insert_mip_filter_attitude_dcm_data(struct microstrain_serializer* serializer, const mip_filter_attitude_dcm_data* self); -void extract_mip_filter_attitude_dcm_data(struct microstrain_serializer* serializer, mip_filter_attitude_dcm_data* self); +void insert_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, const mip_filter_attitude_dcm_data* self); +void extract_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, mip_filter_attitude_dcm_data* self); bool extract_mip_filter_attitude_dcm_data_from_field(const struct mip_field* field, void* ptr); @@ -335,8 +335,8 @@ struct mip_filter_euler_angles_data }; typedef struct mip_filter_euler_angles_data mip_filter_euler_angles_data; -void insert_mip_filter_euler_angles_data(struct microstrain_serializer* serializer, const mip_filter_euler_angles_data* self); -void extract_mip_filter_euler_angles_data(struct microstrain_serializer* serializer, mip_filter_euler_angles_data* self); +void insert_mip_filter_euler_angles_data(microstrain_serializer* serializer, const mip_filter_euler_angles_data* self); +void extract_mip_filter_euler_angles_data(microstrain_serializer* serializer, mip_filter_euler_angles_data* self); bool extract_mip_filter_euler_angles_data_from_field(const struct mip_field* field, void* ptr); @@ -355,8 +355,8 @@ struct mip_filter_gyro_bias_data }; typedef struct mip_filter_gyro_bias_data mip_filter_gyro_bias_data; -void insert_mip_filter_gyro_bias_data(struct microstrain_serializer* serializer, const mip_filter_gyro_bias_data* self); -void extract_mip_filter_gyro_bias_data(struct microstrain_serializer* serializer, mip_filter_gyro_bias_data* self); +void insert_mip_filter_gyro_bias_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_data* self); +void extract_mip_filter_gyro_bias_data(microstrain_serializer* serializer, mip_filter_gyro_bias_data* self); bool extract_mip_filter_gyro_bias_data_from_field(const struct mip_field* field, void* ptr); @@ -375,8 +375,8 @@ struct mip_filter_accel_bias_data }; typedef struct mip_filter_accel_bias_data mip_filter_accel_bias_data; -void insert_mip_filter_accel_bias_data(struct microstrain_serializer* serializer, const mip_filter_accel_bias_data* self); -void extract_mip_filter_accel_bias_data(struct microstrain_serializer* serializer, mip_filter_accel_bias_data* self); +void insert_mip_filter_accel_bias_data(microstrain_serializer* serializer, const mip_filter_accel_bias_data* self); +void extract_mip_filter_accel_bias_data(microstrain_serializer* serializer, mip_filter_accel_bias_data* self); bool extract_mip_filter_accel_bias_data_from_field(const struct mip_field* field, void* ptr); @@ -397,8 +397,8 @@ struct mip_filter_position_llh_uncertainty_data }; typedef struct mip_filter_position_llh_uncertainty_data mip_filter_position_llh_uncertainty_data; -void insert_mip_filter_position_llh_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self); -void extract_mip_filter_position_llh_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_position_llh_uncertainty_data* self); +void insert_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self); +void extract_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, mip_filter_position_llh_uncertainty_data* self); bool extract_mip_filter_position_llh_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -419,8 +419,8 @@ struct mip_filter_velocity_ned_uncertainty_data }; typedef struct mip_filter_velocity_ned_uncertainty_data mip_filter_velocity_ned_uncertainty_data; -void insert_mip_filter_velocity_ned_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self); -void extract_mip_filter_velocity_ned_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self); +void insert_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self); +void extract_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self); bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -442,8 +442,8 @@ struct mip_filter_euler_angles_uncertainty_data }; typedef struct mip_filter_euler_angles_uncertainty_data mip_filter_euler_angles_uncertainty_data; -void insert_mip_filter_euler_angles_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self); -void extract_mip_filter_euler_angles_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self); +void insert_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self); +void extract_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self); bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -462,8 +462,8 @@ struct mip_filter_gyro_bias_uncertainty_data }; typedef struct mip_filter_gyro_bias_uncertainty_data mip_filter_gyro_bias_uncertainty_data; -void insert_mip_filter_gyro_bias_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self); -void extract_mip_filter_gyro_bias_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self); +void insert_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self); +void extract_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self); bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -482,8 +482,8 @@ struct mip_filter_accel_bias_uncertainty_data }; typedef struct mip_filter_accel_bias_uncertainty_data mip_filter_accel_bias_uncertainty_data; -void insert_mip_filter_accel_bias_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self); -void extract_mip_filter_accel_bias_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self); +void insert_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self); +void extract_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self); bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -509,8 +509,8 @@ struct mip_filter_timestamp_data }; typedef struct mip_filter_timestamp_data mip_filter_timestamp_data; -void insert_mip_filter_timestamp_data(struct microstrain_serializer* serializer, const mip_filter_timestamp_data* self); -void extract_mip_filter_timestamp_data(struct microstrain_serializer* serializer, mip_filter_timestamp_data* self); +void insert_mip_filter_timestamp_data(microstrain_serializer* serializer, const mip_filter_timestamp_data* self); +void extract_mip_filter_timestamp_data(microstrain_serializer* serializer, mip_filter_timestamp_data* self); bool extract_mip_filter_timestamp_data_from_field(const struct mip_field* field, void* ptr); @@ -530,8 +530,8 @@ struct mip_filter_status_data }; typedef struct mip_filter_status_data mip_filter_status_data; -void insert_mip_filter_status_data(struct microstrain_serializer* serializer, const mip_filter_status_data* self); -void extract_mip_filter_status_data(struct microstrain_serializer* serializer, mip_filter_status_data* self); +void insert_mip_filter_status_data(microstrain_serializer* serializer, const mip_filter_status_data* self); +void extract_mip_filter_status_data(microstrain_serializer* serializer, mip_filter_status_data* self); bool extract_mip_filter_status_data_from_field(const struct mip_field* field, void* ptr); @@ -551,8 +551,8 @@ struct mip_filter_linear_accel_data }; typedef struct mip_filter_linear_accel_data mip_filter_linear_accel_data; -void insert_mip_filter_linear_accel_data(struct microstrain_serializer* serializer, const mip_filter_linear_accel_data* self); -void extract_mip_filter_linear_accel_data(struct microstrain_serializer* serializer, mip_filter_linear_accel_data* self); +void insert_mip_filter_linear_accel_data(microstrain_serializer* serializer, const mip_filter_linear_accel_data* self); +void extract_mip_filter_linear_accel_data(microstrain_serializer* serializer, mip_filter_linear_accel_data* self); bool extract_mip_filter_linear_accel_data_from_field(const struct mip_field* field, void* ptr); @@ -571,8 +571,8 @@ struct mip_filter_gravity_vector_data }; typedef struct mip_filter_gravity_vector_data mip_filter_gravity_vector_data; -void insert_mip_filter_gravity_vector_data(struct microstrain_serializer* serializer, const mip_filter_gravity_vector_data* self); -void extract_mip_filter_gravity_vector_data(struct microstrain_serializer* serializer, mip_filter_gravity_vector_data* self); +void insert_mip_filter_gravity_vector_data(microstrain_serializer* serializer, const mip_filter_gravity_vector_data* self); +void extract_mip_filter_gravity_vector_data(microstrain_serializer* serializer, mip_filter_gravity_vector_data* self); bool extract_mip_filter_gravity_vector_data_from_field(const struct mip_field* field, void* ptr); @@ -591,8 +591,8 @@ struct mip_filter_comp_accel_data }; typedef struct mip_filter_comp_accel_data mip_filter_comp_accel_data; -void insert_mip_filter_comp_accel_data(struct microstrain_serializer* serializer, const mip_filter_comp_accel_data* self); -void extract_mip_filter_comp_accel_data(struct microstrain_serializer* serializer, mip_filter_comp_accel_data* self); +void insert_mip_filter_comp_accel_data(microstrain_serializer* serializer, const mip_filter_comp_accel_data* self); +void extract_mip_filter_comp_accel_data(microstrain_serializer* serializer, mip_filter_comp_accel_data* self); bool extract_mip_filter_comp_accel_data_from_field(const struct mip_field* field, void* ptr); @@ -611,8 +611,8 @@ struct mip_filter_comp_angular_rate_data }; typedef struct mip_filter_comp_angular_rate_data mip_filter_comp_angular_rate_data; -void insert_mip_filter_comp_angular_rate_data(struct microstrain_serializer* serializer, const mip_filter_comp_angular_rate_data* self); -void extract_mip_filter_comp_angular_rate_data(struct microstrain_serializer* serializer, mip_filter_comp_angular_rate_data* self); +void insert_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, const mip_filter_comp_angular_rate_data* self); +void extract_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, mip_filter_comp_angular_rate_data* self); bool extract_mip_filter_comp_angular_rate_data_from_field(const struct mip_field* field, void* ptr); @@ -631,8 +631,8 @@ struct mip_filter_quaternion_attitude_uncertainty_data }; typedef struct mip_filter_quaternion_attitude_uncertainty_data mip_filter_quaternion_attitude_uncertainty_data; -void insert_mip_filter_quaternion_attitude_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self); -void extract_mip_filter_quaternion_attitude_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self); +void insert_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self); +void extract_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self); bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -651,8 +651,8 @@ struct mip_filter_wgs84_gravity_mag_data }; typedef struct mip_filter_wgs84_gravity_mag_data mip_filter_wgs84_gravity_mag_data; -void insert_mip_filter_wgs84_gravity_mag_data(struct microstrain_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self); -void extract_mip_filter_wgs84_gravity_mag_data(struct microstrain_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self); +void insert_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self); +void extract_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self); bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const struct mip_field* field, void* ptr); @@ -683,12 +683,12 @@ struct mip_filter_heading_update_state_data }; typedef struct mip_filter_heading_update_state_data mip_filter_heading_update_state_data; -void insert_mip_filter_heading_update_state_data(struct microstrain_serializer* serializer, const mip_filter_heading_update_state_data* self); -void extract_mip_filter_heading_update_state_data(struct microstrain_serializer* serializer, mip_filter_heading_update_state_data* self); +void insert_mip_filter_heading_update_state_data(microstrain_serializer* serializer, const mip_filter_heading_update_state_data* self); +void extract_mip_filter_heading_update_state_data(microstrain_serializer* serializer, mip_filter_heading_update_state_data* self); bool extract_mip_filter_heading_update_state_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_filter_heading_update_state_data_heading_source(struct microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self); -void extract_mip_filter_heading_update_state_data_heading_source(struct microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self); +void insert_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self); +void extract_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self); ///@} @@ -711,8 +711,8 @@ struct mip_filter_magnetic_model_data }; typedef struct mip_filter_magnetic_model_data mip_filter_magnetic_model_data; -void insert_mip_filter_magnetic_model_data(struct microstrain_serializer* serializer, const mip_filter_magnetic_model_data* self); -void extract_mip_filter_magnetic_model_data(struct microstrain_serializer* serializer, mip_filter_magnetic_model_data* self); +void insert_mip_filter_magnetic_model_data(microstrain_serializer* serializer, const mip_filter_magnetic_model_data* self); +void extract_mip_filter_magnetic_model_data(microstrain_serializer* serializer, mip_filter_magnetic_model_data* self); bool extract_mip_filter_magnetic_model_data_from_field(const struct mip_field* field, void* ptr); @@ -731,8 +731,8 @@ struct mip_filter_accel_scale_factor_data }; typedef struct mip_filter_accel_scale_factor_data mip_filter_accel_scale_factor_data; -void insert_mip_filter_accel_scale_factor_data(struct microstrain_serializer* serializer, const mip_filter_accel_scale_factor_data* self); -void extract_mip_filter_accel_scale_factor_data(struct microstrain_serializer* serializer, mip_filter_accel_scale_factor_data* self); +void insert_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_data* self); +void extract_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_data* self); bool extract_mip_filter_accel_scale_factor_data_from_field(const struct mip_field* field, void* ptr); @@ -751,8 +751,8 @@ struct mip_filter_accel_scale_factor_uncertainty_data }; typedef struct mip_filter_accel_scale_factor_uncertainty_data mip_filter_accel_scale_factor_uncertainty_data; -void insert_mip_filter_accel_scale_factor_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self); -void extract_mip_filter_accel_scale_factor_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self); +void insert_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self); +void extract_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self); bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -771,8 +771,8 @@ struct mip_filter_gyro_scale_factor_data }; typedef struct mip_filter_gyro_scale_factor_data mip_filter_gyro_scale_factor_data; -void insert_mip_filter_gyro_scale_factor_data(struct microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_data* self); -void extract_mip_filter_gyro_scale_factor_data(struct microstrain_serializer* serializer, mip_filter_gyro_scale_factor_data* self); +void insert_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_data* self); +void extract_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_data* self); bool extract_mip_filter_gyro_scale_factor_data_from_field(const struct mip_field* field, void* ptr); @@ -791,8 +791,8 @@ struct mip_filter_gyro_scale_factor_uncertainty_data }; typedef struct mip_filter_gyro_scale_factor_uncertainty_data mip_filter_gyro_scale_factor_uncertainty_data; -void insert_mip_filter_gyro_scale_factor_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self); -void extract_mip_filter_gyro_scale_factor_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self); +void insert_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self); +void extract_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self); bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -811,8 +811,8 @@ struct mip_filter_mag_bias_data }; typedef struct mip_filter_mag_bias_data mip_filter_mag_bias_data; -void insert_mip_filter_mag_bias_data(struct microstrain_serializer* serializer, const mip_filter_mag_bias_data* self); -void extract_mip_filter_mag_bias_data(struct microstrain_serializer* serializer, mip_filter_mag_bias_data* self); +void insert_mip_filter_mag_bias_data(microstrain_serializer* serializer, const mip_filter_mag_bias_data* self); +void extract_mip_filter_mag_bias_data(microstrain_serializer* serializer, mip_filter_mag_bias_data* self); bool extract_mip_filter_mag_bias_data_from_field(const struct mip_field* field, void* ptr); @@ -831,8 +831,8 @@ struct mip_filter_mag_bias_uncertainty_data }; typedef struct mip_filter_mag_bias_uncertainty_data mip_filter_mag_bias_uncertainty_data; -void insert_mip_filter_mag_bias_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self); -void extract_mip_filter_mag_bias_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self); +void insert_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self); +void extract_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self); bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -857,8 +857,8 @@ struct mip_filter_standard_atmosphere_data }; typedef struct mip_filter_standard_atmosphere_data mip_filter_standard_atmosphere_data; -void insert_mip_filter_standard_atmosphere_data(struct microstrain_serializer* serializer, const mip_filter_standard_atmosphere_data* self); -void extract_mip_filter_standard_atmosphere_data(struct microstrain_serializer* serializer, mip_filter_standard_atmosphere_data* self); +void insert_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, const mip_filter_standard_atmosphere_data* self); +void extract_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, mip_filter_standard_atmosphere_data* self); bool extract_mip_filter_standard_atmosphere_data_from_field(const struct mip_field* field, void* ptr); @@ -881,8 +881,8 @@ struct mip_filter_pressure_altitude_data }; typedef struct mip_filter_pressure_altitude_data mip_filter_pressure_altitude_data; -void insert_mip_filter_pressure_altitude_data(struct microstrain_serializer* serializer, const mip_filter_pressure_altitude_data* self); -void extract_mip_filter_pressure_altitude_data(struct microstrain_serializer* serializer, mip_filter_pressure_altitude_data* self); +void insert_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, const mip_filter_pressure_altitude_data* self); +void extract_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, mip_filter_pressure_altitude_data* self); bool extract_mip_filter_pressure_altitude_data_from_field(const struct mip_field* field, void* ptr); @@ -900,8 +900,8 @@ struct mip_filter_density_altitude_data }; typedef struct mip_filter_density_altitude_data mip_filter_density_altitude_data; -void insert_mip_filter_density_altitude_data(struct microstrain_serializer* serializer, const mip_filter_density_altitude_data* self); -void extract_mip_filter_density_altitude_data(struct microstrain_serializer* serializer, mip_filter_density_altitude_data* self); +void insert_mip_filter_density_altitude_data(microstrain_serializer* serializer, const mip_filter_density_altitude_data* self); +void extract_mip_filter_density_altitude_data(microstrain_serializer* serializer, mip_filter_density_altitude_data* self); bool extract_mip_filter_density_altitude_data_from_field(const struct mip_field* field, void* ptr); @@ -922,8 +922,8 @@ struct mip_filter_antenna_offset_correction_data }; typedef struct mip_filter_antenna_offset_correction_data mip_filter_antenna_offset_correction_data; -void insert_mip_filter_antenna_offset_correction_data(struct microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_data* self); -void extract_mip_filter_antenna_offset_correction_data(struct microstrain_serializer* serializer, mip_filter_antenna_offset_correction_data* self); +void insert_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_data* self); +void extract_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_data* self); bool extract_mip_filter_antenna_offset_correction_data_from_field(const struct mip_field* field, void* ptr); @@ -942,8 +942,8 @@ struct mip_filter_antenna_offset_correction_uncertainty_data }; typedef struct mip_filter_antenna_offset_correction_uncertainty_data mip_filter_antenna_offset_correction_uncertainty_data; -void insert_mip_filter_antenna_offset_correction_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self); -void extract_mip_filter_antenna_offset_correction_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self); +void insert_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self); +void extract_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self); bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -965,8 +965,8 @@ struct mip_filter_multi_antenna_offset_correction_data }; typedef struct mip_filter_multi_antenna_offset_correction_data mip_filter_multi_antenna_offset_correction_data; -void insert_mip_filter_multi_antenna_offset_correction_data(struct microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_data* self); -void extract_mip_filter_multi_antenna_offset_correction_data(struct microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_data* self); +void insert_mip_filter_multi_antenna_offset_correction_data(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_data* self); +void extract_mip_filter_multi_antenna_offset_correction_data(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_data* self); bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const struct mip_field* field, void* ptr); @@ -986,8 +986,8 @@ struct mip_filter_multi_antenna_offset_correction_uncertainty_data }; typedef struct mip_filter_multi_antenna_offset_correction_uncertainty_data mip_filter_multi_antenna_offset_correction_uncertainty_data; -void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_uncertainty_data* self); -void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_uncertainty_data* self); +void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_uncertainty_data* self); +void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_uncertainty_data* self); bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1008,8 +1008,8 @@ struct mip_filter_magnetometer_offset_data }; typedef struct mip_filter_magnetometer_offset_data mip_filter_magnetometer_offset_data; -void insert_mip_filter_magnetometer_offset_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_offset_data* self); -void extract_mip_filter_magnetometer_offset_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_offset_data* self); +void insert_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_data* self); +void extract_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_data* self); bool extract_mip_filter_magnetometer_offset_data_from_field(const struct mip_field* field, void* ptr); @@ -1030,8 +1030,8 @@ struct mip_filter_magnetometer_matrix_data }; typedef struct mip_filter_magnetometer_matrix_data mip_filter_magnetometer_matrix_data; -void insert_mip_filter_magnetometer_matrix_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_data* self); -void extract_mip_filter_magnetometer_matrix_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_matrix_data* self); +void insert_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_data* self); +void extract_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_data* self); bool extract_mip_filter_magnetometer_matrix_data_from_field(const struct mip_field* field, void* ptr); @@ -1050,8 +1050,8 @@ struct mip_filter_magnetometer_offset_uncertainty_data }; typedef struct mip_filter_magnetometer_offset_uncertainty_data mip_filter_magnetometer_offset_uncertainty_data; -void insert_mip_filter_magnetometer_offset_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self); -void extract_mip_filter_magnetometer_offset_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self); +void insert_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self); +void extract_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self); bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1070,8 +1070,8 @@ struct mip_filter_magnetometer_matrix_uncertainty_data }; typedef struct mip_filter_magnetometer_matrix_uncertainty_data mip_filter_magnetometer_matrix_uncertainty_data; -void insert_mip_filter_magnetometer_matrix_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self); -void extract_mip_filter_magnetometer_matrix_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self); +void insert_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self); +void extract_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self); bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1089,8 +1089,8 @@ struct mip_filter_magnetometer_covariance_matrix_data }; typedef struct mip_filter_magnetometer_covariance_matrix_data mip_filter_magnetometer_covariance_matrix_data; -void insert_mip_filter_magnetometer_covariance_matrix_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self); -void extract_mip_filter_magnetometer_covariance_matrix_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self); +void insert_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self); +void extract_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self); bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const struct mip_field* field, void* ptr); @@ -1109,8 +1109,8 @@ struct mip_filter_magnetometer_residual_vector_data }; typedef struct mip_filter_magnetometer_residual_vector_data mip_filter_magnetometer_residual_vector_data; -void insert_mip_filter_magnetometer_residual_vector_data(struct microstrain_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self); -void extract_mip_filter_magnetometer_residual_vector_data(struct microstrain_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self); +void insert_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self); +void extract_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self); bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const struct mip_field* field, void* ptr); @@ -1131,8 +1131,8 @@ struct mip_filter_clock_correction_data }; typedef struct mip_filter_clock_correction_data mip_filter_clock_correction_data; -void insert_mip_filter_clock_correction_data(struct microstrain_serializer* serializer, const mip_filter_clock_correction_data* self); -void extract_mip_filter_clock_correction_data(struct microstrain_serializer* serializer, mip_filter_clock_correction_data* self); +void insert_mip_filter_clock_correction_data(microstrain_serializer* serializer, const mip_filter_clock_correction_data* self); +void extract_mip_filter_clock_correction_data(microstrain_serializer* serializer, mip_filter_clock_correction_data* self); bool extract_mip_filter_clock_correction_data_from_field(const struct mip_field* field, void* ptr); @@ -1153,8 +1153,8 @@ struct mip_filter_clock_correction_uncertainty_data }; typedef struct mip_filter_clock_correction_uncertainty_data mip_filter_clock_correction_uncertainty_data; -void insert_mip_filter_clock_correction_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self); -void extract_mip_filter_clock_correction_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self); +void insert_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self); +void extract_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self); bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1175,8 +1175,8 @@ struct mip_filter_gnss_pos_aid_status_data }; typedef struct mip_filter_gnss_pos_aid_status_data mip_filter_gnss_pos_aid_status_data; -void insert_mip_filter_gnss_pos_aid_status_data(struct microstrain_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self); -void extract_mip_filter_gnss_pos_aid_status_data(struct microstrain_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self); +void insert_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self); +void extract_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self); bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const struct mip_field* field, void* ptr); @@ -1196,8 +1196,8 @@ struct mip_filter_gnss_att_aid_status_data }; typedef struct mip_filter_gnss_att_aid_status_data mip_filter_gnss_att_aid_status_data; -void insert_mip_filter_gnss_att_aid_status_data(struct microstrain_serializer* serializer, const mip_filter_gnss_att_aid_status_data* self); -void extract_mip_filter_gnss_att_aid_status_data(struct microstrain_serializer* serializer, mip_filter_gnss_att_aid_status_data* self); +void insert_mip_filter_gnss_att_aid_status_data(microstrain_serializer* serializer, const mip_filter_gnss_att_aid_status_data* self); +void extract_mip_filter_gnss_att_aid_status_data(microstrain_serializer* serializer, mip_filter_gnss_att_aid_status_data* self); bool extract_mip_filter_gnss_att_aid_status_data_from_field(const struct mip_field* field, void* ptr); @@ -1221,12 +1221,12 @@ struct mip_filter_head_aid_status_data }; typedef struct mip_filter_head_aid_status_data mip_filter_head_aid_status_data; -void insert_mip_filter_head_aid_status_data(struct microstrain_serializer* serializer, const mip_filter_head_aid_status_data* self); -void extract_mip_filter_head_aid_status_data(struct microstrain_serializer* serializer, mip_filter_head_aid_status_data* self); +void insert_mip_filter_head_aid_status_data(microstrain_serializer* serializer, const mip_filter_head_aid_status_data* self); +void extract_mip_filter_head_aid_status_data(microstrain_serializer* serializer, mip_filter_head_aid_status_data* self); bool extract_mip_filter_head_aid_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_filter_head_aid_status_data_heading_aid_type(struct microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self); -void extract_mip_filter_head_aid_status_data_heading_aid_type(struct microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self); +void insert_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self); +void extract_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self); ///@} @@ -1244,8 +1244,8 @@ struct mip_filter_rel_pos_ned_data }; typedef struct mip_filter_rel_pos_ned_data mip_filter_rel_pos_ned_data; -void insert_mip_filter_rel_pos_ned_data(struct microstrain_serializer* serializer, const mip_filter_rel_pos_ned_data* self); -void extract_mip_filter_rel_pos_ned_data(struct microstrain_serializer* serializer, mip_filter_rel_pos_ned_data* self); +void insert_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, const mip_filter_rel_pos_ned_data* self); +void extract_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, mip_filter_rel_pos_ned_data* self); bool extract_mip_filter_rel_pos_ned_data_from_field(const struct mip_field* field, void* ptr); @@ -1264,8 +1264,8 @@ struct mip_filter_ecef_pos_data }; typedef struct mip_filter_ecef_pos_data mip_filter_ecef_pos_data; -void insert_mip_filter_ecef_pos_data(struct microstrain_serializer* serializer, const mip_filter_ecef_pos_data* self); -void extract_mip_filter_ecef_pos_data(struct microstrain_serializer* serializer, mip_filter_ecef_pos_data* self); +void insert_mip_filter_ecef_pos_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_data* self); +void extract_mip_filter_ecef_pos_data(microstrain_serializer* serializer, mip_filter_ecef_pos_data* self); bool extract_mip_filter_ecef_pos_data_from_field(const struct mip_field* field, void* ptr); @@ -1284,8 +1284,8 @@ struct mip_filter_ecef_vel_data }; typedef struct mip_filter_ecef_vel_data mip_filter_ecef_vel_data; -void insert_mip_filter_ecef_vel_data(struct microstrain_serializer* serializer, const mip_filter_ecef_vel_data* self); -void extract_mip_filter_ecef_vel_data(struct microstrain_serializer* serializer, mip_filter_ecef_vel_data* self); +void insert_mip_filter_ecef_vel_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_data* self); +void extract_mip_filter_ecef_vel_data(microstrain_serializer* serializer, mip_filter_ecef_vel_data* self); bool extract_mip_filter_ecef_vel_data_from_field(const struct mip_field* field, void* ptr); @@ -1304,8 +1304,8 @@ struct mip_filter_ecef_pos_uncertainty_data }; typedef struct mip_filter_ecef_pos_uncertainty_data mip_filter_ecef_pos_uncertainty_data; -void insert_mip_filter_ecef_pos_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self); -void extract_mip_filter_ecef_pos_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self); +void insert_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self); +void extract_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self); bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1324,8 +1324,8 @@ struct mip_filter_ecef_vel_uncertainty_data }; typedef struct mip_filter_ecef_vel_uncertainty_data mip_filter_ecef_vel_uncertainty_data; -void insert_mip_filter_ecef_vel_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self); -void extract_mip_filter_ecef_vel_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self); +void insert_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self); +void extract_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self); bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1346,8 +1346,8 @@ struct mip_filter_aiding_measurement_summary_data }; typedef struct mip_filter_aiding_measurement_summary_data mip_filter_aiding_measurement_summary_data; -void insert_mip_filter_aiding_measurement_summary_data(struct microstrain_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self); -void extract_mip_filter_aiding_measurement_summary_data(struct microstrain_serializer* serializer, mip_filter_aiding_measurement_summary_data* self); +void insert_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self); +void extract_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, mip_filter_aiding_measurement_summary_data* self); bool extract_mip_filter_aiding_measurement_summary_data_from_field(const struct mip_field* field, void* ptr); @@ -1366,8 +1366,8 @@ struct mip_filter_odometer_scale_factor_error_data }; typedef struct mip_filter_odometer_scale_factor_error_data mip_filter_odometer_scale_factor_error_data; -void insert_mip_filter_odometer_scale_factor_error_data(struct microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self); -void extract_mip_filter_odometer_scale_factor_error_data(struct microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self); +void insert_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self); +void extract_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self); bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const struct mip_field* field, void* ptr); @@ -1386,8 +1386,8 @@ struct mip_filter_odometer_scale_factor_error_uncertainty_data }; typedef struct mip_filter_odometer_scale_factor_error_uncertainty_data mip_filter_odometer_scale_factor_error_uncertainty_data; -void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self); -void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self); +void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self); +void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self); bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field(const struct mip_field* field, void* ptr); @@ -1422,15 +1422,15 @@ struct mip_filter_gnss_dual_antenna_status_data }; typedef struct mip_filter_gnss_dual_antenna_status_data mip_filter_gnss_dual_antenna_status_data; -void insert_mip_filter_gnss_dual_antenna_status_data(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self); -void extract_mip_filter_gnss_dual_antenna_status_data(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self); +void insert_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self); +void extract_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self); bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self); -void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self); +void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self); +void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self); -void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self); -void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(struct microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self); +void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self); +void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self); ///@} @@ -1451,8 +1451,8 @@ struct mip_filter_aiding_frame_config_error_data }; typedef struct mip_filter_aiding_frame_config_error_data mip_filter_aiding_frame_config_error_data; -void insert_mip_filter_aiding_frame_config_error_data(struct microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self); -void extract_mip_filter_aiding_frame_config_error_data(struct microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_data* self); +void insert_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self); +void extract_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_data* self); bool extract_mip_filter_aiding_frame_config_error_data_from_field(const struct mip_field* field, void* ptr); @@ -1474,8 +1474,8 @@ struct mip_filter_aiding_frame_config_error_uncertainty_data }; typedef struct mip_filter_aiding_frame_config_error_uncertainty_data mip_filter_aiding_frame_config_error_uncertainty_data; -void insert_mip_filter_aiding_frame_config_error_uncertainty_data(struct microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_uncertainty_data* self); -void extract_mip_filter_aiding_frame_config_error_uncertainty_data(struct microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self); +void insert_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_uncertainty_data* self); +void extract_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self); bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const struct mip_field* field, void* ptr); diff --git a/src/mip/definitions/data_gnss.c b/src/mip/definitions/data_gnss.c index e30aa5123..90dfadc6c 100644 --- a/src/mip/definitions/data_gnss.c +++ b/src/mip/definitions/data_gnss.c @@ -22,33 +22,33 @@ struct mip_field; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert_mip_gnss_constellation_id(struct microstrain_serializer* serializer, const mip_gnss_constellation_id self) +void insert_mip_gnss_constellation_id(microstrain_serializer* serializer, const mip_gnss_constellation_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_constellation_id(struct microstrain_serializer* serializer, mip_gnss_constellation_id* self) +void extract_mip_gnss_constellation_id(microstrain_serializer* serializer, mip_gnss_constellation_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_signal_id(struct microstrain_serializer* serializer, const mip_gnss_signal_id self) +void insert_mip_gnss_signal_id(microstrain_serializer* serializer, const mip_gnss_signal_id self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_signal_id(struct microstrain_serializer* serializer, mip_gnss_signal_id* self) +void extract_mip_gnss_signal_id(microstrain_serializer* serializer, mip_gnss_signal_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_sbas_system(struct microstrain_serializer* serializer, const mip_sbas_system self) +void insert_mip_sbas_system(microstrain_serializer* serializer, const mip_sbas_system self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_sbas_system(struct microstrain_serializer* serializer, mip_sbas_system* self) +void extract_mip_sbas_system(microstrain_serializer* serializer, mip_sbas_system* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -104,11 +104,11 @@ bool extract_mip_gnss_pos_llh_data_from_field(const mip_field* field, void* ptr) return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_pos_llh_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self) +void insert_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_pos_llh_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self) +void extract_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -145,11 +145,11 @@ bool extract_mip_gnss_pos_ecef_data_from_field(const mip_field* field, void* ptr return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_pos_ecef_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self) +void insert_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_pos_ecef_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self) +void extract_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -202,11 +202,11 @@ bool extract_mip_gnss_vel_ned_data_from_field(const mip_field* field, void* ptr) return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_vel_ned_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self) +void insert_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_vel_ned_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self) +void extract_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -243,11 +243,11 @@ bool extract_mip_gnss_vel_ecef_data_from_field(const mip_field* field, void* ptr return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_vel_ecef_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self) +void insert_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_vel_ecef_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self) +void extract_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -302,11 +302,11 @@ bool extract_mip_gnss_dop_data_from_field(const mip_field* field, void* ptr) return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_dop_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self) +void insert_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_dop_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self) +void extract_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -361,11 +361,11 @@ bool extract_mip_gnss_utc_time_data_from_field(const mip_field* field, void* ptr return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_utc_time_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self) +void insert_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_utc_time_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self) +void extract_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -400,11 +400,11 @@ bool extract_mip_gnss_gps_time_data_from_field(const mip_field* field, void* ptr return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_time_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self) +void insert_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_gps_time_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self) +void extract_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -443,11 +443,11 @@ bool extract_mip_gnss_clock_info_data_from_field(const mip_field* field, void* p return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_clock_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self) +void insert_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_clock_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self) +void extract_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -486,33 +486,33 @@ bool extract_mip_gnss_fix_info_data_from_field(const mip_field* field, void* ptr return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_fix_info_data_fix_type(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self) +void insert_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_fix_info_data_fix_type(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self) +void extract_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_fix_info_data_fix_flags(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self) +void insert_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_fix_info_data_fix_flags(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self) +void extract_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_fix_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self) +void insert_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_fix_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self) +void extract_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -563,22 +563,22 @@ bool extract_mip_gnss_sv_info_data_from_field(const mip_field* field, void* ptr) return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_sv_info_data_svflags(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self) +void insert_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_sv_info_data_svflags(struct microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self) +void extract_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_sv_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self) +void insert_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_sv_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self) +void extract_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -617,44 +617,44 @@ bool extract_mip_gnss_hw_status_data_from_field(const mip_field* field, void* pt return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_hw_status_data_receiver_state(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self) +void insert_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_hw_status_data_receiver_state(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self) +void extract_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_hw_status_data_antenna_state(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self) +void insert_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_hw_status_data_antenna_state(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self) +void extract_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_hw_status_data_antenna_power(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self) +void insert_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_hw_status_data_antenna_power(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self) +void extract_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_hw_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self) +void insert_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_hw_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self) +void extract_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -697,11 +697,11 @@ bool extract_mip_gnss_dgps_info_data_from_field(const mip_field* field, void* pt return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_dgps_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self) +void insert_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_dgps_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self) +void extract_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -744,11 +744,11 @@ bool extract_mip_gnss_dgps_channel_data_from_field(const mip_field* field, void* return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_dgps_channel_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self) +void insert_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_dgps_channel_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self) +void extract_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -791,11 +791,11 @@ bool extract_mip_gnss_clock_info_2_data_from_field(const mip_field* field, void* return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_clock_info_2_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self) +void insert_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_clock_info_2_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self) +void extract_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -826,11 +826,11 @@ bool extract_mip_gnss_gps_leap_seconds_data_from_field(const mip_field* field, v return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_leap_seconds_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self) +void insert_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_gps_leap_seconds_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self) +void extract_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -881,22 +881,22 @@ bool extract_mip_gnss_sbas_info_data_from_field(const mip_field* field, void* pt return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_sbas_info_data_sbas_status(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self) +void insert_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_sbas_info_data_sbas_status(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self) +void extract_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_sbas_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self) +void insert_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_sbas_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self) +void extract_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -959,11 +959,11 @@ bool extract_mip_gnss_sbas_correction_data_from_field(const mip_field* field, vo return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_sbas_correction_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self) +void insert_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_sbas_correction_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self) +void extract_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1008,44 +1008,44 @@ bool extract_mip_gnss_rf_error_detection_data_from_field(const mip_field* field, return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_rf_error_detection_data_rfband(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self) +void insert_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_rf_error_detection_data_rfband(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self) +void extract_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rf_error_detection_data_jamming_state(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self) +void insert_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_rf_error_detection_data_jamming_state(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self) +void extract_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rf_error_detection_data_spoofing_state(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self) +void insert_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_rf_error_detection_data_spoofing_state(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self) +void extract_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rf_error_detection_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self) +void insert_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_rf_error_detection_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self) +void extract_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1098,22 +1098,22 @@ bool extract_mip_gnss_base_station_info_data_from_field(const mip_field* field, return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_base_station_info_data_indicator_flags(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self) +void insert_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_base_station_info_data_indicator_flags(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self) +void extract_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_base_station_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self) +void insert_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_base_station_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self) +void extract_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1178,22 +1178,22 @@ bool extract_mip_gnss_rtk_corrections_status_data_from_field(const mip_field* fi return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_rtk_corrections_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self) +void insert_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_rtk_corrections_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self) +void extract_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_rtk_corrections_status_data_epoch_status(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self) +void insert_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_rtk_corrections_status_data_epoch_status(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self) +void extract_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1256,11 +1256,11 @@ bool extract_mip_gnss_satellite_status_data_from_field(const mip_field* field, v return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_satellite_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self) +void insert_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_satellite_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self) +void extract_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1359,22 +1359,22 @@ bool extract_mip_gnss_raw_data_from_field(const mip_field* field, void* ptr) return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_raw_data_gnss_signal_quality(struct microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self) +void insert_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self) { microstrain_insert_u8(serializer, (uint8_t) (self)); } -void extract_mip_gnss_raw_data_gnss_signal_quality(struct microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self) +void extract_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); *self = tmp; } -void insert_mip_gnss_raw_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self) +void insert_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_raw_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self) +void extract_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1533,11 +1533,11 @@ bool extract_mip_gnss_gps_ephemeris_data_from_field(const mip_field* field, void return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) +void insert_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_gps_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self) +void extract_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1696,11 +1696,11 @@ bool extract_mip_gnss_galileo_ephemeris_data_from_field(const mip_field* field, return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_galileo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) +void insert_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_galileo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self) +void extract_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1829,11 +1829,11 @@ bool extract_mip_gnss_glo_ephemeris_data_from_field(const mip_field* field, void return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_glo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self) +void insert_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_glo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self) +void extract_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1880,11 +1880,11 @@ bool extract_mip_gnss_gps_iono_corr_data_from_field(const mip_field* field, void return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self) +void insert_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_gps_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self) +void extract_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1929,11 +1929,11 @@ bool extract_mip_gnss_galileo_iono_corr_data_from_field(const mip_field* field, return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_galileo_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self) +void insert_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_gnss_galileo_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self) +void extract_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/mip/definitions/data_gnss.h b/src/mip/definitions/data_gnss.h index e955692df..4b2cc9cb0 100644 --- a/src/mip/definitions/data_gnss.h +++ b/src/mip/definitions/data_gnss.h @@ -82,8 +82,8 @@ static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_GALILEO = 3; // static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_BEIDOU = 4; ///< static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_SBAS = 5; ///< -void insert_mip_gnss_constellation_id(struct microstrain_serializer* serializer, const mip_gnss_constellation_id self); -void extract_mip_gnss_constellation_id(struct microstrain_serializer* serializer, mip_gnss_constellation_id* self); +void insert_mip_gnss_constellation_id(microstrain_serializer* serializer, const mip_gnss_constellation_id self); +void extract_mip_gnss_constellation_id(microstrain_serializer* serializer, mip_gnss_constellation_id* self); typedef uint8_t mip_gnss_signal_id; static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_UNKNOWN = 0; ///< @@ -152,8 +152,8 @@ static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2I = 166; ///< static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2Q = 167; ///< static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2IQ = 168; ///< -void insert_mip_gnss_signal_id(struct microstrain_serializer* serializer, const mip_gnss_signal_id self); -void extract_mip_gnss_signal_id(struct microstrain_serializer* serializer, mip_gnss_signal_id* self); +void insert_mip_gnss_signal_id(microstrain_serializer* serializer, const mip_gnss_signal_id self); +void extract_mip_gnss_signal_id(microstrain_serializer* serializer, mip_gnss_signal_id* self); typedef uint8_t mip_sbas_system; static const mip_sbas_system MIP_SBAS_SYSTEM_UNKNOWN = 0; ///< @@ -162,8 +162,8 @@ static const mip_sbas_system MIP_SBAS_SYSTEM_EGNOS = 2; ///< static const mip_sbas_system MIP_SBAS_SYSTEM_MSAS = 3; ///< static const mip_sbas_system MIP_SBAS_SYSTEM_GAGAN = 4; ///< -void insert_mip_sbas_system(struct microstrain_serializer* serializer, const mip_sbas_system self); -void extract_mip_sbas_system(struct microstrain_serializer* serializer, mip_sbas_system* self); +void insert_mip_sbas_system(microstrain_serializer* serializer, const mip_sbas_system self); +void extract_mip_sbas_system(microstrain_serializer* serializer, mip_sbas_system* self); enum { MIP_GNSS_DGPS_INFO_MAX_CHANNEL_NUMBER = 32 }; enum { MIP_GNSS_SV_INFO_MAX_SV_NUMBER = 32 }; @@ -200,12 +200,12 @@ struct mip_gnss_pos_llh_data }; typedef struct mip_gnss_pos_llh_data mip_gnss_pos_llh_data; -void insert_mip_gnss_pos_llh_data(struct microstrain_serializer* serializer, const mip_gnss_pos_llh_data* self); -void extract_mip_gnss_pos_llh_data(struct microstrain_serializer* serializer, mip_gnss_pos_llh_data* self); +void insert_mip_gnss_pos_llh_data(microstrain_serializer* serializer, const mip_gnss_pos_llh_data* self); +void extract_mip_gnss_pos_llh_data(microstrain_serializer* serializer, mip_gnss_pos_llh_data* self); bool extract_mip_gnss_pos_llh_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_pos_llh_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self); -void extract_mip_gnss_pos_llh_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self); +void insert_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self); +void extract_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self); ///@} @@ -231,12 +231,12 @@ struct mip_gnss_pos_ecef_data }; typedef struct mip_gnss_pos_ecef_data mip_gnss_pos_ecef_data; -void insert_mip_gnss_pos_ecef_data(struct microstrain_serializer* serializer, const mip_gnss_pos_ecef_data* self); -void extract_mip_gnss_pos_ecef_data(struct microstrain_serializer* serializer, mip_gnss_pos_ecef_data* self); +void insert_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data* self); +void extract_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, mip_gnss_pos_ecef_data* self); bool extract_mip_gnss_pos_ecef_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_pos_ecef_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self); -void extract_mip_gnss_pos_ecef_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self); +void insert_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self); +void extract_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self); ///@} @@ -270,12 +270,12 @@ struct mip_gnss_vel_ned_data }; typedef struct mip_gnss_vel_ned_data mip_gnss_vel_ned_data; -void insert_mip_gnss_vel_ned_data(struct microstrain_serializer* serializer, const mip_gnss_vel_ned_data* self); -void extract_mip_gnss_vel_ned_data(struct microstrain_serializer* serializer, mip_gnss_vel_ned_data* self); +void insert_mip_gnss_vel_ned_data(microstrain_serializer* serializer, const mip_gnss_vel_ned_data* self); +void extract_mip_gnss_vel_ned_data(microstrain_serializer* serializer, mip_gnss_vel_ned_data* self); bool extract_mip_gnss_vel_ned_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_vel_ned_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self); -void extract_mip_gnss_vel_ned_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self); +void insert_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self); +void extract_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self); ///@} @@ -301,12 +301,12 @@ struct mip_gnss_vel_ecef_data }; typedef struct mip_gnss_vel_ecef_data mip_gnss_vel_ecef_data; -void insert_mip_gnss_vel_ecef_data(struct microstrain_serializer* serializer, const mip_gnss_vel_ecef_data* self); -void extract_mip_gnss_vel_ecef_data(struct microstrain_serializer* serializer, mip_gnss_vel_ecef_data* self); +void insert_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data* self); +void extract_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, mip_gnss_vel_ecef_data* self); bool extract_mip_gnss_vel_ecef_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_vel_ecef_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self); -void extract_mip_gnss_vel_ecef_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self); +void insert_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self); +void extract_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self); ///@} @@ -342,12 +342,12 @@ struct mip_gnss_dop_data }; typedef struct mip_gnss_dop_data mip_gnss_dop_data; -void insert_mip_gnss_dop_data(struct microstrain_serializer* serializer, const mip_gnss_dop_data* self); -void extract_mip_gnss_dop_data(struct microstrain_serializer* serializer, mip_gnss_dop_data* self); +void insert_mip_gnss_dop_data(microstrain_serializer* serializer, const mip_gnss_dop_data* self); +void extract_mip_gnss_dop_data(microstrain_serializer* serializer, mip_gnss_dop_data* self); bool extract_mip_gnss_dop_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_dop_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self); -void extract_mip_gnss_dop_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self); +void insert_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self); +void extract_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self); ///@} @@ -378,12 +378,12 @@ struct mip_gnss_utc_time_data }; typedef struct mip_gnss_utc_time_data mip_gnss_utc_time_data; -void insert_mip_gnss_utc_time_data(struct microstrain_serializer* serializer, const mip_gnss_utc_time_data* self); -void extract_mip_gnss_utc_time_data(struct microstrain_serializer* serializer, mip_gnss_utc_time_data* self); +void insert_mip_gnss_utc_time_data(microstrain_serializer* serializer, const mip_gnss_utc_time_data* self); +void extract_mip_gnss_utc_time_data(microstrain_serializer* serializer, mip_gnss_utc_time_data* self); bool extract_mip_gnss_utc_time_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_utc_time_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self); -void extract_mip_gnss_utc_time_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self); +void insert_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self); +void extract_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self); ///@} @@ -409,12 +409,12 @@ struct mip_gnss_gps_time_data }; typedef struct mip_gnss_gps_time_data mip_gnss_gps_time_data; -void insert_mip_gnss_gps_time_data(struct microstrain_serializer* serializer, const mip_gnss_gps_time_data* self); -void extract_mip_gnss_gps_time_data(struct microstrain_serializer* serializer, mip_gnss_gps_time_data* self); +void insert_mip_gnss_gps_time_data(microstrain_serializer* serializer, const mip_gnss_gps_time_data* self); +void extract_mip_gnss_gps_time_data(microstrain_serializer* serializer, mip_gnss_gps_time_data* self); bool extract_mip_gnss_gps_time_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_gps_time_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self); -void extract_mip_gnss_gps_time_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self); +void insert_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self); +void extract_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self); ///@} @@ -442,12 +442,12 @@ struct mip_gnss_clock_info_data }; typedef struct mip_gnss_clock_info_data mip_gnss_clock_info_data; -void insert_mip_gnss_clock_info_data(struct microstrain_serializer* serializer, const mip_gnss_clock_info_data* self); -void extract_mip_gnss_clock_info_data(struct microstrain_serializer* serializer, mip_gnss_clock_info_data* self); +void insert_mip_gnss_clock_info_data(microstrain_serializer* serializer, const mip_gnss_clock_info_data* self); +void extract_mip_gnss_clock_info_data(microstrain_serializer* serializer, mip_gnss_clock_info_data* self); bool extract_mip_gnss_clock_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_clock_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self); -void extract_mip_gnss_clock_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self); +void insert_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self); +void extract_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self); ///@} @@ -491,18 +491,18 @@ struct mip_gnss_fix_info_data }; typedef struct mip_gnss_fix_info_data mip_gnss_fix_info_data; -void insert_mip_gnss_fix_info_data(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data* self); -void extract_mip_gnss_fix_info_data(struct microstrain_serializer* serializer, mip_gnss_fix_info_data* self); +void insert_mip_gnss_fix_info_data(microstrain_serializer* serializer, const mip_gnss_fix_info_data* self); +void extract_mip_gnss_fix_info_data(microstrain_serializer* serializer, mip_gnss_fix_info_data* self); bool extract_mip_gnss_fix_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_fix_info_data_fix_type(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self); -void extract_mip_gnss_fix_info_data_fix_type(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self); +void insert_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self); +void extract_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self); -void insert_mip_gnss_fix_info_data_fix_flags(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self); -void extract_mip_gnss_fix_info_data_fix_flags(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self); +void insert_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self); +void extract_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self); -void insert_mip_gnss_fix_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self); -void extract_mip_gnss_fix_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self); +void insert_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self); +void extract_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self); ///@} @@ -544,15 +544,15 @@ struct mip_gnss_sv_info_data }; typedef struct mip_gnss_sv_info_data mip_gnss_sv_info_data; -void insert_mip_gnss_sv_info_data(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data* self); -void extract_mip_gnss_sv_info_data(struct microstrain_serializer* serializer, mip_gnss_sv_info_data* self); +void insert_mip_gnss_sv_info_data(microstrain_serializer* serializer, const mip_gnss_sv_info_data* self); +void extract_mip_gnss_sv_info_data(microstrain_serializer* serializer, mip_gnss_sv_info_data* self); bool extract_mip_gnss_sv_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_sv_info_data_svflags(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self); -void extract_mip_gnss_sv_info_data_svflags(struct microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self); +void insert_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self); +void extract_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self); -void insert_mip_gnss_sv_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self); -void extract_mip_gnss_sv_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self); +void insert_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self); +void extract_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self); ///@} @@ -597,21 +597,21 @@ struct mip_gnss_hw_status_data }; typedef struct mip_gnss_hw_status_data mip_gnss_hw_status_data; -void insert_mip_gnss_hw_status_data(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data* self); -void extract_mip_gnss_hw_status_data(struct microstrain_serializer* serializer, mip_gnss_hw_status_data* self); +void insert_mip_gnss_hw_status_data(microstrain_serializer* serializer, const mip_gnss_hw_status_data* self); +void extract_mip_gnss_hw_status_data(microstrain_serializer* serializer, mip_gnss_hw_status_data* self); bool extract_mip_gnss_hw_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_hw_status_data_receiver_state(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self); -void extract_mip_gnss_hw_status_data_receiver_state(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self); +void insert_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self); +void extract_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self); -void insert_mip_gnss_hw_status_data_antenna_state(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self); -void extract_mip_gnss_hw_status_data_antenna_state(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self); +void insert_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self); +void extract_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self); -void insert_mip_gnss_hw_status_data_antenna_power(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self); -void extract_mip_gnss_hw_status_data_antenna_power(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self); +void insert_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self); +void extract_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self); -void insert_mip_gnss_hw_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self); -void extract_mip_gnss_hw_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self); +void insert_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self); +void extract_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self); ///@} @@ -653,12 +653,12 @@ struct mip_gnss_dgps_info_data }; typedef struct mip_gnss_dgps_info_data mip_gnss_dgps_info_data; -void insert_mip_gnss_dgps_info_data(struct microstrain_serializer* serializer, const mip_gnss_dgps_info_data* self); -void extract_mip_gnss_dgps_info_data(struct microstrain_serializer* serializer, mip_gnss_dgps_info_data* self); +void insert_mip_gnss_dgps_info_data(microstrain_serializer* serializer, const mip_gnss_dgps_info_data* self); +void extract_mip_gnss_dgps_info_data(microstrain_serializer* serializer, mip_gnss_dgps_info_data* self); bool extract_mip_gnss_dgps_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_dgps_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self); -void extract_mip_gnss_dgps_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self); +void insert_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self); +void extract_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self); ///@} @@ -690,12 +690,12 @@ struct mip_gnss_dgps_channel_data }; typedef struct mip_gnss_dgps_channel_data mip_gnss_dgps_channel_data; -void insert_mip_gnss_dgps_channel_data(struct microstrain_serializer* serializer, const mip_gnss_dgps_channel_data* self); -void extract_mip_gnss_dgps_channel_data(struct microstrain_serializer* serializer, mip_gnss_dgps_channel_data* self); +void insert_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data* self); +void extract_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, mip_gnss_dgps_channel_data* self); bool extract_mip_gnss_dgps_channel_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_dgps_channel_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self); -void extract_mip_gnss_dgps_channel_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self); +void insert_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self); +void extract_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self); ///@} @@ -727,12 +727,12 @@ struct mip_gnss_clock_info_2_data }; typedef struct mip_gnss_clock_info_2_data mip_gnss_clock_info_2_data; -void insert_mip_gnss_clock_info_2_data(struct microstrain_serializer* serializer, const mip_gnss_clock_info_2_data* self); -void extract_mip_gnss_clock_info_2_data(struct microstrain_serializer* serializer, mip_gnss_clock_info_2_data* self); +void insert_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data* self); +void extract_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, mip_gnss_clock_info_2_data* self); bool extract_mip_gnss_clock_info_2_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_clock_info_2_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self); -void extract_mip_gnss_clock_info_2_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self); +void insert_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self); +void extract_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self); ///@} @@ -755,12 +755,12 @@ struct mip_gnss_gps_leap_seconds_data }; typedef struct mip_gnss_gps_leap_seconds_data mip_gnss_gps_leap_seconds_data; -void insert_mip_gnss_gps_leap_seconds_data(struct microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self); -void extract_mip_gnss_gps_leap_seconds_data(struct microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data* self); +void insert_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self); +void extract_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data* self); bool extract_mip_gnss_gps_leap_seconds_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_gps_leap_seconds_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self); -void extract_mip_gnss_gps_leap_seconds_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self); +void insert_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self); +void extract_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self); ///@} @@ -802,15 +802,15 @@ struct mip_gnss_sbas_info_data }; typedef struct mip_gnss_sbas_info_data mip_gnss_sbas_info_data; -void insert_mip_gnss_sbas_info_data(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data* self); -void extract_mip_gnss_sbas_info_data(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data* self); +void insert_mip_gnss_sbas_info_data(microstrain_serializer* serializer, const mip_gnss_sbas_info_data* self); +void extract_mip_gnss_sbas_info_data(microstrain_serializer* serializer, mip_gnss_sbas_info_data* self); bool extract_mip_gnss_sbas_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_sbas_info_data_sbas_status(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self); -void extract_mip_gnss_sbas_info_data_sbas_status(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self); +void insert_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self); +void extract_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self); -void insert_mip_gnss_sbas_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self); -void extract_mip_gnss_sbas_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self); +void insert_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self); +void extract_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self); ///@} @@ -866,12 +866,12 @@ struct mip_gnss_sbas_correction_data }; typedef struct mip_gnss_sbas_correction_data mip_gnss_sbas_correction_data; -void insert_mip_gnss_sbas_correction_data(struct microstrain_serializer* serializer, const mip_gnss_sbas_correction_data* self); -void extract_mip_gnss_sbas_correction_data(struct microstrain_serializer* serializer, mip_gnss_sbas_correction_data* self); +void insert_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data* self); +void extract_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, mip_gnss_sbas_correction_data* self); bool extract_mip_gnss_sbas_correction_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_sbas_correction_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self); -void extract_mip_gnss_sbas_correction_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self); +void insert_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self); +void extract_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self); ///@} @@ -918,21 +918,21 @@ struct mip_gnss_rf_error_detection_data }; typedef struct mip_gnss_rf_error_detection_data mip_gnss_rf_error_detection_data; -void insert_mip_gnss_rf_error_detection_data(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data* self); -void extract_mip_gnss_rf_error_detection_data(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data* self); +void insert_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data* self); +void extract_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data* self); bool extract_mip_gnss_rf_error_detection_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_rf_error_detection_data_rfband(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self); -void extract_mip_gnss_rf_error_detection_data_rfband(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self); +void insert_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self); +void extract_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self); -void insert_mip_gnss_rf_error_detection_data_jamming_state(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self); -void extract_mip_gnss_rf_error_detection_data_jamming_state(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self); +void insert_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self); +void extract_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self); -void insert_mip_gnss_rf_error_detection_data_spoofing_state(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self); -void extract_mip_gnss_rf_error_detection_data_spoofing_state(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self); +void insert_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self); +void extract_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self); -void insert_mip_gnss_rf_error_detection_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self); -void extract_mip_gnss_rf_error_detection_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self); +void insert_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self); +void extract_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self); ///@} @@ -981,15 +981,15 @@ struct mip_gnss_base_station_info_data }; typedef struct mip_gnss_base_station_info_data mip_gnss_base_station_info_data; -void insert_mip_gnss_base_station_info_data(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data* self); -void extract_mip_gnss_base_station_info_data(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data* self); +void insert_mip_gnss_base_station_info_data(microstrain_serializer* serializer, const mip_gnss_base_station_info_data* self); +void extract_mip_gnss_base_station_info_data(microstrain_serializer* serializer, mip_gnss_base_station_info_data* self); bool extract_mip_gnss_base_station_info_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_base_station_info_data_indicator_flags(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self); -void extract_mip_gnss_base_station_info_data_indicator_flags(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self); +void insert_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self); +void extract_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self); -void insert_mip_gnss_base_station_info_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self); -void extract_mip_gnss_base_station_info_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self); +void insert_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self); +void extract_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self); ///@} @@ -1040,15 +1040,15 @@ struct mip_gnss_rtk_corrections_status_data }; typedef struct mip_gnss_rtk_corrections_status_data mip_gnss_rtk_corrections_status_data; -void insert_mip_gnss_rtk_corrections_status_data(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self); -void extract_mip_gnss_rtk_corrections_status_data(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data* self); +void insert_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self); +void extract_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data* self); bool extract_mip_gnss_rtk_corrections_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_rtk_corrections_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self); -void extract_mip_gnss_rtk_corrections_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self); +void insert_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self); +void extract_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self); -void insert_mip_gnss_rtk_corrections_status_data_epoch_status(struct microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self); -void extract_mip_gnss_rtk_corrections_status_data_epoch_status(struct microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self); +void insert_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self); +void extract_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self); ///@} @@ -1086,12 +1086,12 @@ struct mip_gnss_satellite_status_data }; typedef struct mip_gnss_satellite_status_data mip_gnss_satellite_status_data; -void insert_mip_gnss_satellite_status_data(struct microstrain_serializer* serializer, const mip_gnss_satellite_status_data* self); -void extract_mip_gnss_satellite_status_data(struct microstrain_serializer* serializer, mip_gnss_satellite_status_data* self); +void insert_mip_gnss_satellite_status_data(microstrain_serializer* serializer, const mip_gnss_satellite_status_data* self); +void extract_mip_gnss_satellite_status_data(microstrain_serializer* serializer, mip_gnss_satellite_status_data* self); bool extract_mip_gnss_satellite_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_satellite_status_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self); -void extract_mip_gnss_satellite_status_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self); +void insert_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self); +void extract_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self); ///@} @@ -1155,15 +1155,15 @@ struct mip_gnss_raw_data }; typedef struct mip_gnss_raw_data mip_gnss_raw_data; -void insert_mip_gnss_raw_data(struct microstrain_serializer* serializer, const mip_gnss_raw_data* self); -void extract_mip_gnss_raw_data(struct microstrain_serializer* serializer, mip_gnss_raw_data* self); +void insert_mip_gnss_raw_data(microstrain_serializer* serializer, const mip_gnss_raw_data* self); +void extract_mip_gnss_raw_data(microstrain_serializer* serializer, mip_gnss_raw_data* self); bool extract_mip_gnss_raw_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_raw_data_gnss_signal_quality(struct microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self); -void extract_mip_gnss_raw_data_gnss_signal_quality(struct microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self); +void insert_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self); +void extract_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self); -void insert_mip_gnss_raw_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self); -void extract_mip_gnss_raw_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self); +void insert_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self); +void extract_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self); ///@} @@ -1220,12 +1220,12 @@ struct mip_gnss_gps_ephemeris_data }; typedef struct mip_gnss_gps_ephemeris_data mip_gnss_gps_ephemeris_data; -void insert_mip_gnss_gps_ephemeris_data(struct microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data* self); -void extract_mip_gnss_gps_ephemeris_data(struct microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data* self); +void insert_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data* self); +void extract_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data* self); bool extract_mip_gnss_gps_ephemeris_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_gps_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self); -void extract_mip_gnss_gps_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self); +void insert_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self); +void extract_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self); ///@} @@ -1282,12 +1282,12 @@ struct mip_gnss_galileo_ephemeris_data }; typedef struct mip_gnss_galileo_ephemeris_data mip_gnss_galileo_ephemeris_data; -void insert_mip_gnss_galileo_ephemeris_data(struct microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self); -void extract_mip_gnss_galileo_ephemeris_data(struct microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data* self); +void insert_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self); +void extract_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data* self); bool extract_mip_gnss_galileo_ephemeris_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_galileo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self); -void extract_mip_gnss_galileo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self); +void insert_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self); +void extract_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self); ///@} @@ -1334,12 +1334,12 @@ struct mip_gnss_glo_ephemeris_data }; typedef struct mip_gnss_glo_ephemeris_data mip_gnss_glo_ephemeris_data; -void insert_mip_gnss_glo_ephemeris_data(struct microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data* self); -void extract_mip_gnss_glo_ephemeris_data(struct microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data* self); +void insert_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data* self); +void extract_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data* self); bool extract_mip_gnss_glo_ephemeris_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_glo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self); -void extract_mip_gnss_glo_ephemeris_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self); +void insert_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self); +void extract_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self); ///@} @@ -1369,12 +1369,12 @@ struct mip_gnss_gps_iono_corr_data }; typedef struct mip_gnss_gps_iono_corr_data mip_gnss_gps_iono_corr_data; -void insert_mip_gnss_gps_iono_corr_data(struct microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data* self); -void extract_mip_gnss_gps_iono_corr_data(struct microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data* self); +void insert_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data* self); +void extract_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data* self); bool extract_mip_gnss_gps_iono_corr_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_gps_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self); -void extract_mip_gnss_gps_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self); +void insert_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self); +void extract_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self); ///@} @@ -1404,12 +1404,12 @@ struct mip_gnss_galileo_iono_corr_data }; typedef struct mip_gnss_galileo_iono_corr_data mip_gnss_galileo_iono_corr_data; -void insert_mip_gnss_galileo_iono_corr_data(struct microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self); -void extract_mip_gnss_galileo_iono_corr_data(struct microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data* self); +void insert_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self); +void extract_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data* self); bool extract_mip_gnss_galileo_iono_corr_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_gnss_galileo_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self); -void extract_mip_gnss_galileo_iono_corr_data_valid_flags(struct microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self); +void insert_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self); +void extract_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self); ///@} diff --git a/src/mip/definitions/data_sensor.c b/src/mip/definitions/data_sensor.c index 99a8c0318..9f35292c3 100644 --- a/src/mip/definitions/data_sensor.c +++ b/src/mip/definitions/data_sensor.c @@ -431,11 +431,11 @@ bool extract_mip_sensor_gps_timestamp_data_from_field(const mip_field* field, vo return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self) +void insert_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_sensor_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self) +void extract_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -534,11 +534,11 @@ bool extract_mip_sensor_overrange_status_data_from_field(const mip_field* field, return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_overrange_status_data_status(struct microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self) +void insert_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_sensor_overrange_status_data_status(struct microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self) +void extract_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/mip/definitions/data_sensor.h b/src/mip/definitions/data_sensor.h index c280064d2..0d833b545 100644 --- a/src/mip/definitions/data_sensor.h +++ b/src/mip/definitions/data_sensor.h @@ -84,8 +84,8 @@ struct mip_sensor_raw_accel_data }; typedef struct mip_sensor_raw_accel_data mip_sensor_raw_accel_data; -void insert_mip_sensor_raw_accel_data(struct microstrain_serializer* serializer, const mip_sensor_raw_accel_data* self); -void extract_mip_sensor_raw_accel_data(struct microstrain_serializer* serializer, mip_sensor_raw_accel_data* self); +void insert_mip_sensor_raw_accel_data(microstrain_serializer* serializer, const mip_sensor_raw_accel_data* self); +void extract_mip_sensor_raw_accel_data(microstrain_serializer* serializer, mip_sensor_raw_accel_data* self); bool extract_mip_sensor_raw_accel_data_from_field(const struct mip_field* field, void* ptr); @@ -104,8 +104,8 @@ struct mip_sensor_raw_gyro_data }; typedef struct mip_sensor_raw_gyro_data mip_sensor_raw_gyro_data; -void insert_mip_sensor_raw_gyro_data(struct microstrain_serializer* serializer, const mip_sensor_raw_gyro_data* self); -void extract_mip_sensor_raw_gyro_data(struct microstrain_serializer* serializer, mip_sensor_raw_gyro_data* self); +void insert_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, const mip_sensor_raw_gyro_data* self); +void extract_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, mip_sensor_raw_gyro_data* self); bool extract_mip_sensor_raw_gyro_data_from_field(const struct mip_field* field, void* ptr); @@ -124,8 +124,8 @@ struct mip_sensor_raw_mag_data }; typedef struct mip_sensor_raw_mag_data mip_sensor_raw_mag_data; -void insert_mip_sensor_raw_mag_data(struct microstrain_serializer* serializer, const mip_sensor_raw_mag_data* self); -void extract_mip_sensor_raw_mag_data(struct microstrain_serializer* serializer, mip_sensor_raw_mag_data* self); +void insert_mip_sensor_raw_mag_data(microstrain_serializer* serializer, const mip_sensor_raw_mag_data* self); +void extract_mip_sensor_raw_mag_data(microstrain_serializer* serializer, mip_sensor_raw_mag_data* self); bool extract_mip_sensor_raw_mag_data_from_field(const struct mip_field* field, void* ptr); @@ -144,8 +144,8 @@ struct mip_sensor_raw_pressure_data }; typedef struct mip_sensor_raw_pressure_data mip_sensor_raw_pressure_data; -void insert_mip_sensor_raw_pressure_data(struct microstrain_serializer* serializer, const mip_sensor_raw_pressure_data* self); -void extract_mip_sensor_raw_pressure_data(struct microstrain_serializer* serializer, mip_sensor_raw_pressure_data* self); +void insert_mip_sensor_raw_pressure_data(microstrain_serializer* serializer, const mip_sensor_raw_pressure_data* self); +void extract_mip_sensor_raw_pressure_data(microstrain_serializer* serializer, mip_sensor_raw_pressure_data* self); bool extract_mip_sensor_raw_pressure_data_from_field(const struct mip_field* field, void* ptr); @@ -164,8 +164,8 @@ struct mip_sensor_scaled_accel_data }; typedef struct mip_sensor_scaled_accel_data mip_sensor_scaled_accel_data; -void insert_mip_sensor_scaled_accel_data(struct microstrain_serializer* serializer, const mip_sensor_scaled_accel_data* self); -void extract_mip_sensor_scaled_accel_data(struct microstrain_serializer* serializer, mip_sensor_scaled_accel_data* self); +void insert_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, const mip_sensor_scaled_accel_data* self); +void extract_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, mip_sensor_scaled_accel_data* self); bool extract_mip_sensor_scaled_accel_data_from_field(const struct mip_field* field, void* ptr); @@ -184,8 +184,8 @@ struct mip_sensor_scaled_gyro_data }; typedef struct mip_sensor_scaled_gyro_data mip_sensor_scaled_gyro_data; -void insert_mip_sensor_scaled_gyro_data(struct microstrain_serializer* serializer, const mip_sensor_scaled_gyro_data* self); -void extract_mip_sensor_scaled_gyro_data(struct microstrain_serializer* serializer, mip_sensor_scaled_gyro_data* self); +void insert_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, const mip_sensor_scaled_gyro_data* self); +void extract_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, mip_sensor_scaled_gyro_data* self); bool extract_mip_sensor_scaled_gyro_data_from_field(const struct mip_field* field, void* ptr); @@ -204,8 +204,8 @@ struct mip_sensor_scaled_mag_data }; typedef struct mip_sensor_scaled_mag_data mip_sensor_scaled_mag_data; -void insert_mip_sensor_scaled_mag_data(struct microstrain_serializer* serializer, const mip_sensor_scaled_mag_data* self); -void extract_mip_sensor_scaled_mag_data(struct microstrain_serializer* serializer, mip_sensor_scaled_mag_data* self); +void insert_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, const mip_sensor_scaled_mag_data* self); +void extract_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, mip_sensor_scaled_mag_data* self); bool extract_mip_sensor_scaled_mag_data_from_field(const struct mip_field* field, void* ptr); @@ -223,8 +223,8 @@ struct mip_sensor_scaled_pressure_data }; typedef struct mip_sensor_scaled_pressure_data mip_sensor_scaled_pressure_data; -void insert_mip_sensor_scaled_pressure_data(struct microstrain_serializer* serializer, const mip_sensor_scaled_pressure_data* self); -void extract_mip_sensor_scaled_pressure_data(struct microstrain_serializer* serializer, mip_sensor_scaled_pressure_data* self); +void insert_mip_sensor_scaled_pressure_data(microstrain_serializer* serializer, const mip_sensor_scaled_pressure_data* self); +void extract_mip_sensor_scaled_pressure_data(microstrain_serializer* serializer, mip_sensor_scaled_pressure_data* self); bool extract_mip_sensor_scaled_pressure_data_from_field(const struct mip_field* field, void* ptr); @@ -243,8 +243,8 @@ struct mip_sensor_delta_theta_data }; typedef struct mip_sensor_delta_theta_data mip_sensor_delta_theta_data; -void insert_mip_sensor_delta_theta_data(struct microstrain_serializer* serializer, const mip_sensor_delta_theta_data* self); -void extract_mip_sensor_delta_theta_data(struct microstrain_serializer* serializer, mip_sensor_delta_theta_data* self); +void insert_mip_sensor_delta_theta_data(microstrain_serializer* serializer, const mip_sensor_delta_theta_data* self); +void extract_mip_sensor_delta_theta_data(microstrain_serializer* serializer, mip_sensor_delta_theta_data* self); bool extract_mip_sensor_delta_theta_data_from_field(const struct mip_field* field, void* ptr); @@ -263,8 +263,8 @@ struct mip_sensor_delta_velocity_data }; typedef struct mip_sensor_delta_velocity_data mip_sensor_delta_velocity_data; -void insert_mip_sensor_delta_velocity_data(struct microstrain_serializer* serializer, const mip_sensor_delta_velocity_data* self); -void extract_mip_sensor_delta_velocity_data(struct microstrain_serializer* serializer, mip_sensor_delta_velocity_data* self); +void insert_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, const mip_sensor_delta_velocity_data* self); +void extract_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, mip_sensor_delta_velocity_data* self); bool extract_mip_sensor_delta_velocity_data_from_field(const struct mip_field* field, void* ptr); @@ -292,8 +292,8 @@ struct mip_sensor_comp_orientation_matrix_data }; typedef struct mip_sensor_comp_orientation_matrix_data mip_sensor_comp_orientation_matrix_data; -void insert_mip_sensor_comp_orientation_matrix_data(struct microstrain_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self); -void extract_mip_sensor_comp_orientation_matrix_data(struct microstrain_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self); +void insert_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self); +void extract_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self); bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const struct mip_field* field, void* ptr); @@ -319,8 +319,8 @@ struct mip_sensor_comp_quaternion_data }; typedef struct mip_sensor_comp_quaternion_data mip_sensor_comp_quaternion_data; -void insert_mip_sensor_comp_quaternion_data(struct microstrain_serializer* serializer, const mip_sensor_comp_quaternion_data* self); -void extract_mip_sensor_comp_quaternion_data(struct microstrain_serializer* serializer, mip_sensor_comp_quaternion_data* self); +void insert_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, const mip_sensor_comp_quaternion_data* self); +void extract_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, mip_sensor_comp_quaternion_data* self); bool extract_mip_sensor_comp_quaternion_data_from_field(const struct mip_field* field, void* ptr); @@ -341,8 +341,8 @@ struct mip_sensor_comp_euler_angles_data }; typedef struct mip_sensor_comp_euler_angles_data mip_sensor_comp_euler_angles_data; -void insert_mip_sensor_comp_euler_angles_data(struct microstrain_serializer* serializer, const mip_sensor_comp_euler_angles_data* self); -void extract_mip_sensor_comp_euler_angles_data(struct microstrain_serializer* serializer, mip_sensor_comp_euler_angles_data* self); +void insert_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, const mip_sensor_comp_euler_angles_data* self); +void extract_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, mip_sensor_comp_euler_angles_data* self); bool extract_mip_sensor_comp_euler_angles_data_from_field(const struct mip_field* field, void* ptr); @@ -360,8 +360,8 @@ struct mip_sensor_comp_orientation_update_matrix_data }; typedef struct mip_sensor_comp_orientation_update_matrix_data mip_sensor_comp_orientation_update_matrix_data; -void insert_mip_sensor_comp_orientation_update_matrix_data(struct microstrain_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self); -void extract_mip_sensor_comp_orientation_update_matrix_data(struct microstrain_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self); +void insert_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self); +void extract_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self); bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const struct mip_field* field, void* ptr); @@ -379,8 +379,8 @@ struct mip_sensor_orientation_raw_temp_data }; typedef struct mip_sensor_orientation_raw_temp_data mip_sensor_orientation_raw_temp_data; -void insert_mip_sensor_orientation_raw_temp_data(struct microstrain_serializer* serializer, const mip_sensor_orientation_raw_temp_data* self); -void extract_mip_sensor_orientation_raw_temp_data(struct microstrain_serializer* serializer, mip_sensor_orientation_raw_temp_data* self); +void insert_mip_sensor_orientation_raw_temp_data(microstrain_serializer* serializer, const mip_sensor_orientation_raw_temp_data* self); +void extract_mip_sensor_orientation_raw_temp_data(microstrain_serializer* serializer, mip_sensor_orientation_raw_temp_data* self); bool extract_mip_sensor_orientation_raw_temp_data_from_field(const struct mip_field* field, void* ptr); @@ -398,8 +398,8 @@ struct mip_sensor_internal_timestamp_data }; typedef struct mip_sensor_internal_timestamp_data mip_sensor_internal_timestamp_data; -void insert_mip_sensor_internal_timestamp_data(struct microstrain_serializer* serializer, const mip_sensor_internal_timestamp_data* self); -void extract_mip_sensor_internal_timestamp_data(struct microstrain_serializer* serializer, mip_sensor_internal_timestamp_data* self); +void insert_mip_sensor_internal_timestamp_data(microstrain_serializer* serializer, const mip_sensor_internal_timestamp_data* self); +void extract_mip_sensor_internal_timestamp_data(microstrain_serializer* serializer, mip_sensor_internal_timestamp_data* self); bool extract_mip_sensor_internal_timestamp_data_from_field(const struct mip_field* field, void* ptr); @@ -418,8 +418,8 @@ struct mip_sensor_pps_timestamp_data }; typedef struct mip_sensor_pps_timestamp_data mip_sensor_pps_timestamp_data; -void insert_mip_sensor_pps_timestamp_data(struct microstrain_serializer* serializer, const mip_sensor_pps_timestamp_data* self); -void extract_mip_sensor_pps_timestamp_data(struct microstrain_serializer* serializer, mip_sensor_pps_timestamp_data* self); +void insert_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_pps_timestamp_data* self); +void extract_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, mip_sensor_pps_timestamp_data* self); bool extract_mip_sensor_pps_timestamp_data_from_field(const struct mip_field* field, void* ptr); @@ -454,12 +454,12 @@ struct mip_sensor_gps_timestamp_data }; typedef struct mip_sensor_gps_timestamp_data mip_sensor_gps_timestamp_data; -void insert_mip_sensor_gps_timestamp_data(struct microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data* self); -void extract_mip_sensor_gps_timestamp_data(struct microstrain_serializer* serializer, mip_sensor_gps_timestamp_data* self); +void insert_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data* self); +void extract_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data* self); bool extract_mip_sensor_gps_timestamp_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_sensor_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self); -void extract_mip_sensor_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self); +void insert_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self); +void extract_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self); ///@} @@ -482,8 +482,8 @@ struct mip_sensor_temperature_abs_data }; typedef struct mip_sensor_temperature_abs_data mip_sensor_temperature_abs_data; -void insert_mip_sensor_temperature_abs_data(struct microstrain_serializer* serializer, const mip_sensor_temperature_abs_data* self); -void extract_mip_sensor_temperature_abs_data(struct microstrain_serializer* serializer, mip_sensor_temperature_abs_data* self); +void insert_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, const mip_sensor_temperature_abs_data* self); +void extract_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, mip_sensor_temperature_abs_data* self); bool extract_mip_sensor_temperature_abs_data_from_field(const struct mip_field* field, void* ptr); @@ -507,8 +507,8 @@ struct mip_sensor_up_vector_data }; typedef struct mip_sensor_up_vector_data mip_sensor_up_vector_data; -void insert_mip_sensor_up_vector_data(struct microstrain_serializer* serializer, const mip_sensor_up_vector_data* self); -void extract_mip_sensor_up_vector_data(struct microstrain_serializer* serializer, mip_sensor_up_vector_data* self); +void insert_mip_sensor_up_vector_data(microstrain_serializer* serializer, const mip_sensor_up_vector_data* self); +void extract_mip_sensor_up_vector_data(microstrain_serializer* serializer, mip_sensor_up_vector_data* self); bool extract_mip_sensor_up_vector_data_from_field(const struct mip_field* field, void* ptr); @@ -529,8 +529,8 @@ struct mip_sensor_north_vector_data }; typedef struct mip_sensor_north_vector_data mip_sensor_north_vector_data; -void insert_mip_sensor_north_vector_data(struct microstrain_serializer* serializer, const mip_sensor_north_vector_data* self); -void extract_mip_sensor_north_vector_data(struct microstrain_serializer* serializer, mip_sensor_north_vector_data* self); +void insert_mip_sensor_north_vector_data(microstrain_serializer* serializer, const mip_sensor_north_vector_data* self); +void extract_mip_sensor_north_vector_data(microstrain_serializer* serializer, mip_sensor_north_vector_data* self); bool extract_mip_sensor_north_vector_data_from_field(const struct mip_field* field, void* ptr); @@ -561,12 +561,12 @@ struct mip_sensor_overrange_status_data }; typedef struct mip_sensor_overrange_status_data mip_sensor_overrange_status_data; -void insert_mip_sensor_overrange_status_data(struct microstrain_serializer* serializer, const mip_sensor_overrange_status_data* self); -void extract_mip_sensor_overrange_status_data(struct microstrain_serializer* serializer, mip_sensor_overrange_status_data* self); +void insert_mip_sensor_overrange_status_data(microstrain_serializer* serializer, const mip_sensor_overrange_status_data* self); +void extract_mip_sensor_overrange_status_data(microstrain_serializer* serializer, mip_sensor_overrange_status_data* self); bool extract_mip_sensor_overrange_status_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_sensor_overrange_status_data_status(struct microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self); -void extract_mip_sensor_overrange_status_data_status(struct microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self); +void insert_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self); +void extract_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self); ///@} @@ -584,8 +584,8 @@ struct mip_sensor_odometer_data_data }; typedef struct mip_sensor_odometer_data_data mip_sensor_odometer_data_data; -void insert_mip_sensor_odometer_data_data(struct microstrain_serializer* serializer, const mip_sensor_odometer_data_data* self); -void extract_mip_sensor_odometer_data_data(struct microstrain_serializer* serializer, mip_sensor_odometer_data_data* self); +void insert_mip_sensor_odometer_data_data(microstrain_serializer* serializer, const mip_sensor_odometer_data_data* self); +void extract_mip_sensor_odometer_data_data(microstrain_serializer* serializer, mip_sensor_odometer_data_data* self); bool extract_mip_sensor_odometer_data_data_from_field(const struct mip_field* field, void* ptr); diff --git a/src/mip/definitions/data_shared.c b/src/mip/definitions/data_shared.c index fcc5d97a1..1171de07a 100644 --- a/src/mip/definitions/data_shared.c +++ b/src/mip/definitions/data_shared.c @@ -115,11 +115,11 @@ bool extract_mip_shared_gps_timestamp_data_from_field(const mip_field* field, vo return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self) +void insert_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_shared_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self) +void extract_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -210,11 +210,11 @@ bool extract_mip_shared_external_timestamp_data_from_field(const mip_field* fiel return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_external_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self) +void insert_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_shared_external_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self) +void extract_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -245,11 +245,11 @@ bool extract_mip_shared_external_time_delta_data_from_field(const mip_field* fie return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_external_time_delta_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self) +void insert_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t) (self)); } -void extract_mip_shared_external_time_delta_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self) +void extract_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/mip/definitions/data_shared.h b/src/mip/definitions/data_shared.h index 9e7cf172a..adaf86cb1 100644 --- a/src/mip/definitions/data_shared.h +++ b/src/mip/definitions/data_shared.h @@ -71,8 +71,8 @@ struct mip_shared_event_source_data }; typedef struct mip_shared_event_source_data mip_shared_event_source_data; -void insert_mip_shared_event_source_data(struct microstrain_serializer* serializer, const mip_shared_event_source_data* self); -void extract_mip_shared_event_source_data(struct microstrain_serializer* serializer, mip_shared_event_source_data* self); +void insert_mip_shared_event_source_data(microstrain_serializer* serializer, const mip_shared_event_source_data* self); +void extract_mip_shared_event_source_data(microstrain_serializer* serializer, mip_shared_event_source_data* self); bool extract_mip_shared_event_source_data_from_field(const struct mip_field* field, void* ptr); @@ -93,8 +93,8 @@ struct mip_shared_ticks_data }; typedef struct mip_shared_ticks_data mip_shared_ticks_data; -void insert_mip_shared_ticks_data(struct microstrain_serializer* serializer, const mip_shared_ticks_data* self); -void extract_mip_shared_ticks_data(struct microstrain_serializer* serializer, mip_shared_ticks_data* self); +void insert_mip_shared_ticks_data(microstrain_serializer* serializer, const mip_shared_ticks_data* self); +void extract_mip_shared_ticks_data(microstrain_serializer* serializer, mip_shared_ticks_data* self); bool extract_mip_shared_ticks_data_from_field(const struct mip_field* field, void* ptr); @@ -116,8 +116,8 @@ struct mip_shared_delta_ticks_data }; typedef struct mip_shared_delta_ticks_data mip_shared_delta_ticks_data; -void insert_mip_shared_delta_ticks_data(struct microstrain_serializer* serializer, const mip_shared_delta_ticks_data* self); -void extract_mip_shared_delta_ticks_data(struct microstrain_serializer* serializer, mip_shared_delta_ticks_data* self); +void insert_mip_shared_delta_ticks_data(microstrain_serializer* serializer, const mip_shared_delta_ticks_data* self); +void extract_mip_shared_delta_ticks_data(microstrain_serializer* serializer, mip_shared_delta_ticks_data* self); bool extract_mip_shared_delta_ticks_data_from_field(const struct mip_field* field, void* ptr); @@ -147,12 +147,12 @@ struct mip_shared_gps_timestamp_data }; typedef struct mip_shared_gps_timestamp_data mip_shared_gps_timestamp_data; -void insert_mip_shared_gps_timestamp_data(struct microstrain_serializer* serializer, const mip_shared_gps_timestamp_data* self); -void extract_mip_shared_gps_timestamp_data(struct microstrain_serializer* serializer, mip_shared_gps_timestamp_data* self); +void insert_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data* self); +void extract_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, mip_shared_gps_timestamp_data* self); bool extract_mip_shared_gps_timestamp_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_shared_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self); -void extract_mip_shared_gps_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self); +void insert_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self); +void extract_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self); ///@} @@ -178,8 +178,8 @@ struct mip_shared_delta_time_data }; typedef struct mip_shared_delta_time_data mip_shared_delta_time_data; -void insert_mip_shared_delta_time_data(struct microstrain_serializer* serializer, const mip_shared_delta_time_data* self); -void extract_mip_shared_delta_time_data(struct microstrain_serializer* serializer, mip_shared_delta_time_data* self); +void insert_mip_shared_delta_time_data(microstrain_serializer* serializer, const mip_shared_delta_time_data* self); +void extract_mip_shared_delta_time_data(microstrain_serializer* serializer, mip_shared_delta_time_data* self); bool extract_mip_shared_delta_time_data_from_field(const struct mip_field* field, void* ptr); @@ -204,8 +204,8 @@ struct mip_shared_reference_timestamp_data }; typedef struct mip_shared_reference_timestamp_data mip_shared_reference_timestamp_data; -void insert_mip_shared_reference_timestamp_data(struct microstrain_serializer* serializer, const mip_shared_reference_timestamp_data* self); -void extract_mip_shared_reference_timestamp_data(struct microstrain_serializer* serializer, mip_shared_reference_timestamp_data* self); +void insert_mip_shared_reference_timestamp_data(microstrain_serializer* serializer, const mip_shared_reference_timestamp_data* self); +void extract_mip_shared_reference_timestamp_data(microstrain_serializer* serializer, mip_shared_reference_timestamp_data* self); bool extract_mip_shared_reference_timestamp_data_from_field(const struct mip_field* field, void* ptr); @@ -232,8 +232,8 @@ struct mip_shared_reference_time_delta_data }; typedef struct mip_shared_reference_time_delta_data mip_shared_reference_time_delta_data; -void insert_mip_shared_reference_time_delta_data(struct microstrain_serializer* serializer, const mip_shared_reference_time_delta_data* self); -void extract_mip_shared_reference_time_delta_data(struct microstrain_serializer* serializer, mip_shared_reference_time_delta_data* self); +void insert_mip_shared_reference_time_delta_data(microstrain_serializer* serializer, const mip_shared_reference_time_delta_data* self); +void extract_mip_shared_reference_time_delta_data(microstrain_serializer* serializer, mip_shared_reference_time_delta_data* self); bool extract_mip_shared_reference_time_delta_data_from_field(const struct mip_field* field, void* ptr); @@ -265,12 +265,12 @@ struct mip_shared_external_timestamp_data }; typedef struct mip_shared_external_timestamp_data mip_shared_external_timestamp_data; -void insert_mip_shared_external_timestamp_data(struct microstrain_serializer* serializer, const mip_shared_external_timestamp_data* self); -void extract_mip_shared_external_timestamp_data(struct microstrain_serializer* serializer, mip_shared_external_timestamp_data* self); +void insert_mip_shared_external_timestamp_data(microstrain_serializer* serializer, const mip_shared_external_timestamp_data* self); +void extract_mip_shared_external_timestamp_data(microstrain_serializer* serializer, mip_shared_external_timestamp_data* self); bool extract_mip_shared_external_timestamp_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_shared_external_timestamp_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self); -void extract_mip_shared_external_timestamp_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self); +void insert_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self); +void extract_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self); ///@} @@ -305,12 +305,12 @@ struct mip_shared_external_time_delta_data }; typedef struct mip_shared_external_time_delta_data mip_shared_external_time_delta_data; -void insert_mip_shared_external_time_delta_data(struct microstrain_serializer* serializer, const mip_shared_external_time_delta_data* self); -void extract_mip_shared_external_time_delta_data(struct microstrain_serializer* serializer, mip_shared_external_time_delta_data* self); +void insert_mip_shared_external_time_delta_data(microstrain_serializer* serializer, const mip_shared_external_time_delta_data* self); +void extract_mip_shared_external_time_delta_data(microstrain_serializer* serializer, mip_shared_external_time_delta_data* self); bool extract_mip_shared_external_time_delta_data_from_field(const struct mip_field* field, void* ptr); -void insert_mip_shared_external_time_delta_data_valid_flags(struct microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self); -void extract_mip_shared_external_time_delta_data_valid_flags(struct microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self); +void insert_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self); +void extract_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self); ///@} diff --git a/src/mip/definitions/data_system.h b/src/mip/definitions/data_system.h index 0fe41b46e..8296188dc 100644 --- a/src/mip/definitions/data_system.h +++ b/src/mip/definitions/data_system.h @@ -79,8 +79,8 @@ struct mip_system_built_in_test_data }; typedef struct mip_system_built_in_test_data mip_system_built_in_test_data; -void insert_mip_system_built_in_test_data(struct microstrain_serializer* serializer, const mip_system_built_in_test_data* self); -void extract_mip_system_built_in_test_data(struct microstrain_serializer* serializer, mip_system_built_in_test_data* self); +void insert_mip_system_built_in_test_data(microstrain_serializer* serializer, const mip_system_built_in_test_data* self); +void extract_mip_system_built_in_test_data(microstrain_serializer* serializer, mip_system_built_in_test_data* self); bool extract_mip_system_built_in_test_data_from_field(const struct mip_field* field, void* ptr); @@ -99,8 +99,8 @@ struct mip_system_time_sync_status_data }; typedef struct mip_system_time_sync_status_data mip_system_time_sync_status_data; -void insert_mip_system_time_sync_status_data(struct microstrain_serializer* serializer, const mip_system_time_sync_status_data* self); -void extract_mip_system_time_sync_status_data(struct microstrain_serializer* serializer, mip_system_time_sync_status_data* self); +void insert_mip_system_time_sync_status_data(microstrain_serializer* serializer, const mip_system_time_sync_status_data* self); +void extract_mip_system_time_sync_status_data(microstrain_serializer* serializer, mip_system_time_sync_status_data* self); bool extract_mip_system_time_sync_status_data_from_field(const struct mip_field* field, void* ptr); @@ -136,8 +136,8 @@ struct mip_system_gpio_state_data }; typedef struct mip_system_gpio_state_data mip_system_gpio_state_data; -void insert_mip_system_gpio_state_data(struct microstrain_serializer* serializer, const mip_system_gpio_state_data* self); -void extract_mip_system_gpio_state_data(struct microstrain_serializer* serializer, mip_system_gpio_state_data* self); +void insert_mip_system_gpio_state_data(microstrain_serializer* serializer, const mip_system_gpio_state_data* self); +void extract_mip_system_gpio_state_data(microstrain_serializer* serializer, mip_system_gpio_state_data* self); bool extract_mip_system_gpio_state_data_from_field(const struct mip_field* field, void* ptr); @@ -157,8 +157,8 @@ struct mip_system_gpio_analog_value_data }; typedef struct mip_system_gpio_analog_value_data mip_system_gpio_analog_value_data; -void insert_mip_system_gpio_analog_value_data(struct microstrain_serializer* serializer, const mip_system_gpio_analog_value_data* self); -void extract_mip_system_gpio_analog_value_data(struct microstrain_serializer* serializer, mip_system_gpio_analog_value_data* self); +void insert_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, const mip_system_gpio_analog_value_data* self); +void extract_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, mip_system_gpio_analog_value_data* self); bool extract_mip_system_gpio_analog_value_data_from_field(const struct mip_field* field, void* ptr); diff --git a/src/mip/mip_field.h b/src/mip/mip_field.h index 9aba6af82..ee0b5677c 100644 --- a/src/mip/mip_field.h +++ b/src/mip/mip_field.h @@ -118,7 +118,7 @@ bool mip_field_next_in_packet(mip_field* field, const mip_packet* packet); //////////////////////////////////////////////////////////////////////////////// /// -void microstrain_serializer_init_from_field(struct microstrain_serializer* serializer, const mip_field* field); +void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field* field); #ifdef __cplusplus } // namespace mip diff --git a/src/mip/mip_packet.h b/src/mip/mip_packet.h index f53203bd5..6ab413388 100644 --- a/src/mip/mip_packet.h +++ b/src/mip/mip_packet.h @@ -3,9 +3,18 @@ #include "mip_types.h" #ifdef __cplusplus + +namespace microstrain { +namespace C { +struct microstrain_serializer; +} +} + namespace mip { namespace C { extern "C" { +#else +struct microstrain_serializer; #endif @@ -106,10 +115,9 @@ bool mip_packet_is_data(const mip_packet* packet); ///@defgroup Serialization Accessors - Functions for serializing a MIP packet. /// ///@{ -struct microstrain_serializer; -void microstrain_serializer_init_new_field(struct microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor); -void microstrain_serializer_finish_new_field(const struct microstrain_serializer* serializer, mip_packet* packet); +void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor); +void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet* packet); ///@} ///@} From 65a7b37d5700c360cf87369c4ffecfc6657b653c Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 22 May 2024 16:26:47 -0400 Subject: [PATCH 009/147] Fix Jenkinsfile release from master (take 2). --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 269e5f624..5e83bdeba 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -135,7 +135,7 @@ pipeline { # Release to the latest version if the master commit matches up with the commit of that version if (cd "${WORKSPACE}" && git describe --exact-match --tags HEAD &> /dev/null); then # Publish a release - ./scripts/release.sh \ + ${WORKSPACE}/scripts/release.sh" \ --artifacts "$(find "$(pwd)" -type f)" \ --target "${BRANCH_NAME}" \ --release "$(cd ${WORKSPACE} && git describe --exact-match --tags HEAD)" \ From 36a38f210347e96fbfebfaadbd88957d99c54870 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 23 May 2024 18:19:57 -0400 Subject: [PATCH 010/147] WIP updating serialization stuff. --- examples/watch_imu.cpp | 2 +- src/microstrain/common/buffer.hpp | 328 ++++++ src/microstrain/common/platform.h | 8 +- src/microstrain/common/serialization.h | 76 +- src/mip/definitions/commands_3dm.cpp | 1106 +++++++++---------- src/mip/definitions/commands_3dm.hpp | 386 +++---- src/mip/definitions/commands_aiding.cpp | 140 +-- src/mip/definitions/commands_aiding.hpp | 58 +- src/mip/definitions/commands_base.cpp | 117 +- src/mip/definitions/commands_base.hpp | 79 +- src/mip/definitions/commands_filter.cpp | 1341 ++++++++++++----------- src/mip/definitions/commands_filter.hpp | 382 +++---- src/mip/definitions/commands_gnss.cpp | 78 +- src/mip/definitions/commands_gnss.hpp | 30 +- src/mip/definitions/commands_rtk.cpp | 138 +-- src/mip/definitions/commands_rtk.hpp | 86 +- src/mip/definitions/commands_system.cpp | 26 +- src/mip/definitions/commands_system.hpp | 10 +- src/mip/definitions/common.h | 19 +- src/mip/definitions/data_filter.cpp | 232 ++-- src/mip/definitions/data_filter.hpp | 230 ++-- src/mip/definitions/data_gnss.cpp | 112 +- src/mip/definitions/data_gnss.hpp | 110 +- src/mip/definitions/data_sensor.cpp | 96 +- src/mip/definitions/data_sensor.hpp | 94 +- src/mip/definitions/data_shared.cpp | 40 +- src/mip/definitions/data_shared.hpp | 38 +- src/mip/definitions/data_system.cpp | 20 +- src/mip/definitions/data_system.hpp | 18 +- src/mip/definitions/descriptors.h | 6 +- src/mip/mip.hpp | 40 +- src/mip/mip_all.hpp | 2 +- src/mip/mip_field.h | 2 +- src/mip/mip_packet.h | 4 +- 34 files changed, 2915 insertions(+), 2539 deletions(-) create mode 100644 src/microstrain/common/buffer.hpp diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index 13237f0db..e5b6692c3 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -3,7 +3,7 @@ #include #include -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include #include diff --git a/src/microstrain/common/buffer.hpp b/src/microstrain/common/buffer.hpp new file mode 100644 index 000000000..d8c7ed623 --- /dev/null +++ b/src/microstrain/common/buffer.hpp @@ -0,0 +1,328 @@ +#pragma once + +#include +#include + +#include + + +namespace microstrain +{ + + +// +// Basic Insertion +// + +template +typename std::enable_if::value && sizeof(T)==1, size_t>::type +/*size_t*/ insert_basic(uint8_t* buffer, T value) +{ + buffer[0] = reinterpret_cast(&value)[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T)==2, size_t>::type +/*size_t*/ insert_basic(uint8_t* buffer, T value) +{ + buffer[0] = reinterpret_cast(&value)[1]; + buffer[1] = reinterpret_cast(&value)[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T)==4, size_t>::type +/*size_t*/ insert_basic(uint8_t* buffer, T value) +{ + buffer[0] = reinterpret_cast(&value)[3]; + buffer[1] = reinterpret_cast(&value)[2]; + buffer[2] = reinterpret_cast(&value)[1]; + buffer[3] = reinterpret_cast(&value)[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T)==8, size_t>::type +/*size_t*/ insert_basic(uint8_t* buffer, T value) +{ + buffer[0] = reinterpret_cast(&value)[7]; + buffer[1] = reinterpret_cast(&value)[6]; + buffer[2] = reinterpret_cast(&value)[5]; + buffer[3] = reinterpret_cast(&value)[4]; + buffer[4] = reinterpret_cast(&value)[3]; + buffer[5] = reinterpret_cast(&value)[2]; + buffer[6] = reinterpret_cast(&value)[1]; + buffer[7] = reinterpret_cast(&value)[0]; + return sizeof(T); +} + +// +// Basic Extraction +// + +template +typename std::enable_if::value && sizeof(T)==1, size_t>::type +/*size_t*/ extract_basic(const uint8_t* buffer, T& value) +{ + reinterpret_cast(&value)[0] = buffer[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T)==2, size_t>::type +/*size_t*/ extract_basic(const uint8_t* buffer, T& value) +{ + reinterpret_cast(&value)[0] = buffer[1]; + reinterpret_cast(&value)[1] = buffer[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T)==4, size_t>::type +/*size_t*/ extract_basic(const uint8_t* buffer, T& value) +{ + reinterpret_cast(&value)[0] = buffer[3]; + reinterpret_cast(&value)[1] = buffer[2]; + reinterpret_cast(&value)[2] = buffer[1]; + reinterpret_cast(&value)[3] = buffer[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T)==8, size_t>::type +/*size_t*/ extract_basic(const uint8_t* buffer, T& value) +{ + reinterpret_cast(&value)[0] = buffer[7]; + reinterpret_cast(&value)[1] = buffer[6]; + reinterpret_cast(&value)[2] = buffer[5]; + reinterpret_cast(&value)[3] = buffer[4]; + reinterpret_cast(&value)[4] = buffer[3]; + reinterpret_cast(&value)[5] = buffer[2]; + reinterpret_cast(&value)[6] = buffer[1]; + reinterpret_cast(&value)[7] = buffer[0]; + return sizeof(T); +} + + +class Buffer +{ +public: + Buffer() = default; + Buffer(uint8_t* ptr, size_t capacity, size_t offset=0) : m_ptr(ptr), m_size(capacity), m_offset(offset) {} + Buffer(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} + + size_t capacity() const { return m_size; } + size_t length() const { return m_size; } + size_t offset() const { return m_offset; } + int remaining() const { return m_size - m_offset; } + + bool noRemaining() const { return m_offset == m_size; } + bool isOverrun() const { return m_offset > m_size; } + bool isOk() const { return !isOverrun(); } + bool hasRemaining(size_t count) const { return m_offset+count <= m_size; } + + const uint8_t* pointer() const { return m_ptr; } + uint8_t* pointer() { return m_ptr; } + + const uint8_t* pointer(size_t required_size) const { return hasRemaining(required_size) ? m_ptr : nullptr; } + uint8_t* pointer(size_t required_size) { return hasRemaining(required_size) ? m_ptr : nullptr; } + + uint8_t* getPtrAndAdvance(size_t size) { uint8_t* ptr = (hasRemaining(size) ? m_ptr : nullptr); m_offset += size; return ptr; } + + void invalidate() { m_offset = -1U; } + + template + bool insert(const Ts&... values); + + template + bool extract(Ts&... values); + + template + struct Count + { + T& count; + size_t max_count = 0; + }; + +private: + uint8_t* m_ptr = nullptr; + size_t m_size = 0; + size_t m_offset = 0; +}; + + + +//template +//struct fixed_size {}; +// +//template +//struct fixed_size> : std::integral_constant {}; + + +// +// General Insertion +// + +// Built-in types (bool, int, float, ...) +template +typename std::enable_if::value, size_t>::type +/*size_t*/ insert(Buffer& buffer, T value) +{ + if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) + insert_basic(ptr, value); + + return sizeof(T); +} + +// Enums +template +typename std::enable_if::value, size_t>::type +/*size_t*/ insert(Buffer& buffer, T value) +{ + using BaseType = typename std::underlying_type::type; + + if(auto ptr = buffer.getPtrAndAdvance(sizeof(BaseType))) + insert_basic(ptr, static_cast(value)); + + return sizeof(BaseType); +} + +// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. +template +typename std::enable_if::value, size_t>::type +/*size_t*/ insert(Buffer& buffer, const T& value) +{ + return value.serialize(buffer); +} + +#if __cpp_fold_expressions >= 201603L +template +size_t insert(Buffer& buffer, Ts... values) +{ + if( (std::is_arithmetic::value && ...) ) + { + const size_t size = ( ... + sizeof(Ts) ); + + if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) + { + size_t offset = 0; + return ( ... + (offset += insert_basic(ptr+offset, values)) ); + } + + return size; + } + else + return ( ... + insert(buffer, values) ); +} +#else +template +size_t insert(Buffer& buffer, T0 value0, Ts... values) +{ + return insert(buffer, value0) + insert(buffer, values...); +} +#endif + + +//template +//size_t insert(Buffer& buffer, Ts... values) { return detail::insert(buffer, values...); } + + +//// Class types with known size +//template::value> +//size_t insert(Buffer& buffer, T value) +//{ +// if(auto ptr = buffer.getPtrAndAdvance(Size)) +// insert +//} + +// +// General Extraction +// + +// Built-in types (bool, int, float, ...) +template +typename std::enable_if::value, size_t>::type +/*size_t*/ extract(Buffer& buffer, T& value) +{ + if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) + extract_basic(ptr, value); + + return sizeof(T); +} + +// Enums +template +typename std::enable_if::value, size_t>::type +/*size_t*/ extract(Buffer& buffer, T& value) +{ + using BaseType = typename std::underlying_type::type; + + if(auto ptr = buffer.getPtrAndAdvance(sizeof(BaseType))) + { + BaseType base; + extract_basic(ptr, base); + value = static_cast(base); + } + + return sizeof(BaseType); +} + +// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. +template +typename std::enable_if::value, size_t>::type +/*size_t*/ extract(Buffer& buffer, T& value) +{ + return value.deserialize(buffer); +} + +#if __cpp_fold_expressions >= 201603L +template +size_t insert(Buffer& buffer, Ts&... values) +{ + if( (std::is_arithmetic::value && ...) ) + { + const size_t size = ( ... + sizeof(Ts) ); + + if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) + { + size_t offset = 0; + return ( ... + (offset += extract_basic(ptr+offset, values)) ); + } + + return size; + } + else + return ( ... + extract(buffer, values) ); +} +#else +template +size_t extract(Buffer& buffer, T0 value0, Ts... values) +{ + return extract(buffer, value0) + extract(buffer, values...); +} +#endif + + + +template +size_t extract(Buffer& buffer, Buffer::Count counter) +{ + size_t size = extract(counter.count); + + if(counter.count > counter.max_count) + buffer.invalidate(); + + return size; +} + + + +template +bool Buffer::insert(const Ts&... values) { return insert(*this, values...); } + +template +bool Buffer::extract(Ts&... values) { return extract(*this, values...); } + + +} // namespace microstrain diff --git a/src/microstrain/common/platform.h b/src/microstrain/common/platform.h index e3527ec26..89555cce9 100644 --- a/src/microstrain/common/platform.h +++ b/src/microstrain/common/platform.h @@ -13,4 +13,10 @@ #define MICROSTRAIN_PLATFORM_OTHER #endif - +#ifdef __cplusplus +#if __cpp_if_constexpr >= 201606L +#define IF_CONSTEXPR if constexpr +#else +#define IF_CONSTEXPR if +#endif +#endif diff --git a/src/microstrain/common/serialization.h b/src/microstrain/common/serialization.h index af3ddc315..adc19fcf6 100644 --- a/src/microstrain/common/serialization.h +++ b/src/microstrain/common/serialization.h @@ -102,6 +102,10 @@ void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* coun } // extern "C" } // namespace C + + +#if 0 + //////////////////////////////////////////////////////////////////////////////// ///@addtogroup mip_cpp ///@{ @@ -114,8 +118,8 @@ void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* coun /// There are two overloaded functions defined in the mip namespace, insert and /// extract. The signature for each is as follows: ///@code{.cpp} -/// void mip::insert(Serializer& serializer, Type value); -/// voie mip::extract(Serializer& serializer, Type value); +/// void mip::insert(Buffer& serializer, Type value); +/// voie mip::extract(Buffer& serializer, Type value); ///@endcode /// Where `Type` is a struct or numeric type. /// @@ -124,7 +128,7 @@ void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* coun ///@li Enums, bitfields, and nested structs for commands /// /// Additionally, there are overloads with a different signature which allow -/// one to avoid creating a Serializer object every time. These overloads +/// one to avoid creating a Buffer object every time. These overloads /// create a serializer internally and pass it on to the regular version. ///@code{.cpp} /// template bool mip::insert(const T& value, uint8_t* buffer, size_t bufferSize); @@ -146,12 +150,12 @@ void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* coun //////////////////////////////////////////////////////////////////////////////// ///@brief Serialization class. /// -class Serializer : public C::microstrain_serializer +class Buffer : public C::microstrain_serializer { public: - // Serializer(C::mip_packet& packet, uint8_t newFieldDescriptor) { C::microstrain_serializer_init_new_field(this, &packet, newFieldDescriptor); } - Serializer(uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_insertion(this, buffer, size); this->_offset = offset; } - Serializer(const uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_extraction(this, const_cast(buffer), size); this->_offset = offset; } + // Buffer(C::mip_packet& packet, uint8_t newFieldDescriptor) { C::microstrain_serializer_init_new_field(this, &packet, newFieldDescriptor); } + Buffer(uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_insertion(this, buffer, size); this->_offset = offset; } + Buffer(const uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_extraction(this, const_cast(buffer), size); this->_offset = offset; } size_t capacity() const { return C::microstrain_serializer_capacity(this); } size_t length() const { return C::microstrain_serializer_length(this); } @@ -166,18 +170,18 @@ class Serializer : public C::microstrain_serializer -inline void insert(Serializer& serializer, bool value) { return C::microstrain_insert_bool(&serializer, value); } -inline void insert(Serializer& serializer, char value) { return C::microstrain_insert_char(&serializer, value); } -inline void insert(Serializer& serializer, uint8_t value) { return C::microstrain_insert_u8(&serializer, value); } -inline void insert(Serializer& serializer, uint16_t value) { return C::microstrain_insert_u16(&serializer, value); } -inline void insert(Serializer& serializer, uint32_t value) { return C::microstrain_insert_u32(&serializer, value); } -inline void insert(Serializer& serializer, uint64_t value) { return C::microstrain_insert_u64(&serializer, value); } -inline void insert(Serializer& serializer, int8_t value) { return C::microstrain_insert_s8(&serializer, value); } -inline void insert(Serializer& serializer, int16_t value) { return C::microstrain_insert_s16(&serializer, value); } -inline void insert(Serializer& serializer, int32_t value) { return C::microstrain_insert_s32(&serializer, value); } -inline void insert(Serializer& serializer, int64_t value) { return C::microstrain_insert_s64(&serializer, value); } -inline void insert(Serializer& serializer, float value) { return C::microstrain_insert_float(&serializer, value); } -inline void insert(Serializer& serializer, double value) { return C::microstrain_insert_double(&serializer, value); } +inline void insert(Buffer& serializer, bool value) { return C::microstrain_insert_bool(&serializer, value); } +inline void insert(Buffer& serializer, char value) { return C::microstrain_insert_char(&serializer, value); } +inline void insert(Buffer& serializer, uint8_t value) { return C::microstrain_insert_u8(&serializer, value); } +inline void insert(Buffer& serializer, uint16_t value) { return C::microstrain_insert_u16(&serializer, value); } +inline void insert(Buffer& serializer, uint32_t value) { return C::microstrain_insert_u32(&serializer, value); } +inline void insert(Buffer& serializer, uint64_t value) { return C::microstrain_insert_u64(&serializer, value); } +inline void insert(Buffer& serializer, int8_t value) { return C::microstrain_insert_s8(&serializer, value); } +inline void insert(Buffer& serializer, int16_t value) { return C::microstrain_insert_s16(&serializer, value); } +inline void insert(Buffer& serializer, int32_t value) { return C::microstrain_insert_s32(&serializer, value); } +inline void insert(Buffer& serializer, int64_t value) { return C::microstrain_insert_s64(&serializer, value); } +inline void insert(Buffer& serializer, float value) { return C::microstrain_insert_float(&serializer, value); } +inline void insert(Buffer& serializer, double value) { return C::microstrain_insert_double(&serializer, value); } //////////////////////////////////////////////////////////////////////////////// ///@brief Inserts an enum into the buffer. @@ -189,7 +193,7 @@ inline void insert(Serializer& serializer, double value) { return C::microstra /// template typename std::enable_if< std::is_enum::value, void>::type -/*void*/ insert(Serializer& serializer, Enum value) { return insert(serializer, static_cast< typename std::underlying_type::type >(value) ); } +/*void*/ insert(Buffer& serializer, Enum value) { return insert(serializer, static_cast< typename std::underlying_type::type >(value) ); } //////////////////////////////////////////////////////////////////////////////// ///@brief Insert the given value into the buffer. @@ -207,23 +211,23 @@ typename std::enable_if< std::is_enum::value, void>::type template bool insert(const T& value, uint8_t* buffer, size_t bufferSize, size_t offset=0) { - Serializer serializer(buffer, bufferSize, offset); + Buffer serializer(buffer, bufferSize, offset); insert(serializer, value); return !!serializer; } -inline void extract(Serializer& serializer, bool& value) { return C::microstrain_extract_bool(&serializer, &value); } -inline void extract(Serializer& serializer, char& value) { return C::microstrain_extract_char(&serializer, &value); } -inline void extract(Serializer& serializer, uint8_t& value) { return C::microstrain_extract_u8(&serializer, &value); } -inline void extract(Serializer& serializer, uint16_t& value) { return C::microstrain_extract_u16(&serializer, &value); } -inline void extract(Serializer& serializer, uint32_t& value) { return C::microstrain_extract_u32(&serializer, &value); } -inline void extract(Serializer& serializer, uint64_t& value) { return C::microstrain_extract_u64(&serializer, &value); } -inline void extract(Serializer& serializer, int8_t& value) { return C::microstrain_extract_s8(&serializer, &value); } -inline void extract(Serializer& serializer, int16_t& value) { return C::microstrain_extract_s16(&serializer, &value); } -inline void extract(Serializer& serializer, int32_t& value) { return C::microstrain_extract_s32(&serializer, &value); } -inline void extract(Serializer& serializer, int64_t& value) { return C::microstrain_extract_s64(&serializer, &value); } -inline void extract(Serializer& serializer, float& value) { return C::microstrain_extract_float(&serializer, &value); } -inline void extract(Serializer& serializer, double& value) { return C::microstrain_extract_double(&serializer, &value); } +inline void extract(Buffer& serializer, bool& value) { return C::microstrain_extract_bool(&serializer, &value); } +inline void extract(Buffer& serializer, char& value) { return C::microstrain_extract_char(&serializer, &value); } +inline void extract(Buffer& serializer, uint8_t& value) { return C::microstrain_extract_u8(&serializer, &value); } +inline void extract(Buffer& serializer, uint16_t& value) { return C::microstrain_extract_u16(&serializer, &value); } +inline void extract(Buffer& serializer, uint32_t& value) { return C::microstrain_extract_u32(&serializer, &value); } +inline void extract(Buffer& serializer, uint64_t& value) { return C::microstrain_extract_u64(&serializer, &value); } +inline void extract(Buffer& serializer, int8_t& value) { return C::microstrain_extract_s8(&serializer, &value); } +inline void extract(Buffer& serializer, int16_t& value) { return C::microstrain_extract_s16(&serializer, &value); } +inline void extract(Buffer& serializer, int32_t& value) { return C::microstrain_extract_s32(&serializer, &value); } +inline void extract(Buffer& serializer, int64_t& value) { return C::microstrain_extract_s64(&serializer, &value); } +inline void extract(Buffer& serializer, float& value) { return C::microstrain_extract_float(&serializer, &value); } +inline void extract(Buffer& serializer, double& value) { return C::microstrain_extract_double(&serializer, &value); } //////////////////////////////////////////////////////////////////////////////// ///@brief Extract an enum from the buffer. @@ -235,7 +239,7 @@ inline void extract(Serializer& serializer, double& value) { return C::microst /// template typename std::enable_if< std::is_enum::value, void>::type -/*void*/ extract(Serializer& serializer, Enum& value) { +/*void*/ extract(Buffer& serializer, Enum& value) { typename std::underlying_type::type tmp; extract(serializer, tmp); value = static_cast(tmp); @@ -264,7 +268,7 @@ typename std::enable_if< std::is_enum::value, void>::type template bool extract(T& value_out, const uint8_t* buffer, size_t bufferSize, size_t offset=0, bool exact_size=false) { - Serializer serializer(buffer, bufferSize, offset); + Buffer serializer(buffer, bufferSize, offset); extract(serializer, value_out); return exact_size ? serializer.isComplete() : serializer.isOk(); } @@ -273,6 +277,8 @@ bool extract(T& value_out, const uint8_t* buffer, size_t bufferSize, size_t offs ///@} //////////////////////////////////////////////////////////////////////////////// +#endif // 0 + } // namespace microstrain #endif // __cplusplus diff --git a/src/mip/definitions/commands_3dm.cpp b/src/mip/definitions/commands_3dm.cpp index be0d7fb52..8e01096ba 100644 --- a/src/mip/definitions/commands_3dm.cpp +++ b/src/mip/definitions/commands_3dm.cpp @@ -1,14 +1,14 @@ #include "commands_3dm.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -16,15 +16,15 @@ struct mip_interface; namespace commands_3dm { -using ::mip::insert; -using ::mip::extract; +using ::microstrain::insert; +using ::microstrain::extract; using namespace ::mip::C; //////////////////////////////////////////////////////////////////////////////// // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const NmeaMessage& self) +void insert(::microstrain::Buffer& serializer, const NmeaMessage& self) { insert(serializer, self.message_id); @@ -35,7 +35,7 @@ void insert(Serializer& serializer, const NmeaMessage& self) insert(serializer, self.decimation); } -void extract(Serializer& serializer, NmeaMessage& self) +void extract(::microstrain::Buffer& serializer, NmeaMessage& self) { extract(serializer, self.message_id); @@ -52,7 +52,7 @@ void extract(Serializer& serializer, NmeaMessage& self) // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const PollImuMessage& self) +void insert(::microstrain::Buffer& serializer, const PollImuMessage& self) { insert(serializer, self.suppress_ack); @@ -62,7 +62,7 @@ void insert(Serializer& serializer, const PollImuMessage& self) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, PollImuMessage& self) +void extract(::microstrain::Buffer& serializer, PollImuMessage& self) { extract(serializer, self.suppress_ack); @@ -75,7 +75,7 @@ void extract(Serializer& serializer, PollImuMessage& self) TypedResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -87,9 +87,9 @@ TypedResult pollImuMessage(C::mip_interface& device, bool suppre assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_IMU_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_IMU_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const PollGnssMessage& self) +void insert(::microstrain::Buffer& serializer, const PollGnssMessage& self) { insert(serializer, self.suppress_ack); @@ -99,7 +99,7 @@ void insert(Serializer& serializer, const PollGnssMessage& self) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, PollGnssMessage& self) +void extract(::microstrain::Buffer& serializer, PollGnssMessage& self) { extract(serializer, self.suppress_ack); @@ -112,7 +112,7 @@ void extract(Serializer& serializer, PollGnssMessage& self) TypedResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -124,9 +124,9 @@ TypedResult pollGnssMessage(C::mip_interface& device, bool supp assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_GNSS_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_GNSS_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const PollFilterMessage& self) +void insert(::microstrain::Buffer& serializer, const PollFilterMessage& self) { insert(serializer, self.suppress_ack); @@ -136,7 +136,7 @@ void insert(Serializer& serializer, const PollFilterMessage& self) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, PollFilterMessage& self) +void extract(::microstrain::Buffer& serializer, PollFilterMessage& self) { extract(serializer, self.suppress_ack); @@ -149,7 +149,7 @@ void extract(Serializer& serializer, PollFilterMessage& self) TypedResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -161,9 +161,9 @@ TypedResult pollFilterMessage(C::mip_interface& device, bool assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_FILTER_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_FILTER_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ImuMessageFormat& self) +void insert(::microstrain::Buffer& serializer, const ImuMessageFormat& self) { insert(serializer, self.function); @@ -176,7 +176,7 @@ void insert(Serializer& serializer, const ImuMessageFormat& self) } } -void extract(Serializer& serializer, ImuMessageFormat& self) +void extract(::microstrain::Buffer& serializer, ImuMessageFormat& self) { extract(serializer, self.function); @@ -189,7 +189,7 @@ void extract(Serializer& serializer, ImuMessageFormat& self) } } -void insert(Serializer& serializer, const ImuMessageFormat::Response& self) +void insert(::microstrain::Buffer& serializer, const ImuMessageFormat::Response& self) { insert(serializer, self.num_descriptors); @@ -197,7 +197,7 @@ void insert(Serializer& serializer, const ImuMessageFormat::Response& self) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, ImuMessageFormat::Response& self) +void extract(::microstrain::Buffer& serializer, ImuMessageFormat::Response& self) { C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) @@ -208,7 +208,7 @@ void extract(Serializer& serializer, ImuMessageFormat::Response& self) TypedResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, numDescriptors); @@ -219,22 +219,22 @@ TypedResult writeImuMessageFormat(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_IMU_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_IMU_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); C::extract_count(&deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); @@ -249,34 +249,34 @@ TypedResult readImuMessageFormat(C::mip_interface& device, uin TypedResult saveImuMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult loadImuMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultImuMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GpsMessageFormat& self) +void insert(::microstrain::Buffer& serializer, const GpsMessageFormat& self) { insert(serializer, self.function); @@ -289,7 +289,7 @@ void insert(Serializer& serializer, const GpsMessageFormat& self) } } -void extract(Serializer& serializer, GpsMessageFormat& self) +void extract(::microstrain::Buffer& serializer, GpsMessageFormat& self) { extract(serializer, self.function); @@ -302,7 +302,7 @@ void extract(Serializer& serializer, GpsMessageFormat& self) } } -void insert(Serializer& serializer, const GpsMessageFormat::Response& self) +void insert(::microstrain::Buffer& serializer, const GpsMessageFormat::Response& self) { insert(serializer, self.num_descriptors); @@ -310,7 +310,7 @@ void insert(Serializer& serializer, const GpsMessageFormat::Response& self) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, GpsMessageFormat::Response& self) +void extract(::microstrain::Buffer& serializer, GpsMessageFormat::Response& self) { C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) @@ -321,7 +321,7 @@ void extract(Serializer& serializer, GpsMessageFormat::Response& self) TypedResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, numDescriptors); @@ -332,22 +332,22 @@ TypedResult writeGpsMessageFormat(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_GNSS_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); C::extract_count(&deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); @@ -362,34 +362,34 @@ TypedResult readGpsMessageFormat(C::mip_interface& device, uin TypedResult saveGpsMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult loadGpsMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultGpsMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const FilterMessageFormat& self) +void insert(::microstrain::Buffer& serializer, const FilterMessageFormat& self) { insert(serializer, self.function); @@ -402,7 +402,7 @@ void insert(Serializer& serializer, const FilterMessageFormat& self) } } -void extract(Serializer& serializer, FilterMessageFormat& self) +void extract(::microstrain::Buffer& serializer, FilterMessageFormat& self) { extract(serializer, self.function); @@ -415,7 +415,7 @@ void extract(Serializer& serializer, FilterMessageFormat& self) } } -void insert(Serializer& serializer, const FilterMessageFormat::Response& self) +void insert(::microstrain::Buffer& serializer, const FilterMessageFormat::Response& self) { insert(serializer, self.num_descriptors); @@ -423,7 +423,7 @@ void insert(Serializer& serializer, const FilterMessageFormat::Response& self) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, FilterMessageFormat::Response& self) +void extract(::microstrain::Buffer& serializer, FilterMessageFormat::Response& self) { C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) @@ -434,7 +434,7 @@ void extract(Serializer& serializer, FilterMessageFormat::Response& self) TypedResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, numDescriptors); @@ -445,22 +445,22 @@ TypedResult writeFilterMessageFormat(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_FILTER_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_FILTER_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); C::extract_count(&deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); @@ -475,50 +475,50 @@ TypedResult readFilterMessageFormat(C::mip_interface& devic TypedResult saveFilterMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult loadFilterMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultFilterMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ImuGetBaseRate& self) +void insert(::microstrain::Buffer& serializer, const ImuGetBaseRate& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, ImuGetBaseRate& self) +void extract(::microstrain::Buffer& serializer, ImuGetBaseRate& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const ImuGetBaseRate::Response& self) +void insert(::microstrain::Buffer& serializer, const ImuGetBaseRate::Response& self) { insert(serializer, self.rate); } -void extract(Serializer& serializer, ImuGetBaseRate::Response& self) +void extract(::microstrain::Buffer& serializer, ImuGetBaseRate::Response& self) { extract(serializer, self.rate); @@ -533,7 +533,7 @@ TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* r if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(rateOut); extract(deserializer, *rateOut); @@ -543,23 +543,23 @@ TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* r } return result; } -void insert(Serializer& serializer, const GpsGetBaseRate& self) +void insert(::microstrain::Buffer& serializer, const GpsGetBaseRate& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GpsGetBaseRate& self) +void extract(::microstrain::Buffer& serializer, GpsGetBaseRate& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GpsGetBaseRate::Response& self) +void insert(::microstrain::Buffer& serializer, const GpsGetBaseRate::Response& self) { insert(serializer, self.rate); } -void extract(Serializer& serializer, GpsGetBaseRate::Response& self) +void extract(::microstrain::Buffer& serializer, GpsGetBaseRate::Response& self) { extract(serializer, self.rate); @@ -574,7 +574,7 @@ TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* r if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(rateOut); extract(deserializer, *rateOut); @@ -584,23 +584,23 @@ TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* r } return result; } -void insert(Serializer& serializer, const FilterGetBaseRate& self) +void insert(::microstrain::Buffer& serializer, const FilterGetBaseRate& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, FilterGetBaseRate& self) +void extract(::microstrain::Buffer& serializer, FilterGetBaseRate& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const FilterGetBaseRate::Response& self) +void insert(::microstrain::Buffer& serializer, const FilterGetBaseRate::Response& self) { insert(serializer, self.rate); } -void extract(Serializer& serializer, FilterGetBaseRate::Response& self) +void extract(::microstrain::Buffer& serializer, FilterGetBaseRate::Response& self) { extract(serializer, self.rate); @@ -615,7 +615,7 @@ TypedResult filterGetBaseRate(C::mip_interface& device, uint1 if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(rateOut); extract(deserializer, *rateOut); @@ -625,7 +625,7 @@ TypedResult filterGetBaseRate(C::mip_interface& device, uint1 } return result; } -void insert(Serializer& serializer, const PollData& self) +void insert(::microstrain::Buffer& serializer, const PollData& self) { insert(serializer, self.desc_set); @@ -637,7 +637,7 @@ void insert(Serializer& serializer, const PollData& self) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, PollData& self) +void extract(::microstrain::Buffer& serializer, PollData& self) { extract(serializer, self.desc_set); @@ -652,7 +652,7 @@ void extract(Serializer& serializer, PollData& self) TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, descSet); @@ -666,27 +666,27 @@ TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool s assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_DATA, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_DATA, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GetBaseRate& self) +void insert(::microstrain::Buffer& serializer, const GetBaseRate& self) { insert(serializer, self.desc_set); } -void extract(Serializer& serializer, GetBaseRate& self) +void extract(::microstrain::Buffer& serializer, GetBaseRate& self) { extract(serializer, self.desc_set); } -void insert(Serializer& serializer, const GetBaseRate::Response& self) +void insert(::microstrain::Buffer& serializer, const GetBaseRate::Response& self) { insert(serializer, self.desc_set); insert(serializer, self.rate); } -void extract(Serializer& serializer, GetBaseRate::Response& self) +void extract(::microstrain::Buffer& serializer, GetBaseRate::Response& self) { extract(serializer, self.desc_set); @@ -697,18 +697,18 @@ void extract(Serializer& serializer, GetBaseRate::Response& self) TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, descSet); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_BASE_RATE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_BASE_RATE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_BASE_RATE, buffer, (uint8_t)serializer.length(), REPLY_BASE_RATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -720,7 +720,7 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, } return result; } -void insert(Serializer& serializer, const MessageFormat& self) +void insert(::microstrain::Buffer& serializer, const MessageFormat& self) { insert(serializer, self.function); @@ -735,7 +735,7 @@ void insert(Serializer& serializer, const MessageFormat& self) } } -void extract(Serializer& serializer, MessageFormat& self) +void extract(::microstrain::Buffer& serializer, MessageFormat& self) { extract(serializer, self.function); @@ -750,7 +750,7 @@ void extract(Serializer& serializer, MessageFormat& self) } } -void insert(Serializer& serializer, const MessageFormat::Response& self) +void insert(::microstrain::Buffer& serializer, const MessageFormat::Response& self) { insert(serializer, self.desc_set); @@ -760,7 +760,7 @@ void insert(Serializer& serializer, const MessageFormat::Response& self) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, MessageFormat::Response& self) +void extract(::microstrain::Buffer& serializer, MessageFormat::Response& self) { extract(serializer, self.desc_set); @@ -773,7 +773,7 @@ void extract(Serializer& serializer, MessageFormat::Response& self) TypedResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, descSet); @@ -786,12 +786,12 @@ TypedResult writeMessageFormat(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, descSet); @@ -799,11 +799,11 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -820,40 +820,40 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d TypedResult saveMessageFormat(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, descSet); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, descSet); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, descSet); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const NmeaPollData& self) +void insert(::microstrain::Buffer& serializer, const NmeaPollData& self) { insert(serializer, self.suppress_ack); @@ -863,7 +863,7 @@ void insert(Serializer& serializer, const NmeaPollData& self) insert(serializer, self.format_entries[i]); } -void extract(Serializer& serializer, NmeaPollData& self) +void extract(::microstrain::Buffer& serializer, NmeaPollData& self) { extract(serializer, self.suppress_ack); @@ -876,7 +876,7 @@ void extract(Serializer& serializer, NmeaPollData& self) TypedResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -888,9 +888,9 @@ TypedResult nmeaPollData(C::mip_interface& device, bool suppressAc assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_NMEA_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_NMEA_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const NmeaMessageFormat& self) +void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat& self) { insert(serializer, self.function); @@ -903,7 +903,7 @@ void insert(Serializer& serializer, const NmeaMessageFormat& self) } } -void extract(Serializer& serializer, NmeaMessageFormat& self) +void extract(::microstrain::Buffer& serializer, NmeaMessageFormat& self) { extract(serializer, self.function); @@ -916,7 +916,7 @@ void extract(Serializer& serializer, NmeaMessageFormat& self) } } -void insert(Serializer& serializer, const NmeaMessageFormat::Response& self) +void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat::Response& self) { insert(serializer, self.count); @@ -924,7 +924,7 @@ void insert(Serializer& serializer, const NmeaMessageFormat::Response& self) insert(serializer, self.format_entries[i]); } -void extract(Serializer& serializer, NmeaMessageFormat::Response& self) +void extract(::microstrain::Buffer& serializer, NmeaMessageFormat::Response& self) { C::extract_count(&serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); for(unsigned int i=0; i < self.count; i++) @@ -935,7 +935,7 @@ void extract(Serializer& serializer, NmeaMessageFormat::Response& self) TypedResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, count); @@ -946,22 +946,22 @@ TypedResult writeNmeaMessageFormat(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_NMEA_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_NMEA_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); C::extract_count(&deserializer, countOut, countOutMax); assert(formatEntriesOut || (countOut == 0)); @@ -976,39 +976,39 @@ TypedResult readNmeaMessageFormat(C::mip_interface& device, u TypedResult saveNmeaMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult loadNmeaMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultNmeaMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const DeviceSettings& self) +void insert(::microstrain::Buffer& serializer, const DeviceSettings& self) { insert(serializer, self.function); } -void extract(Serializer& serializer, DeviceSettings& self) +void extract(::microstrain::Buffer& serializer, DeviceSettings& self) { extract(serializer, self.function); @@ -1017,34 +1017,34 @@ void extract(Serializer& serializer, DeviceSettings& self) TypedResult saveDeviceSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult loadDeviceSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultDeviceSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const UartBaudrate& self) +void insert(::microstrain::Buffer& serializer, const UartBaudrate& self) { insert(serializer, self.function); @@ -1054,7 +1054,7 @@ void insert(Serializer& serializer, const UartBaudrate& self) } } -void extract(Serializer& serializer, UartBaudrate& self) +void extract(::microstrain::Buffer& serializer, UartBaudrate& self) { extract(serializer, self.function); @@ -1065,12 +1065,12 @@ void extract(Serializer& serializer, UartBaudrate& self) } } -void insert(Serializer& serializer, const UartBaudrate::Response& self) +void insert(::microstrain::Buffer& serializer, const UartBaudrate::Response& self) { insert(serializer, self.baud); } -void extract(Serializer& serializer, UartBaudrate::Response& self) +void extract(::microstrain::Buffer& serializer, UartBaudrate::Response& self) { extract(serializer, self.baud); @@ -1079,29 +1079,29 @@ void extract(Serializer& serializer, UartBaudrate::Response& self) TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, baud); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); } TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_UART_BAUDRATE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length(), REPLY_UART_BAUDRATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(baudOut); extract(deserializer, *baudOut); @@ -1114,41 +1114,41 @@ TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* b TypedResult saveUartBaudrate(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); } TypedResult loadUartBaudrate(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); } TypedResult defaultUartBaudrate(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const FactoryStreaming& self) +void insert(::microstrain::Buffer& serializer, const FactoryStreaming& self) { insert(serializer, self.action); insert(serializer, self.reserved); } -void extract(Serializer& serializer, FactoryStreaming& self) +void extract(::microstrain::Buffer& serializer, FactoryStreaming& self) { extract(serializer, self.action); @@ -1159,7 +1159,7 @@ void extract(Serializer& serializer, FactoryStreaming& self) TypedResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, action); @@ -1167,9 +1167,9 @@ TypedResult factoryStreaming(C::mip_interface& device, Factory assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const DatastreamControl& self) +void insert(::microstrain::Buffer& serializer, const DatastreamControl& self) { insert(serializer, self.function); @@ -1181,7 +1181,7 @@ void insert(Serializer& serializer, const DatastreamControl& self) } } -void extract(Serializer& serializer, DatastreamControl& self) +void extract(::microstrain::Buffer& serializer, DatastreamControl& self) { extract(serializer, self.function); @@ -1194,14 +1194,14 @@ void extract(Serializer& serializer, DatastreamControl& self) } } -void insert(Serializer& serializer, const DatastreamControl::Response& self) +void insert(::microstrain::Buffer& serializer, const DatastreamControl::Response& self) { insert(serializer, self.desc_set); insert(serializer, self.enabled); } -void extract(Serializer& serializer, DatastreamControl::Response& self) +void extract(::microstrain::Buffer& serializer, DatastreamControl::Response& self) { extract(serializer, self.desc_set); @@ -1212,7 +1212,7 @@ void extract(Serializer& serializer, DatastreamControl::Response& self) TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, descSet); @@ -1221,12 +1221,12 @@ TypedResult writeDatastreamControl(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); } TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, descSet); @@ -1234,11 +1234,11 @@ TypedResult readDatastreamControl(C::mip_interface& device, u assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_DATASTREAM_ENABLE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length(), REPLY_DATASTREAM_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -1253,40 +1253,40 @@ TypedResult readDatastreamControl(C::mip_interface& device, u TypedResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, descSet); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); } TypedResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, descSet); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); } TypedResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, descSet); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ConstellationSettings& self) +void insert(::microstrain::Buffer& serializer, const ConstellationSettings& self) { insert(serializer, self.function); @@ -1301,7 +1301,7 @@ void insert(Serializer& serializer, const ConstellationSettings& self) } } -void extract(Serializer& serializer, ConstellationSettings& self) +void extract(::microstrain::Buffer& serializer, ConstellationSettings& self) { extract(serializer, self.function); @@ -1316,7 +1316,7 @@ void extract(Serializer& serializer, ConstellationSettings& self) } } -void insert(Serializer& serializer, const ConstellationSettings::Response& self) +void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Response& self) { insert(serializer, self.max_channels_available); @@ -1328,7 +1328,7 @@ void insert(Serializer& serializer, const ConstellationSettings::Response& self) insert(serializer, self.settings[i]); } -void extract(Serializer& serializer, ConstellationSettings::Response& self) +void extract(::microstrain::Buffer& serializer, ConstellationSettings::Response& self) { extract(serializer, self.max_channels_available); @@ -1340,7 +1340,7 @@ void extract(Serializer& serializer, ConstellationSettings::Response& self) } -void insert(Serializer& serializer, const ConstellationSettings::Settings& self) +void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Settings& self) { insert(serializer, self.constellation_id); @@ -1353,7 +1353,7 @@ void insert(Serializer& serializer, const ConstellationSettings::Settings& self) insert(serializer, self.option_flags); } -void extract(Serializer& serializer, ConstellationSettings::Settings& self) +void extract(::microstrain::Buffer& serializer, ConstellationSettings::Settings& self) { extract(serializer, self.constellation_id); @@ -1370,7 +1370,7 @@ void extract(Serializer& serializer, ConstellationSettings::Settings& self) TypedResult writeConstellationSettings(C::mip_interface& device, uint16_t maxChannels, uint8_t configCount, const ConstellationSettings::Settings* settings) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, maxChannels); @@ -1383,22 +1383,22 @@ TypedResult writeConstellationSettings(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(maxChannelsAvailableOut); extract(deserializer, *maxChannelsAvailableOut); @@ -1419,34 +1419,34 @@ TypedResult readConstellationSettings(C::mip_interface& d TypedResult saveConstellationSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult loadConstellationSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultConstellationSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GnssSbasSettings& self) +void insert(::microstrain::Buffer& serializer, const GnssSbasSettings& self) { insert(serializer, self.function); @@ -1463,7 +1463,7 @@ void insert(Serializer& serializer, const GnssSbasSettings& self) } } -void extract(Serializer& serializer, GnssSbasSettings& self) +void extract(::microstrain::Buffer& serializer, GnssSbasSettings& self) { extract(serializer, self.function); @@ -1480,7 +1480,7 @@ void extract(Serializer& serializer, GnssSbasSettings& self) } } -void insert(Serializer& serializer, const GnssSbasSettings::Response& self) +void insert(::microstrain::Buffer& serializer, const GnssSbasSettings::Response& self) { insert(serializer, self.enable_sbas); @@ -1492,7 +1492,7 @@ void insert(Serializer& serializer, const GnssSbasSettings::Response& self) insert(serializer, self.included_prns[i]); } -void extract(Serializer& serializer, GnssSbasSettings::Response& self) +void extract(::microstrain::Buffer& serializer, GnssSbasSettings::Response& self) { extract(serializer, self.enable_sbas); @@ -1507,7 +1507,7 @@ void extract(Serializer& serializer, GnssSbasSettings::Response& self) TypedResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enableSbas); @@ -1522,22 +1522,22 @@ TypedResult writeGnssSbasSettings(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_SBAS_SETTINGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_SBAS_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableSbasOut); extract(deserializer, *enableSbasOut); @@ -1558,34 +1558,34 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin TypedResult saveGnssSbasSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult loadGnssSbasSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultGnssSbasSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GnssAssistedFix& self) +void insert(::microstrain::Buffer& serializer, const GnssAssistedFix& self) { insert(serializer, self.function); @@ -1597,7 +1597,7 @@ void insert(Serializer& serializer, const GnssAssistedFix& self) } } -void extract(Serializer& serializer, GnssAssistedFix& self) +void extract(::microstrain::Buffer& serializer, GnssAssistedFix& self) { extract(serializer, self.function); @@ -1610,14 +1610,14 @@ void extract(Serializer& serializer, GnssAssistedFix& self) } } -void insert(Serializer& serializer, const GnssAssistedFix::Response& self) +void insert(::microstrain::Buffer& serializer, const GnssAssistedFix::Response& self) { insert(serializer, self.option); insert(serializer, self.flags); } -void extract(Serializer& serializer, GnssAssistedFix::Response& self) +void extract(::microstrain::Buffer& serializer, GnssAssistedFix::Response& self) { extract(serializer, self.option); @@ -1628,7 +1628,7 @@ void extract(Serializer& serializer, GnssAssistedFix::Response& self) TypedResult writeGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption option, uint8_t flags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, option); @@ -1637,22 +1637,22 @@ TypedResult writeGnssAssistedFix(C::mip_interface& device, Gnss assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(optionOut); extract(deserializer, *optionOut); @@ -1668,34 +1668,34 @@ TypedResult readGnssAssistedFix(C::mip_interface& device, GnssA TypedResult saveGnssAssistedFix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult loadGnssAssistedFix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultGnssAssistedFix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GnssTimeAssistance& self) +void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance& self) { insert(serializer, self.function); @@ -1709,7 +1709,7 @@ void insert(Serializer& serializer, const GnssTimeAssistance& self) } } -void extract(Serializer& serializer, GnssTimeAssistance& self) +void extract(::microstrain::Buffer& serializer, GnssTimeAssistance& self) { extract(serializer, self.function); @@ -1724,7 +1724,7 @@ void extract(Serializer& serializer, GnssTimeAssistance& self) } } -void insert(Serializer& serializer, const GnssTimeAssistance::Response& self) +void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance::Response& self) { insert(serializer, self.tow); @@ -1733,7 +1733,7 @@ void insert(Serializer& serializer, const GnssTimeAssistance::Response& self) insert(serializer, self.accuracy); } -void extract(Serializer& serializer, GnssTimeAssistance::Response& self) +void extract(::microstrain::Buffer& serializer, GnssTimeAssistance::Response& self) { extract(serializer, self.tow); @@ -1746,7 +1746,7 @@ void extract(Serializer& serializer, GnssTimeAssistance::Response& self) TypedResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, tow); @@ -1757,22 +1757,22 @@ TypedResult writeGnssTimeAssistance(C::mip_interface& device assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)serializer.length()); } TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_TIME_ASSISTANCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)serializer.length(), REPLY_GNSS_TIME_ASSISTANCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(towOut); extract(deserializer, *towOut); @@ -1788,7 +1788,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, } return result; } -void insert(Serializer& serializer, const ImuLowpassFilter& self) +void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter& self) { insert(serializer, self.function); @@ -1806,7 +1806,7 @@ void insert(Serializer& serializer, const ImuLowpassFilter& self) } } -void extract(Serializer& serializer, ImuLowpassFilter& self) +void extract(::microstrain::Buffer& serializer, ImuLowpassFilter& self) { extract(serializer, self.function); @@ -1825,7 +1825,7 @@ void extract(Serializer& serializer, ImuLowpassFilter& self) } } -void insert(Serializer& serializer, const ImuLowpassFilter::Response& self) +void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter::Response& self) { insert(serializer, self.target_descriptor); @@ -1838,7 +1838,7 @@ void insert(Serializer& serializer, const ImuLowpassFilter::Response& self) insert(serializer, self.reserved); } -void extract(Serializer& serializer, ImuLowpassFilter::Response& self) +void extract(::microstrain::Buffer& serializer, ImuLowpassFilter::Response& self) { extract(serializer, self.target_descriptor); @@ -1855,7 +1855,7 @@ void extract(Serializer& serializer, ImuLowpassFilter::Response& self) TypedResult writeImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, targetDescriptor); @@ -1870,12 +1870,12 @@ TypedResult writeImuLowpassFilter(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, targetDescriptor); @@ -1883,11 +1883,11 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ADVANCED_DATA_FILTER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length(), REPLY_ADVANCED_DATA_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, targetDescriptor); @@ -1911,40 +1911,40 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin TypedResult saveImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, targetDescriptor); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult loadImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, targetDescriptor); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult defaultImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, targetDescriptor); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const PpsSource& self) +void insert(::microstrain::Buffer& serializer, const PpsSource& self) { insert(serializer, self.function); @@ -1954,7 +1954,7 @@ void insert(Serializer& serializer, const PpsSource& self) } } -void extract(Serializer& serializer, PpsSource& self) +void extract(::microstrain::Buffer& serializer, PpsSource& self) { extract(serializer, self.function); @@ -1965,12 +1965,12 @@ void extract(Serializer& serializer, PpsSource& self) } } -void insert(Serializer& serializer, const PpsSource::Response& self) +void insert(::microstrain::Buffer& serializer, const PpsSource::Response& self) { insert(serializer, self.source); } -void extract(Serializer& serializer, PpsSource::Response& self) +void extract(::microstrain::Buffer& serializer, PpsSource::Response& self) { extract(serializer, self.source); @@ -1979,29 +1979,29 @@ void extract(Serializer& serializer, PpsSource::Response& self) TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_PPS_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_PPS_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -2014,34 +2014,34 @@ TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source TypedResult savePpsSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult loadPpsSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult defaultPpsSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GpioConfig& self) +void insert(::microstrain::Buffer& serializer, const GpioConfig& self) { insert(serializer, self.function); @@ -2057,7 +2057,7 @@ void insert(Serializer& serializer, const GpioConfig& self) } } -void extract(Serializer& serializer, GpioConfig& self) +void extract(::microstrain::Buffer& serializer, GpioConfig& self) { extract(serializer, self.function); @@ -2074,7 +2074,7 @@ void extract(Serializer& serializer, GpioConfig& self) } } -void insert(Serializer& serializer, const GpioConfig::Response& self) +void insert(::microstrain::Buffer& serializer, const GpioConfig::Response& self) { insert(serializer, self.pin); @@ -2085,7 +2085,7 @@ void insert(Serializer& serializer, const GpioConfig::Response& self) insert(serializer, self.pin_mode); } -void extract(Serializer& serializer, GpioConfig::Response& self) +void extract(::microstrain::Buffer& serializer, GpioConfig::Response& self) { extract(serializer, self.pin); @@ -2100,7 +2100,7 @@ void extract(Serializer& serializer, GpioConfig::Response& self) TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, pin); @@ -2113,12 +2113,12 @@ TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, G assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, pin); @@ -2126,11 +2126,11 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GPIO_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_GPIO_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, pin); @@ -2151,40 +2151,40 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, pin); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, pin); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, pin); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GpioState& self) +void insert(::microstrain::Buffer& serializer, const GpioState& self) { insert(serializer, self.function); @@ -2199,7 +2199,7 @@ void insert(Serializer& serializer, const GpioState& self) } } -void extract(Serializer& serializer, GpioState& self) +void extract(::microstrain::Buffer& serializer, GpioState& self) { extract(serializer, self.function); @@ -2215,14 +2215,14 @@ void extract(Serializer& serializer, GpioState& self) } } -void insert(Serializer& serializer, const GpioState::Response& self) +void insert(::microstrain::Buffer& serializer, const GpioState::Response& self) { insert(serializer, self.pin); insert(serializer, self.state); } -void extract(Serializer& serializer, GpioState::Response& self) +void extract(::microstrain::Buffer& serializer, GpioState::Response& self) { extract(serializer, self.pin); @@ -2233,7 +2233,7 @@ void extract(Serializer& serializer, GpioState::Response& self) TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, pin); @@ -2242,12 +2242,12 @@ TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, boo assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)serializer.length()); } TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, pin); @@ -2255,11 +2255,11 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GPIO_STATE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)serializer.length(), REPLY_GPIO_STATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, pin); @@ -2271,7 +2271,7 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool } return result; } -void insert(Serializer& serializer, const Odometer& self) +void insert(::microstrain::Buffer& serializer, const Odometer& self) { insert(serializer, self.function); @@ -2285,7 +2285,7 @@ void insert(Serializer& serializer, const Odometer& self) } } -void extract(Serializer& serializer, Odometer& self) +void extract(::microstrain::Buffer& serializer, Odometer& self) { extract(serializer, self.function); @@ -2300,7 +2300,7 @@ void extract(Serializer& serializer, Odometer& self) } } -void insert(Serializer& serializer, const Odometer::Response& self) +void insert(::microstrain::Buffer& serializer, const Odometer::Response& self) { insert(serializer, self.mode); @@ -2309,7 +2309,7 @@ void insert(Serializer& serializer, const Odometer::Response& self) insert(serializer, self.uncertainty); } -void extract(Serializer& serializer, Odometer::Response& self) +void extract(::microstrain::Buffer& serializer, Odometer::Response& self) { extract(serializer, self.mode); @@ -2322,7 +2322,7 @@ void extract(Serializer& serializer, Odometer::Response& self) TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); @@ -2333,22 +2333,22 @@ TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mod assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ODOMETER_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_ODOMETER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -2367,45 +2367,45 @@ TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* mod TypedResult saveOdometer(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult loadOdometer(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult defaultOdometer(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GetEventSupport& self) +void insert(::microstrain::Buffer& serializer, const GetEventSupport& self) { insert(serializer, self.query); } -void extract(Serializer& serializer, GetEventSupport& self) +void extract(::microstrain::Buffer& serializer, GetEventSupport& self) { extract(serializer, self.query); } -void insert(Serializer& serializer, const GetEventSupport::Response& self) +void insert(::microstrain::Buffer& serializer, const GetEventSupport::Response& self) { insert(serializer, self.query); @@ -2417,7 +2417,7 @@ void insert(Serializer& serializer, const GetEventSupport::Response& self) insert(serializer, self.entries[i]); } -void extract(Serializer& serializer, GetEventSupport::Response& self) +void extract(::microstrain::Buffer& serializer, GetEventSupport::Response& self) { extract(serializer, self.query); @@ -2429,14 +2429,14 @@ void extract(Serializer& serializer, GetEventSupport::Response& self) } -void insert(Serializer& serializer, const GetEventSupport::Info& self) +void insert(::microstrain::Buffer& serializer, const GetEventSupport::Info& self) { insert(serializer, self.type); insert(serializer, self.count); } -void extract(Serializer& serializer, GetEventSupport::Info& self) +void extract(::microstrain::Buffer& serializer, GetEventSupport::Info& self) { extract(serializer, self.type); @@ -2447,18 +2447,18 @@ void extract(Serializer& serializer, GetEventSupport::Info& self) TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, query); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_SUPPORT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_SUPPORT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_SUPPORT, buffer, (uint8_t)serializer.length(), REPLY_EVENT_SUPPORT, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, query); @@ -2475,7 +2475,7 @@ TypedResult getEventSupport(C::mip_interface& device, GetEventS } return result; } -void insert(Serializer& serializer, const EventControl& self) +void insert(::microstrain::Buffer& serializer, const EventControl& self) { insert(serializer, self.function); @@ -2487,7 +2487,7 @@ void insert(Serializer& serializer, const EventControl& self) } } -void extract(Serializer& serializer, EventControl& self) +void extract(::microstrain::Buffer& serializer, EventControl& self) { extract(serializer, self.function); @@ -2500,14 +2500,14 @@ void extract(Serializer& serializer, EventControl& self) } } -void insert(Serializer& serializer, const EventControl::Response& self) +void insert(::microstrain::Buffer& serializer, const EventControl::Response& self) { insert(serializer, self.instance); insert(serializer, self.mode); } -void extract(Serializer& serializer, EventControl::Response& self) +void extract(::microstrain::Buffer& serializer, EventControl::Response& self) { extract(serializer, self.instance); @@ -2518,7 +2518,7 @@ void extract(Serializer& serializer, EventControl::Response& self) TypedResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, instance); @@ -2527,12 +2527,12 @@ TypedResult writeEventControl(C::mip_interface& device, uint8_t in assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, instance); @@ -2540,11 +2540,11 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_EVENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, instance); @@ -2559,40 +2559,40 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins TypedResult saveEventControl(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, instance); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadEventControl(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, instance); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultEventControl(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, instance); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GetEventTriggerStatus& self) +void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus& self) { insert(serializer, self.requested_count); @@ -2600,7 +2600,7 @@ void insert(Serializer& serializer, const GetEventTriggerStatus& self) insert(serializer, self.requested_instances[i]); } -void extract(Serializer& serializer, GetEventTriggerStatus& self) +void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus& self) { C::extract_count(&serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); for(unsigned int i=0; i < self.requested_count; i++) @@ -2608,7 +2608,7 @@ void extract(Serializer& serializer, GetEventTriggerStatus& self) } -void insert(Serializer& serializer, const GetEventTriggerStatus::Response& self) +void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Response& self) { insert(serializer, self.count); @@ -2616,7 +2616,7 @@ void insert(Serializer& serializer, const GetEventTriggerStatus::Response& self) insert(serializer, self.triggers[i]); } -void extract(Serializer& serializer, GetEventTriggerStatus::Response& self) +void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Response& self) { C::extract_count(&serializer, &self.count, sizeof(self.triggers)/sizeof(self.triggers[0])); for(unsigned int i=0; i < self.count; i++) @@ -2624,14 +2624,14 @@ void extract(Serializer& serializer, GetEventTriggerStatus::Response& self) } -void insert(Serializer& serializer, const GetEventTriggerStatus::Entry& self) +void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Entry& self) { insert(serializer, self.type); insert(serializer, self.status); } -void extract(Serializer& serializer, GetEventTriggerStatus::Entry& self) +void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Entry& self) { extract(serializer, self.type); @@ -2642,7 +2642,7 @@ void extract(Serializer& serializer, GetEventTriggerStatus::Entry& self) TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, requestedCount); @@ -2653,11 +2653,11 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_STATUS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_STATUS, buffer, (uint8_t)serializer.length(), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); C::extract_count(&deserializer, countOut, countOutMax); assert(triggersOut || (countOut == 0)); @@ -2669,7 +2669,7 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic } return result; } -void insert(Serializer& serializer, const GetEventActionStatus& self) +void insert(::microstrain::Buffer& serializer, const GetEventActionStatus& self) { insert(serializer, self.requested_count); @@ -2677,7 +2677,7 @@ void insert(Serializer& serializer, const GetEventActionStatus& self) insert(serializer, self.requested_instances[i]); } -void extract(Serializer& serializer, GetEventActionStatus& self) +void extract(::microstrain::Buffer& serializer, GetEventActionStatus& self) { C::extract_count(&serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); for(unsigned int i=0; i < self.requested_count; i++) @@ -2685,7 +2685,7 @@ void extract(Serializer& serializer, GetEventActionStatus& self) } -void insert(Serializer& serializer, const GetEventActionStatus::Response& self) +void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Response& self) { insert(serializer, self.count); @@ -2693,7 +2693,7 @@ void insert(Serializer& serializer, const GetEventActionStatus::Response& self) insert(serializer, self.actions[i]); } -void extract(Serializer& serializer, GetEventActionStatus::Response& self) +void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Response& self) { C::extract_count(&serializer, &self.count, sizeof(self.actions)/sizeof(self.actions[0])); for(unsigned int i=0; i < self.count; i++) @@ -2701,14 +2701,14 @@ void extract(Serializer& serializer, GetEventActionStatus::Response& self) } -void insert(Serializer& serializer, const GetEventActionStatus::Entry& self) +void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Entry& self) { insert(serializer, self.action_type); insert(serializer, self.trigger_id); } -void extract(Serializer& serializer, GetEventActionStatus::Entry& self) +void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Entry& self) { extract(serializer, self.action_type); @@ -2719,7 +2719,7 @@ void extract(Serializer& serializer, GetEventActionStatus::Entry& self) TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, requestedCount); @@ -2730,11 +2730,11 @@ TypedResult getEventActionStatus(C::mip_interface& device, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_STATUS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_ACTION_STATUS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_STATUS, buffer, (uint8_t)serializer.length(), REPLY_EVENT_ACTION_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); C::extract_count(&deserializer, countOut, countOutMax); assert(actionsOut || (countOut == 0)); @@ -2746,7 +2746,7 @@ TypedResult getEventActionStatus(C::mip_interface& device, } return result; } -void insert(Serializer& serializer, const EventTrigger& self) +void insert(::microstrain::Buffer& serializer, const EventTrigger& self) { insert(serializer, self.function); @@ -2773,7 +2773,7 @@ void insert(Serializer& serializer, const EventTrigger& self) } } } -void extract(Serializer& serializer, EventTrigger& self) +void extract(::microstrain::Buffer& serializer, EventTrigger& self) { extract(serializer, self.function); @@ -2801,7 +2801,7 @@ void extract(Serializer& serializer, EventTrigger& self) } } -void insert(Serializer& serializer, const EventTrigger::Response& self) +void insert(::microstrain::Buffer& serializer, const EventTrigger::Response& self) { insert(serializer, self.instance); @@ -2823,7 +2823,7 @@ void insert(Serializer& serializer, const EventTrigger::Response& self) } } -void extract(Serializer& serializer, EventTrigger::Response& self) +void extract(::microstrain::Buffer& serializer, EventTrigger::Response& self) { extract(serializer, self.instance); @@ -2846,14 +2846,14 @@ void extract(Serializer& serializer, EventTrigger::Response& self) } } -void insert(Serializer& serializer, const EventTrigger::GpioParams& self) +void insert(::microstrain::Buffer& serializer, const EventTrigger::GpioParams& self) { insert(serializer, self.pin); insert(serializer, self.mode); } -void extract(Serializer& serializer, EventTrigger::GpioParams& self) +void extract(::microstrain::Buffer& serializer, EventTrigger::GpioParams& self) { extract(serializer, self.pin); @@ -2861,7 +2861,7 @@ void extract(Serializer& serializer, EventTrigger::GpioParams& self) } -void insert(Serializer& serializer, const EventTrigger::ThresholdParams& self) +void insert(::microstrain::Buffer& serializer, const EventTrigger::ThresholdParams& self) { insert(serializer, self.desc_set); @@ -2892,7 +2892,7 @@ void insert(Serializer& serializer, const EventTrigger::ThresholdParams& self) } } -void extract(Serializer& serializer, EventTrigger::ThresholdParams& self) +void extract(::microstrain::Buffer& serializer, EventTrigger::ThresholdParams& self) { extract(serializer, self.desc_set); @@ -2924,7 +2924,7 @@ void extract(Serializer& serializer, EventTrigger::ThresholdParams& self) } } -void insert(Serializer& serializer, const EventTrigger::CombinationParams& self) +void insert(::microstrain::Buffer& serializer, const EventTrigger::CombinationParams& self) { insert(serializer, self.logic_table); @@ -2932,7 +2932,7 @@ void insert(Serializer& serializer, const EventTrigger::CombinationParams& self) insert(serializer, self.input_triggers[i]); } -void extract(Serializer& serializer, EventTrigger::CombinationParams& self) +void extract(::microstrain::Buffer& serializer, EventTrigger::CombinationParams& self) { extract(serializer, self.logic_table); @@ -2944,7 +2944,7 @@ void extract(Serializer& serializer, EventTrigger::CombinationParams& self) TypedResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, instance); @@ -2968,12 +2968,12 @@ TypedResult writeEventTrigger(C::mip_interface& device, uint8_t in } assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, instance); @@ -2981,11 +2981,11 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_TRIGGER_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_EVENT_TRIGGER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, instance); @@ -3015,40 +3015,40 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins TypedResult saveEventTrigger(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, instance); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult loadEventTrigger(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, instance); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, instance); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const EventAction& self) +void insert(::microstrain::Buffer& serializer, const EventAction& self) { insert(serializer, self.function); @@ -3072,7 +3072,7 @@ void insert(Serializer& serializer, const EventAction& self) } } } -void extract(Serializer& serializer, EventAction& self) +void extract(::microstrain::Buffer& serializer, EventAction& self) { extract(serializer, self.function); @@ -3097,7 +3097,7 @@ void extract(Serializer& serializer, EventAction& self) } } -void insert(Serializer& serializer, const EventAction::Response& self) +void insert(::microstrain::Buffer& serializer, const EventAction::Response& self) { insert(serializer, self.instance); @@ -3116,7 +3116,7 @@ void insert(Serializer& serializer, const EventAction::Response& self) } } -void extract(Serializer& serializer, EventAction::Response& self) +void extract(::microstrain::Buffer& serializer, EventAction::Response& self) { extract(serializer, self.instance); @@ -3136,14 +3136,14 @@ void extract(Serializer& serializer, EventAction::Response& self) } } -void insert(Serializer& serializer, const EventAction::GpioParams& self) +void insert(::microstrain::Buffer& serializer, const EventAction::GpioParams& self) { insert(serializer, self.pin); insert(serializer, self.mode); } -void extract(Serializer& serializer, EventAction::GpioParams& self) +void extract(::microstrain::Buffer& serializer, EventAction::GpioParams& self) { extract(serializer, self.pin); @@ -3151,7 +3151,7 @@ void extract(Serializer& serializer, EventAction::GpioParams& self) } -void insert(Serializer& serializer, const EventAction::MessageParams& self) +void insert(::microstrain::Buffer& serializer, const EventAction::MessageParams& self) { insert(serializer, self.desc_set); @@ -3163,7 +3163,7 @@ void insert(Serializer& serializer, const EventAction::MessageParams& self) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, EventAction::MessageParams& self) +void extract(::microstrain::Buffer& serializer, EventAction::MessageParams& self) { extract(serializer, self.desc_set); @@ -3178,7 +3178,7 @@ void extract(Serializer& serializer, EventAction::MessageParams& self) TypedResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, instance); @@ -3199,12 +3199,12 @@ TypedResult writeEventAction(C::mip_interface& device, uint8_t inst } assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, instance); @@ -3212,11 +3212,11 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_EVENT_ACTION_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_EVENT_ACTION_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, instance); @@ -3244,40 +3244,40 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta TypedResult saveEventAction(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, instance); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult loadEventAction(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, instance); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult defaultEventAction(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, instance); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AccelBias& self) +void insert(::microstrain::Buffer& serializer, const AccelBias& self) { insert(serializer, self.function); @@ -3288,7 +3288,7 @@ void insert(Serializer& serializer, const AccelBias& self) } } -void extract(Serializer& serializer, AccelBias& self) +void extract(::microstrain::Buffer& serializer, AccelBias& self) { extract(serializer, self.function); @@ -3300,13 +3300,13 @@ void extract(Serializer& serializer, AccelBias& self) } } -void insert(Serializer& serializer, const AccelBias::Response& self) +void insert(::microstrain::Buffer& serializer, const AccelBias::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); } -void extract(Serializer& serializer, AccelBias::Response& self) +void extract(::microstrain::Buffer& serializer, AccelBias::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -3316,7 +3316,7 @@ void extract(Serializer& serializer, AccelBias::Response& self) TypedResult writeAccelBias(C::mip_interface& device, const float* bias) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(bias || (3 == 0)); @@ -3325,22 +3325,22 @@ TypedResult writeAccelBias(C::mip_interface& device, const float* bia assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult readAccelBias(C::mip_interface& device, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ACCEL_BIAS_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(biasOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3354,34 +3354,34 @@ TypedResult readAccelBias(C::mip_interface& device, float* biasOut) TypedResult saveAccelBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult loadAccelBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult defaultAccelBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GyroBias& self) +void insert(::microstrain::Buffer& serializer, const GyroBias& self) { insert(serializer, self.function); @@ -3392,7 +3392,7 @@ void insert(Serializer& serializer, const GyroBias& self) } } -void extract(Serializer& serializer, GyroBias& self) +void extract(::microstrain::Buffer& serializer, GyroBias& self) { extract(serializer, self.function); @@ -3404,13 +3404,13 @@ void extract(Serializer& serializer, GyroBias& self) } } -void insert(Serializer& serializer, const GyroBias::Response& self) +void insert(::microstrain::Buffer& serializer, const GyroBias::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); } -void extract(Serializer& serializer, GyroBias::Response& self) +void extract(::microstrain::Buffer& serializer, GyroBias::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -3420,7 +3420,7 @@ void extract(Serializer& serializer, GyroBias::Response& self) TypedResult writeGyroBias(C::mip_interface& device, const float* bias) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(bias || (3 == 0)); @@ -3429,22 +3429,22 @@ TypedResult writeGyroBias(C::mip_interface& device, const float* bias) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult readGyroBias(C::mip_interface& device, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(biasOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3458,51 +3458,51 @@ TypedResult readGyroBias(C::mip_interface& device, float* biasOut) TypedResult saveGyroBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult loadGyroBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult defaultGyroBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const CaptureGyroBias& self) +void insert(::microstrain::Buffer& serializer, const CaptureGyroBias& self) { insert(serializer, self.averaging_time_ms); } -void extract(Serializer& serializer, CaptureGyroBias& self) +void extract(::microstrain::Buffer& serializer, CaptureGyroBias& self) { extract(serializer, self.averaging_time_ms); } -void insert(Serializer& serializer, const CaptureGyroBias::Response& self) +void insert(::microstrain::Buffer& serializer, const CaptureGyroBias::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); } -void extract(Serializer& serializer, CaptureGyroBias::Response& self) +void extract(::microstrain::Buffer& serializer, CaptureGyroBias::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -3512,18 +3512,18 @@ void extract(Serializer& serializer, CaptureGyroBias::Response& self) TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, averagingTimeMs); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CAPTURE_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CAPTURE_GYRO_BIAS, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(biasOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3534,7 +3534,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t } return result; } -void insert(Serializer& serializer, const MagHardIronOffset& self) +void insert(::microstrain::Buffer& serializer, const MagHardIronOffset& self) { insert(serializer, self.function); @@ -3545,7 +3545,7 @@ void insert(Serializer& serializer, const MagHardIronOffset& self) } } -void extract(Serializer& serializer, MagHardIronOffset& self) +void extract(::microstrain::Buffer& serializer, MagHardIronOffset& self) { extract(serializer, self.function); @@ -3557,13 +3557,13 @@ void extract(Serializer& serializer, MagHardIronOffset& self) } } -void insert(Serializer& serializer, const MagHardIronOffset::Response& self) +void insert(::microstrain::Buffer& serializer, const MagHardIronOffset::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset[i]); } -void extract(Serializer& serializer, MagHardIronOffset::Response& self) +void extract(::microstrain::Buffer& serializer, MagHardIronOffset::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset[i]); @@ -3573,7 +3573,7 @@ void extract(Serializer& serializer, MagHardIronOffset::Response& self) TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (3 == 0)); @@ -3582,22 +3582,22 @@ TypedResult writeMagHardIronOffset(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(offsetOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3611,34 +3611,34 @@ TypedResult readMagHardIronOffset(C::mip_interface& device, f TypedResult saveMagHardIronOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult loadMagHardIronOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagHardIronOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const MagSoftIronMatrix& self) +void insert(::microstrain::Buffer& serializer, const MagSoftIronMatrix& self) { insert(serializer, self.function); @@ -3649,7 +3649,7 @@ void insert(Serializer& serializer, const MagSoftIronMatrix& self) } } -void extract(Serializer& serializer, MagSoftIronMatrix& self) +void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix& self) { extract(serializer, self.function); @@ -3661,13 +3661,13 @@ void extract(Serializer& serializer, MagSoftIronMatrix& self) } } -void insert(Serializer& serializer, const MagSoftIronMatrix::Response& self) +void insert(::microstrain::Buffer& serializer, const MagSoftIronMatrix::Response& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.offset[i]); } -void extract(Serializer& serializer, MagSoftIronMatrix::Response& self) +void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix::Response& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.offset[i]); @@ -3677,7 +3677,7 @@ void extract(Serializer& serializer, MagSoftIronMatrix::Response& self) TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (9 == 0)); @@ -3686,22 +3686,22 @@ TypedResult writeMagSoftIronMatrix(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); } TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length(), REPLY_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(offsetOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -3715,34 +3715,34 @@ TypedResult readMagSoftIronMatrix(C::mip_interface& device, f TypedResult saveMagSoftIronMatrix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); } TypedResult loadMagSoftIronMatrix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagSoftIronMatrix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ConingScullingEnable& self) +void insert(::microstrain::Buffer& serializer, const ConingScullingEnable& self) { insert(serializer, self.function); @@ -3752,7 +3752,7 @@ void insert(Serializer& serializer, const ConingScullingEnable& self) } } -void extract(Serializer& serializer, ConingScullingEnable& self) +void extract(::microstrain::Buffer& serializer, ConingScullingEnable& self) { extract(serializer, self.function); @@ -3763,12 +3763,12 @@ void extract(Serializer& serializer, ConingScullingEnable& self) } } -void insert(Serializer& serializer, const ConingScullingEnable::Response& self) +void insert(::microstrain::Buffer& serializer, const ConingScullingEnable::Response& self) { insert(serializer, self.enable); } -void extract(Serializer& serializer, ConingScullingEnable::Response& self) +void extract(::microstrain::Buffer& serializer, ConingScullingEnable::Response& self) { extract(serializer, self.enable); @@ -3777,29 +3777,29 @@ void extract(Serializer& serializer, ConingScullingEnable::Response& self) TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); } TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length(), REPLY_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -3812,34 +3812,34 @@ TypedResult readConingScullingEnable(C::mip_interface& dev TypedResult saveConingScullingEnable(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); } TypedResult loadConingScullingEnable(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); } TypedResult defaultConingScullingEnable(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const Sensor2VehicleTransformEuler& self) +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEuler& self) { insert(serializer, self.function); @@ -3853,7 +3853,7 @@ void insert(Serializer& serializer, const Sensor2VehicleTransformEuler& self) } } -void extract(Serializer& serializer, Sensor2VehicleTransformEuler& self) +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler& self) { extract(serializer, self.function); @@ -3868,7 +3868,7 @@ void extract(Serializer& serializer, Sensor2VehicleTransformEuler& self) } } -void insert(Serializer& serializer, const Sensor2VehicleTransformEuler::Response& self) +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEuler::Response& self) { insert(serializer, self.roll); @@ -3877,7 +3877,7 @@ void insert(Serializer& serializer, const Sensor2VehicleTransformEuler::Response insert(serializer, self.yaw); } -void extract(Serializer& serializer, Sensor2VehicleTransformEuler::Response& self) +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler::Response& self) { extract(serializer, self.roll); @@ -3890,7 +3890,7 @@ void extract(Serializer& serializer, Sensor2VehicleTransformEuler::Response& sel TypedResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, roll); @@ -3901,22 +3901,22 @@ TypedResult writeSensor2VehicleTransformEuler(C::m assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); } TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(rollOut); extract(deserializer, *rollOut); @@ -3935,34 +3935,34 @@ TypedResult readSensor2VehicleTransformEuler(C::mi TypedResult saveSensor2VehicleTransformEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); } TypedResult loadSensor2VehicleTransformEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensor2VehicleTransformEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const Sensor2VehicleTransformQuaternion& self) +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformQuaternion& self) { insert(serializer, self.function); @@ -3973,7 +3973,7 @@ void insert(Serializer& serializer, const Sensor2VehicleTransformQuaternion& sel } } -void extract(Serializer& serializer, Sensor2VehicleTransformQuaternion& self) +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternion& self) { extract(serializer, self.function); @@ -3985,13 +3985,13 @@ void extract(Serializer& serializer, Sensor2VehicleTransformQuaternion& self) } } -void insert(Serializer& serializer, const Sensor2VehicleTransformQuaternion::Response& self) +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformQuaternion::Response& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.q[i]); } -void extract(Serializer& serializer, Sensor2VehicleTransformQuaternion::Response& self) +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternion::Response& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.q[i]); @@ -4001,7 +4001,7 @@ void extract(Serializer& serializer, Sensor2VehicleTransformQuaternion::Response TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(q || (4 == 0)); @@ -4010,22 +4010,22 @@ TypedResult writeSensor2VehicleTransformQuate assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); } TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(qOut || (4 == 0)); for(unsigned int i=0; i < 4; i++) @@ -4039,34 +4039,34 @@ TypedResult readSensor2VehicleTransformQuater TypedResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); } TypedResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const Sensor2VehicleTransformDcm& self) +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformDcm& self) { insert(serializer, self.function); @@ -4077,7 +4077,7 @@ void insert(Serializer& serializer, const Sensor2VehicleTransformDcm& self) } } -void extract(Serializer& serializer, Sensor2VehicleTransformDcm& self) +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm& self) { extract(serializer, self.function); @@ -4089,13 +4089,13 @@ void extract(Serializer& serializer, Sensor2VehicleTransformDcm& self) } } -void insert(Serializer& serializer, const Sensor2VehicleTransformDcm::Response& self) +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformDcm::Response& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.dcm[i]); } -void extract(Serializer& serializer, Sensor2VehicleTransformDcm::Response& self) +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm::Response& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.dcm[i]); @@ -4105,7 +4105,7 @@ void extract(Serializer& serializer, Sensor2VehicleTransformDcm::Response& self) TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(dcm || (9 == 0)); @@ -4114,22 +4114,22 @@ TypedResult writeSensor2VehicleTransformDcm(C::mip_i assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); } TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(dcmOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -4143,34 +4143,34 @@ TypedResult readSensor2VehicleTransformDcm(C::mip_in TypedResult saveSensor2VehicleTransformDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); } TypedResult loadSensor2VehicleTransformDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensor2VehicleTransformDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ComplementaryFilter& self) +void insert(::microstrain::Buffer& serializer, const ComplementaryFilter& self) { insert(serializer, self.function); @@ -4186,7 +4186,7 @@ void insert(Serializer& serializer, const ComplementaryFilter& self) } } -void extract(Serializer& serializer, ComplementaryFilter& self) +void extract(::microstrain::Buffer& serializer, ComplementaryFilter& self) { extract(serializer, self.function); @@ -4203,7 +4203,7 @@ void extract(Serializer& serializer, ComplementaryFilter& self) } } -void insert(Serializer& serializer, const ComplementaryFilter::Response& self) +void insert(::microstrain::Buffer& serializer, const ComplementaryFilter::Response& self) { insert(serializer, self.pitch_roll_enable); @@ -4214,7 +4214,7 @@ void insert(Serializer& serializer, const ComplementaryFilter::Response& self) insert(serializer, self.heading_time_constant); } -void extract(Serializer& serializer, ComplementaryFilter::Response& self) +void extract(::microstrain::Buffer& serializer, ComplementaryFilter::Response& self) { extract(serializer, self.pitch_roll_enable); @@ -4229,7 +4229,7 @@ void extract(Serializer& serializer, ComplementaryFilter::Response& self) TypedResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, pitchRollEnable); @@ -4242,22 +4242,22 @@ TypedResult writeComplementaryFilter(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_LEGACY_COMP_FILTER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length(), REPLY_LEGACY_COMP_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(pitchRollEnableOut); extract(deserializer, *pitchRollEnableOut); @@ -4279,34 +4279,34 @@ TypedResult readComplementaryFilter(C::mip_interface& devic TypedResult saveComplementaryFilter(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult loadComplementaryFilter(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult defaultComplementaryFilter(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SensorRange& self) +void insert(::microstrain::Buffer& serializer, const SensorRange& self) { insert(serializer, self.function); @@ -4318,7 +4318,7 @@ void insert(Serializer& serializer, const SensorRange& self) } } -void extract(Serializer& serializer, SensorRange& self) +void extract(::microstrain::Buffer& serializer, SensorRange& self) { extract(serializer, self.function); @@ -4331,14 +4331,14 @@ void extract(Serializer& serializer, SensorRange& self) } } -void insert(Serializer& serializer, const SensorRange::Response& self) +void insert(::microstrain::Buffer& serializer, const SensorRange::Response& self) { insert(serializer, self.sensor); insert(serializer, self.setting); } -void extract(Serializer& serializer, SensorRange::Response& self) +void extract(::microstrain::Buffer& serializer, SensorRange::Response& self) { extract(serializer, self.sensor); @@ -4349,7 +4349,7 @@ void extract(Serializer& serializer, SensorRange::Response& self) TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, sensor); @@ -4358,12 +4358,12 @@ TypedResult writeSensorRange(C::mip_interface& device, SensorRangeT assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); } TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, sensor); @@ -4371,11 +4371,11 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR_RANGE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length(), REPLY_SENSOR_RANGE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, sensor); @@ -4390,51 +4390,51 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy TypedResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, sensor); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); } TypedResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, sensor); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, sensor); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const CalibratedSensorRanges& self) +void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges& self) { insert(serializer, self.sensor); } -void extract(Serializer& serializer, CalibratedSensorRanges& self) +void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges& self) { extract(serializer, self.sensor); } -void insert(Serializer& serializer, const CalibratedSensorRanges::Response& self) +void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges::Response& self) { insert(serializer, self.sensor); @@ -4444,7 +4444,7 @@ void insert(Serializer& serializer, const CalibratedSensorRanges::Response& self insert(serializer, self.ranges[i]); } -void extract(Serializer& serializer, CalibratedSensorRanges::Response& self) +void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Response& self) { extract(serializer, self.sensor); @@ -4454,14 +4454,14 @@ void extract(Serializer& serializer, CalibratedSensorRanges::Response& self) } -void insert(Serializer& serializer, const CalibratedSensorRanges::Entry& self) +void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges::Entry& self) { insert(serializer, self.setting); insert(serializer, self.range); } -void extract(Serializer& serializer, CalibratedSensorRanges::Entry& self) +void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Entry& self) { extract(serializer, self.setting); @@ -4472,18 +4472,18 @@ void extract(Serializer& serializer, CalibratedSensorRanges::Entry& self) TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, sensor); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CALIBRATED_RANGES, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_CALIBRATED_RANGES, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CALIBRATED_RANGES, buffer, (uint8_t)serializer.length(), REPLY_CALIBRATED_RANGES, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, sensor); @@ -4497,7 +4497,7 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev } return result; } -void insert(Serializer& serializer, const LowpassFilter& self) +void insert(::microstrain::Buffer& serializer, const LowpassFilter& self) { insert(serializer, self.function); @@ -4515,7 +4515,7 @@ void insert(Serializer& serializer, const LowpassFilter& self) } } -void extract(Serializer& serializer, LowpassFilter& self) +void extract(::microstrain::Buffer& serializer, LowpassFilter& self) { extract(serializer, self.function); @@ -4534,7 +4534,7 @@ void extract(Serializer& serializer, LowpassFilter& self) } } -void insert(Serializer& serializer, const LowpassFilter::Response& self) +void insert(::microstrain::Buffer& serializer, const LowpassFilter::Response& self) { insert(serializer, self.desc_set); @@ -4547,7 +4547,7 @@ void insert(Serializer& serializer, const LowpassFilter::Response& self) insert(serializer, self.frequency); } -void extract(Serializer& serializer, LowpassFilter::Response& self) +void extract(::microstrain::Buffer& serializer, LowpassFilter::Response& self) { extract(serializer, self.desc_set); @@ -4564,7 +4564,7 @@ void extract(Serializer& serializer, LowpassFilter::Response& self) TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool enable, bool manual, float frequency) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, descSet); @@ -4579,12 +4579,12 @@ TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, descSet); @@ -4594,11 +4594,11 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_LOWPASS_FILTER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length(), REPLY_LOWPASS_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -4621,7 +4621,7 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, descSet); @@ -4630,12 +4630,12 @@ TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, descSet); @@ -4644,12 +4644,12 @@ TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, descSet); @@ -4658,7 +4658,7 @@ TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } } // namespace commands_3dm diff --git a/src/mip/definitions/commands_3dm.hpp b/src/mip/definitions/commands_3dm.hpp index a9da22541..8ca163811 100644 --- a/src/mip/definitions/commands_3dm.hpp +++ b/src/mip/definitions/commands_3dm.hpp @@ -10,7 +10,7 @@ namespace microstrain { -class Serializer; +class Buffer; } namespace mip { @@ -177,8 +177,8 @@ struct NmeaMessage uint16_t decimation = 0; ///< Decimation from the base rate for source_desc_set. Frequency is limited to 10 Hz or the base rate, whichever is lower. Must be 0 when polling. }; -void insert(Serializer& serializer, const NmeaMessage& self); -void extract(Serializer& serializer, NmeaMessage& self); +void insert(::microstrain::Buffer& serializer, const NmeaMessage& self); +void extract(::microstrain::Buffer& serializer, NmeaMessage& self); enum class SensorRangeType : uint8_t { @@ -233,8 +233,8 @@ struct PollImuMessage } typedef void Response; }; -void insert(Serializer& serializer, const PollImuMessage& self); -void extract(Serializer& serializer, PollImuMessage& self); +void insert(::microstrain::Buffer& serializer, const PollImuMessage& self); +void extract(::microstrain::Buffer& serializer, PollImuMessage& self); TypedResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); @@ -279,8 +279,8 @@ struct PollGnssMessage } typedef void Response; }; -void insert(Serializer& serializer, const PollGnssMessage& self); -void extract(Serializer& serializer, PollGnssMessage& self); +void insert(::microstrain::Buffer& serializer, const PollGnssMessage& self); +void extract(::microstrain::Buffer& serializer, PollGnssMessage& self); TypedResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); @@ -325,8 +325,8 @@ struct PollFilterMessage } typedef void Response; }; -void insert(Serializer& serializer, const PollFilterMessage& self); -void extract(Serializer& serializer, PollFilterMessage& self); +void insert(::microstrain::Buffer& serializer, const PollFilterMessage& self); +void extract(::microstrain::Buffer& serializer, PollFilterMessage& self); TypedResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); @@ -398,11 +398,11 @@ struct ImuMessageFormat } }; }; -void insert(Serializer& serializer, const ImuMessageFormat& self); -void extract(Serializer& serializer, ImuMessageFormat& self); +void insert(::microstrain::Buffer& serializer, const ImuMessageFormat& self); +void extract(::microstrain::Buffer& serializer, ImuMessageFormat& self); -void insert(Serializer& serializer, const ImuMessageFormat::Response& self); -void extract(Serializer& serializer, ImuMessageFormat::Response& self); +void insert(::microstrain::Buffer& serializer, const ImuMessageFormat::Response& self); +void extract(::microstrain::Buffer& serializer, ImuMessageFormat::Response& self); TypedResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); @@ -478,11 +478,11 @@ struct GpsMessageFormat } }; }; -void insert(Serializer& serializer, const GpsMessageFormat& self); -void extract(Serializer& serializer, GpsMessageFormat& self); +void insert(::microstrain::Buffer& serializer, const GpsMessageFormat& self); +void extract(::microstrain::Buffer& serializer, GpsMessageFormat& self); -void insert(Serializer& serializer, const GpsMessageFormat::Response& self); -void extract(Serializer& serializer, GpsMessageFormat::Response& self); +void insert(::microstrain::Buffer& serializer, const GpsMessageFormat::Response& self); +void extract(::microstrain::Buffer& serializer, GpsMessageFormat::Response& self); TypedResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); @@ -558,11 +558,11 @@ struct FilterMessageFormat } }; }; -void insert(Serializer& serializer, const FilterMessageFormat& self); -void extract(Serializer& serializer, FilterMessageFormat& self); +void insert(::microstrain::Buffer& serializer, const FilterMessageFormat& self); +void extract(::microstrain::Buffer& serializer, FilterMessageFormat& self); -void insert(Serializer& serializer, const FilterMessageFormat::Response& self); -void extract(Serializer& serializer, FilterMessageFormat::Response& self); +void insert(::microstrain::Buffer& serializer, const FilterMessageFormat::Response& self); +void extract(::microstrain::Buffer& serializer, FilterMessageFormat::Response& self); TypedResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); @@ -622,11 +622,11 @@ struct ImuGetBaseRate } }; }; -void insert(Serializer& serializer, const ImuGetBaseRate& self); -void extract(Serializer& serializer, ImuGetBaseRate& self); +void insert(::microstrain::Buffer& serializer, const ImuGetBaseRate& self); +void extract(::microstrain::Buffer& serializer, ImuGetBaseRate& self); -void insert(Serializer& serializer, const ImuGetBaseRate::Response& self); -void extract(Serializer& serializer, ImuGetBaseRate::Response& self); +void insert(::microstrain::Buffer& serializer, const ImuGetBaseRate::Response& self); +void extract(::microstrain::Buffer& serializer, ImuGetBaseRate::Response& self); TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut); @@ -682,11 +682,11 @@ struct GpsGetBaseRate } }; }; -void insert(Serializer& serializer, const GpsGetBaseRate& self); -void extract(Serializer& serializer, GpsGetBaseRate& self); +void insert(::microstrain::Buffer& serializer, const GpsGetBaseRate& self); +void extract(::microstrain::Buffer& serializer, GpsGetBaseRate& self); -void insert(Serializer& serializer, const GpsGetBaseRate::Response& self); -void extract(Serializer& serializer, GpsGetBaseRate::Response& self); +void insert(::microstrain::Buffer& serializer, const GpsGetBaseRate::Response& self); +void extract(::microstrain::Buffer& serializer, GpsGetBaseRate::Response& self); TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut); @@ -742,11 +742,11 @@ struct FilterGetBaseRate } }; }; -void insert(Serializer& serializer, const FilterGetBaseRate& self); -void extract(Serializer& serializer, FilterGetBaseRate& self); +void insert(::microstrain::Buffer& serializer, const FilterGetBaseRate& self); +void extract(::microstrain::Buffer& serializer, FilterGetBaseRate& self); -void insert(Serializer& serializer, const FilterGetBaseRate::Response& self); -void extract(Serializer& serializer, FilterGetBaseRate::Response& self); +void insert(::microstrain::Buffer& serializer, const FilterGetBaseRate::Response& self); +void extract(::microstrain::Buffer& serializer, FilterGetBaseRate::Response& self); TypedResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut); @@ -792,8 +792,8 @@ struct PollData } typedef void Response; }; -void insert(Serializer& serializer, const PollData& self); -void extract(Serializer& serializer, PollData& self); +void insert(::microstrain::Buffer& serializer, const PollData& self); +void extract(::microstrain::Buffer& serializer, PollData& self); TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors); @@ -848,11 +848,11 @@ struct GetBaseRate } }; }; -void insert(Serializer& serializer, const GetBaseRate& self); -void extract(Serializer& serializer, GetBaseRate& self); +void insert(::microstrain::Buffer& serializer, const GetBaseRate& self); +void extract(::microstrain::Buffer& serializer, GetBaseRate& self); -void insert(Serializer& serializer, const GetBaseRate::Response& self); -void extract(Serializer& serializer, GetBaseRate::Response& self); +void insert(::microstrain::Buffer& serializer, const GetBaseRate::Response& self); +void extract(::microstrain::Buffer& serializer, GetBaseRate::Response& self); TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut); @@ -927,11 +927,11 @@ struct MessageFormat } }; }; -void insert(Serializer& serializer, const MessageFormat& self); -void extract(Serializer& serializer, MessageFormat& self); +void insert(::microstrain::Buffer& serializer, const MessageFormat& self); +void extract(::microstrain::Buffer& serializer, MessageFormat& self); -void insert(Serializer& serializer, const MessageFormat::Response& self); -void extract(Serializer& serializer, MessageFormat::Response& self); +void insert(::microstrain::Buffer& serializer, const MessageFormat::Response& self); +void extract(::microstrain::Buffer& serializer, MessageFormat::Response& self); TypedResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); @@ -979,8 +979,8 @@ struct NmeaPollData } typedef void Response; }; -void insert(Serializer& serializer, const NmeaPollData& self); -void extract(Serializer& serializer, NmeaPollData& self); +void insert(::microstrain::Buffer& serializer, const NmeaPollData& self); +void extract(::microstrain::Buffer& serializer, NmeaPollData& self); TypedResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries); @@ -1050,11 +1050,11 @@ struct NmeaMessageFormat } }; }; -void insert(Serializer& serializer, const NmeaMessageFormat& self); -void extract(Serializer& serializer, NmeaMessageFormat& self); +void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat& self); +void extract(::microstrain::Buffer& serializer, NmeaMessageFormat& self); -void insert(Serializer& serializer, const NmeaMessageFormat::Response& self); -void extract(Serializer& serializer, NmeaMessageFormat::Response& self); +void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat::Response& self); +void extract(::microstrain::Buffer& serializer, NmeaMessageFormat::Response& self); TypedResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries); TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut); @@ -1111,8 +1111,8 @@ struct DeviceSettings typedef void Response; }; -void insert(Serializer& serializer, const DeviceSettings& self); -void extract(Serializer& serializer, DeviceSettings& self); +void insert(::microstrain::Buffer& serializer, const DeviceSettings& self); +void extract(::microstrain::Buffer& serializer, DeviceSettings& self); TypedResult saveDeviceSettings(C::mip_interface& device); TypedResult loadDeviceSettings(C::mip_interface& device); @@ -1196,11 +1196,11 @@ struct UartBaudrate } }; }; -void insert(Serializer& serializer, const UartBaudrate& self); -void extract(Serializer& serializer, UartBaudrate& self); +void insert(::microstrain::Buffer& serializer, const UartBaudrate& self); +void extract(::microstrain::Buffer& serializer, UartBaudrate& self); -void insert(Serializer& serializer, const UartBaudrate::Response& self); -void extract(Serializer& serializer, UartBaudrate::Response& self); +void insert(::microstrain::Buffer& serializer, const UartBaudrate::Response& self); +void extract(::microstrain::Buffer& serializer, UartBaudrate::Response& self); TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud); TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut); @@ -1251,8 +1251,8 @@ struct FactoryStreaming } typedef void Response; }; -void insert(Serializer& serializer, const FactoryStreaming& self); -void extract(Serializer& serializer, FactoryStreaming& self); +void insert(::microstrain::Buffer& serializer, const FactoryStreaming& self); +void extract(::microstrain::Buffer& serializer, FactoryStreaming& self); TypedResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved); @@ -1332,11 +1332,11 @@ struct DatastreamControl } }; }; -void insert(Serializer& serializer, const DatastreamControl& self); -void extract(Serializer& serializer, DatastreamControl& self); +void insert(::microstrain::Buffer& serializer, const DatastreamControl& self); +void extract(::microstrain::Buffer& serializer, DatastreamControl& self); -void insert(Serializer& serializer, const DatastreamControl::Response& self); -void extract(Serializer& serializer, DatastreamControl::Response& self); +void insert(::microstrain::Buffer& serializer, const DatastreamControl::Response& self); +void extract(::microstrain::Buffer& serializer, DatastreamControl::Response& self); TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable); TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut); @@ -1474,14 +1474,14 @@ struct ConstellationSettings } }; }; -void insert(Serializer& serializer, const ConstellationSettings& self); -void extract(Serializer& serializer, ConstellationSettings& self); +void insert(::microstrain::Buffer& serializer, const ConstellationSettings& self); +void extract(::microstrain::Buffer& serializer, ConstellationSettings& self); -void insert(Serializer& serializer, const ConstellationSettings::Settings& self); -void extract(Serializer& serializer, ConstellationSettings::Settings& self); +void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Settings& self); +void extract(::microstrain::Buffer& serializer, ConstellationSettings::Settings& self); -void insert(Serializer& serializer, const ConstellationSettings::Response& self); -void extract(Serializer& serializer, ConstellationSettings::Response& self); +void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Response& self); +void extract(::microstrain::Buffer& serializer, ConstellationSettings::Response& self); TypedResult writeConstellationSettings(C::mip_interface& device, uint16_t maxChannels, uint8_t configCount, const ConstellationSettings::Settings* settings); TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut); @@ -1593,11 +1593,11 @@ struct GnssSbasSettings } }; }; -void insert(Serializer& serializer, const GnssSbasSettings& self); -void extract(Serializer& serializer, GnssSbasSettings& self); +void insert(::microstrain::Buffer& serializer, const GnssSbasSettings& self); +void extract(::microstrain::Buffer& serializer, GnssSbasSettings& self); -void insert(Serializer& serializer, const GnssSbasSettings::Response& self); -void extract(Serializer& serializer, GnssSbasSettings::Response& self); +void insert(::microstrain::Buffer& serializer, const GnssSbasSettings::Response& self); +void extract(::microstrain::Buffer& serializer, GnssSbasSettings::Response& self); TypedResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns); TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut); @@ -1687,11 +1687,11 @@ struct GnssAssistedFix } }; }; -void insert(Serializer& serializer, const GnssAssistedFix& self); -void extract(Serializer& serializer, GnssAssistedFix& self); +void insert(::microstrain::Buffer& serializer, const GnssAssistedFix& self); +void extract(::microstrain::Buffer& serializer, GnssAssistedFix& self); -void insert(Serializer& serializer, const GnssAssistedFix::Response& self); -void extract(Serializer& serializer, GnssAssistedFix::Response& self); +void insert(::microstrain::Buffer& serializer, const GnssAssistedFix::Response& self); +void extract(::microstrain::Buffer& serializer, GnssAssistedFix::Response& self); TypedResult writeGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption option, uint8_t flags); TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut); @@ -1770,11 +1770,11 @@ struct GnssTimeAssistance } }; }; -void insert(Serializer& serializer, const GnssTimeAssistance& self); -void extract(Serializer& serializer, GnssTimeAssistance& self); +void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance& self); +void extract(::microstrain::Buffer& serializer, GnssTimeAssistance& self); -void insert(Serializer& serializer, const GnssTimeAssistance::Response& self); -void extract(Serializer& serializer, GnssTimeAssistance::Response& self); +void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance::Response& self); +void extract(::microstrain::Buffer& serializer, GnssTimeAssistance::Response& self); TypedResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy); TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut); @@ -1867,11 +1867,11 @@ struct ImuLowpassFilter } }; }; -void insert(Serializer& serializer, const ImuLowpassFilter& self); -void extract(Serializer& serializer, ImuLowpassFilter& self); +void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter& self); +void extract(::microstrain::Buffer& serializer, ImuLowpassFilter& self); -void insert(Serializer& serializer, const ImuLowpassFilter::Response& self); -void extract(Serializer& serializer, ImuLowpassFilter::Response& self); +void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter::Response& self); +void extract(::microstrain::Buffer& serializer, ImuLowpassFilter::Response& self); TypedResult writeImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved); TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut); @@ -1952,11 +1952,11 @@ struct PpsSource } }; }; -void insert(Serializer& serializer, const PpsSource& self); -void extract(Serializer& serializer, PpsSource& self); +void insert(::microstrain::Buffer& serializer, const PpsSource& self); +void extract(::microstrain::Buffer& serializer, PpsSource& self); -void insert(Serializer& serializer, const PpsSource::Response& self); -void extract(Serializer& serializer, PpsSource::Response& self); +void insert(::microstrain::Buffer& serializer, const PpsSource::Response& self); +void extract(::microstrain::Buffer& serializer, PpsSource::Response& self); TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source); TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut); @@ -2111,11 +2111,11 @@ struct GpioConfig } }; }; -void insert(Serializer& serializer, const GpioConfig& self); -void extract(Serializer& serializer, GpioConfig& self); +void insert(::microstrain::Buffer& serializer, const GpioConfig& self); +void extract(::microstrain::Buffer& serializer, GpioConfig& self); -void insert(Serializer& serializer, const GpioConfig::Response& self); -void extract(Serializer& serializer, GpioConfig::Response& self); +void insert(::microstrain::Buffer& serializer, const GpioConfig::Response& self); +void extract(::microstrain::Buffer& serializer, GpioConfig::Response& self); TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode); TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut); @@ -2204,11 +2204,11 @@ struct GpioState } }; }; -void insert(Serializer& serializer, const GpioState& self); -void extract(Serializer& serializer, GpioState& self); +void insert(::microstrain::Buffer& serializer, const GpioState& self); +void extract(::microstrain::Buffer& serializer, GpioState& self); -void insert(Serializer& serializer, const GpioState::Response& self); -void extract(Serializer& serializer, GpioState::Response& self); +void insert(::microstrain::Buffer& serializer, const GpioState::Response& self); +void extract(::microstrain::Buffer& serializer, GpioState::Response& self); TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state); TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut); @@ -2288,11 +2288,11 @@ struct Odometer } }; }; -void insert(Serializer& serializer, const Odometer& self); -void extract(Serializer& serializer, Odometer& self); +void insert(::microstrain::Buffer& serializer, const Odometer& self); +void extract(::microstrain::Buffer& serializer, Odometer& self); -void insert(Serializer& serializer, const Odometer::Response& self); -void extract(Serializer& serializer, Odometer::Response& self); +void insert(::microstrain::Buffer& serializer, const Odometer::Response& self); +void extract(::microstrain::Buffer& serializer, Odometer::Response& self); TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty); TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut); @@ -2381,14 +2381,14 @@ struct GetEventSupport } }; }; -void insert(Serializer& serializer, const GetEventSupport& self); -void extract(Serializer& serializer, GetEventSupport& self); +void insert(::microstrain::Buffer& serializer, const GetEventSupport& self); +void extract(::microstrain::Buffer& serializer, GetEventSupport& self); -void insert(Serializer& serializer, const GetEventSupport::Info& self); -void extract(Serializer& serializer, GetEventSupport::Info& self); +void insert(::microstrain::Buffer& serializer, const GetEventSupport::Info& self); +void extract(::microstrain::Buffer& serializer, GetEventSupport::Info& self); -void insert(Serializer& serializer, const GetEventSupport::Response& self); -void extract(Serializer& serializer, GetEventSupport::Response& self); +void insert(::microstrain::Buffer& serializer, const GetEventSupport::Response& self); +void extract(::microstrain::Buffer& serializer, GetEventSupport::Response& self); TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut); @@ -2476,11 +2476,11 @@ struct EventControl } }; }; -void insert(Serializer& serializer, const EventControl& self); -void extract(Serializer& serializer, EventControl& self); +void insert(::microstrain::Buffer& serializer, const EventControl& self); +void extract(::microstrain::Buffer& serializer, EventControl& self); -void insert(Serializer& serializer, const EventControl::Response& self); -void extract(Serializer& serializer, EventControl::Response& self); +void insert(::microstrain::Buffer& serializer, const EventControl::Response& self); +void extract(::microstrain::Buffer& serializer, EventControl::Response& self); TypedResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode); TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut); @@ -2576,14 +2576,14 @@ struct GetEventTriggerStatus } }; }; -void insert(Serializer& serializer, const GetEventTriggerStatus& self); -void extract(Serializer& serializer, GetEventTriggerStatus& self); +void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus& self); +void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus& self); -void insert(Serializer& serializer, const GetEventTriggerStatus::Entry& self); -void extract(Serializer& serializer, GetEventTriggerStatus::Entry& self); +void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Entry& self); +void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Entry& self); -void insert(Serializer& serializer, const GetEventTriggerStatus::Response& self); -void extract(Serializer& serializer, GetEventTriggerStatus::Response& self); +void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Response& self); +void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Response& self); TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut); @@ -2644,14 +2644,14 @@ struct GetEventActionStatus } }; }; -void insert(Serializer& serializer, const GetEventActionStatus& self); -void extract(Serializer& serializer, GetEventActionStatus& self); +void insert(::microstrain::Buffer& serializer, const GetEventActionStatus& self); +void extract(::microstrain::Buffer& serializer, GetEventActionStatus& self); -void insert(Serializer& serializer, const GetEventActionStatus::Entry& self); -void extract(Serializer& serializer, GetEventActionStatus::Entry& self); +void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Entry& self); +void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Entry& self); -void insert(Serializer& serializer, const GetEventActionStatus::Response& self); -void extract(Serializer& serializer, GetEventActionStatus::Response& self); +void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Response& self); +void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Response& self); TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut); @@ -2797,20 +2797,20 @@ struct EventTrigger } }; }; -void insert(Serializer& serializer, const EventTrigger& self); -void extract(Serializer& serializer, EventTrigger& self); +void insert(::microstrain::Buffer& serializer, const EventTrigger& self); +void extract(::microstrain::Buffer& serializer, EventTrigger& self); -void insert(Serializer& serializer, const EventTrigger::GpioParams& self); -void extract(Serializer& serializer, EventTrigger::GpioParams& self); +void insert(::microstrain::Buffer& serializer, const EventTrigger::GpioParams& self); +void extract(::microstrain::Buffer& serializer, EventTrigger::GpioParams& self); -void insert(Serializer& serializer, const EventTrigger::ThresholdParams& self); -void extract(Serializer& serializer, EventTrigger::ThresholdParams& self); +void insert(::microstrain::Buffer& serializer, const EventTrigger::ThresholdParams& self); +void extract(::microstrain::Buffer& serializer, EventTrigger::ThresholdParams& self); -void insert(Serializer& serializer, const EventTrigger::CombinationParams& self); -void extract(Serializer& serializer, EventTrigger::CombinationParams& self); +void insert(::microstrain::Buffer& serializer, const EventTrigger::CombinationParams& self); +void extract(::microstrain::Buffer& serializer, EventTrigger::CombinationParams& self); -void insert(Serializer& serializer, const EventTrigger::Response& self); -void extract(Serializer& serializer, EventTrigger::Response& self); +void insert(::microstrain::Buffer& serializer, const EventTrigger::Response& self); +void extract(::microstrain::Buffer& serializer, EventTrigger::Response& self); TypedResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters); TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut); @@ -2927,17 +2927,17 @@ struct EventAction } }; }; -void insert(Serializer& serializer, const EventAction& self); -void extract(Serializer& serializer, EventAction& self); +void insert(::microstrain::Buffer& serializer, const EventAction& self); +void extract(::microstrain::Buffer& serializer, EventAction& self); -void insert(Serializer& serializer, const EventAction::GpioParams& self); -void extract(Serializer& serializer, EventAction::GpioParams& self); +void insert(::microstrain::Buffer& serializer, const EventAction::GpioParams& self); +void extract(::microstrain::Buffer& serializer, EventAction::GpioParams& self); -void insert(Serializer& serializer, const EventAction::MessageParams& self); -void extract(Serializer& serializer, EventAction::MessageParams& self); +void insert(::microstrain::Buffer& serializer, const EventAction::MessageParams& self); +void extract(::microstrain::Buffer& serializer, EventAction::MessageParams& self); -void insert(Serializer& serializer, const EventAction::Response& self); -void extract(Serializer& serializer, EventAction::Response& self); +void insert(::microstrain::Buffer& serializer, const EventAction::Response& self); +void extract(::microstrain::Buffer& serializer, EventAction::Response& self); TypedResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters); TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut); @@ -3011,11 +3011,11 @@ struct AccelBias } }; }; -void insert(Serializer& serializer, const AccelBias& self); -void extract(Serializer& serializer, AccelBias& self); +void insert(::microstrain::Buffer& serializer, const AccelBias& self); +void extract(::microstrain::Buffer& serializer, AccelBias& self); -void insert(Serializer& serializer, const AccelBias::Response& self); -void extract(Serializer& serializer, AccelBias::Response& self); +void insert(::microstrain::Buffer& serializer, const AccelBias::Response& self); +void extract(::microstrain::Buffer& serializer, AccelBias::Response& self); TypedResult writeAccelBias(C::mip_interface& device, const float* bias); TypedResult readAccelBias(C::mip_interface& device, float* biasOut); @@ -3089,11 +3089,11 @@ struct GyroBias } }; }; -void insert(Serializer& serializer, const GyroBias& self); -void extract(Serializer& serializer, GyroBias& self); +void insert(::microstrain::Buffer& serializer, const GyroBias& self); +void extract(::microstrain::Buffer& serializer, GyroBias& self); -void insert(Serializer& serializer, const GyroBias::Response& self); -void extract(Serializer& serializer, GyroBias::Response& self); +void insert(::microstrain::Buffer& serializer, const GyroBias::Response& self); +void extract(::microstrain::Buffer& serializer, GyroBias::Response& self); TypedResult writeGyroBias(C::mip_interface& device, const float* bias); TypedResult readGyroBias(C::mip_interface& device, float* biasOut); @@ -3156,11 +3156,11 @@ struct CaptureGyroBias } }; }; -void insert(Serializer& serializer, const CaptureGyroBias& self); -void extract(Serializer& serializer, CaptureGyroBias& self); +void insert(::microstrain::Buffer& serializer, const CaptureGyroBias& self); +void extract(::microstrain::Buffer& serializer, CaptureGyroBias& self); -void insert(Serializer& serializer, const CaptureGyroBias::Response& self); -void extract(Serializer& serializer, CaptureGyroBias::Response& self); +void insert(::microstrain::Buffer& serializer, const CaptureGyroBias::Response& self); +void extract(::microstrain::Buffer& serializer, CaptureGyroBias::Response& self); TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut); @@ -3234,11 +3234,11 @@ struct MagHardIronOffset } }; }; -void insert(Serializer& serializer, const MagHardIronOffset& self); -void extract(Serializer& serializer, MagHardIronOffset& self); +void insert(::microstrain::Buffer& serializer, const MagHardIronOffset& self); +void extract(::microstrain::Buffer& serializer, MagHardIronOffset& self); -void insert(Serializer& serializer, const MagHardIronOffset::Response& self); -void extract(Serializer& serializer, MagHardIronOffset::Response& self); +void insert(::microstrain::Buffer& serializer, const MagHardIronOffset::Response& self); +void extract(::microstrain::Buffer& serializer, MagHardIronOffset::Response& self); TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset); TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut); @@ -3320,11 +3320,11 @@ struct MagSoftIronMatrix } }; }; -void insert(Serializer& serializer, const MagSoftIronMatrix& self); -void extract(Serializer& serializer, MagSoftIronMatrix& self); +void insert(::microstrain::Buffer& serializer, const MagSoftIronMatrix& self); +void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix& self); -void insert(Serializer& serializer, const MagSoftIronMatrix::Response& self); -void extract(Serializer& serializer, MagSoftIronMatrix::Response& self); +void insert(::microstrain::Buffer& serializer, const MagSoftIronMatrix::Response& self); +void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix::Response& self); TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset); TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut); @@ -3396,11 +3396,11 @@ struct ConingScullingEnable } }; }; -void insert(Serializer& serializer, const ConingScullingEnable& self); -void extract(Serializer& serializer, ConingScullingEnable& self); +void insert(::microstrain::Buffer& serializer, const ConingScullingEnable& self); +void extract(::microstrain::Buffer& serializer, ConingScullingEnable& self); -void insert(Serializer& serializer, const ConingScullingEnable::Response& self); -void extract(Serializer& serializer, ConingScullingEnable::Response& self); +void insert(::microstrain::Buffer& serializer, const ConingScullingEnable::Response& self); +void extract(::microstrain::Buffer& serializer, ConingScullingEnable::Response& self); TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable); TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut); @@ -3500,11 +3500,11 @@ struct Sensor2VehicleTransformEuler } }; }; -void insert(Serializer& serializer, const Sensor2VehicleTransformEuler& self); -void extract(Serializer& serializer, Sensor2VehicleTransformEuler& self); +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEuler& self); +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler& self); -void insert(Serializer& serializer, const Sensor2VehicleTransformEuler::Response& self); -void extract(Serializer& serializer, Sensor2VehicleTransformEuler::Response& self); +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEuler::Response& self); +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler::Response& self); TypedResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw); TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut); @@ -3608,11 +3608,11 @@ struct Sensor2VehicleTransformQuaternion } }; }; -void insert(Serializer& serializer, const Sensor2VehicleTransformQuaternion& self); -void extract(Serializer& serializer, Sensor2VehicleTransformQuaternion& self); +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformQuaternion& self); +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternion& self); -void insert(Serializer& serializer, const Sensor2VehicleTransformQuaternion::Response& self); -void extract(Serializer& serializer, Sensor2VehicleTransformQuaternion::Response& self); +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformQuaternion::Response& self); +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternion::Response& self); TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q); TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut); @@ -3714,11 +3714,11 @@ struct Sensor2VehicleTransformDcm } }; }; -void insert(Serializer& serializer, const Sensor2VehicleTransformDcm& self); -void extract(Serializer& serializer, Sensor2VehicleTransformDcm& self); +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformDcm& self); +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm& self); -void insert(Serializer& serializer, const Sensor2VehicleTransformDcm::Response& self); -void extract(Serializer& serializer, Sensor2VehicleTransformDcm::Response& self); +void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformDcm::Response& self); +void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm::Response& self); TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm); TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut); @@ -3800,11 +3800,11 @@ struct ComplementaryFilter } }; }; -void insert(Serializer& serializer, const ComplementaryFilter& self); -void extract(Serializer& serializer, ComplementaryFilter& self); +void insert(::microstrain::Buffer& serializer, const ComplementaryFilter& self); +void extract(::microstrain::Buffer& serializer, ComplementaryFilter& self); -void insert(Serializer& serializer, const ComplementaryFilter::Response& self); -void extract(Serializer& serializer, ComplementaryFilter::Response& self); +void insert(::microstrain::Buffer& serializer, const ComplementaryFilter::Response& self); +void extract(::microstrain::Buffer& serializer, ComplementaryFilter::Response& self); TypedResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant); TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut); @@ -3886,11 +3886,11 @@ struct SensorRange } }; }; -void insert(Serializer& serializer, const SensorRange& self); -void extract(Serializer& serializer, SensorRange& self); +void insert(::microstrain::Buffer& serializer, const SensorRange& self); +void extract(::microstrain::Buffer& serializer, SensorRange& self); -void insert(Serializer& serializer, const SensorRange::Response& self); -void extract(Serializer& serializer, SensorRange::Response& self); +void insert(::microstrain::Buffer& serializer, const SensorRange::Response& self); +void extract(::microstrain::Buffer& serializer, SensorRange::Response& self); TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting); TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut); @@ -3959,14 +3959,14 @@ struct CalibratedSensorRanges } }; }; -void insert(Serializer& serializer, const CalibratedSensorRanges& self); -void extract(Serializer& serializer, CalibratedSensorRanges& self); +void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges& self); +void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges& self); -void insert(Serializer& serializer, const CalibratedSensorRanges::Entry& self); -void extract(Serializer& serializer, CalibratedSensorRanges::Entry& self); +void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges::Entry& self); +void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Entry& self); -void insert(Serializer& serializer, const CalibratedSensorRanges::Response& self); -void extract(Serializer& serializer, CalibratedSensorRanges::Response& self); +void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges::Response& self); +void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Response& self); TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut); @@ -4057,11 +4057,11 @@ struct LowpassFilter } }; }; -void insert(Serializer& serializer, const LowpassFilter& self); -void extract(Serializer& serializer, LowpassFilter& self); +void insert(::microstrain::Buffer& serializer, const LowpassFilter& self); +void extract(::microstrain::Buffer& serializer, LowpassFilter& self); -void insert(Serializer& serializer, const LowpassFilter::Response& self); -void extract(Serializer& serializer, LowpassFilter::Response& self); +void insert(::microstrain::Buffer& serializer, const LowpassFilter::Response& self); +void extract(::microstrain::Buffer& serializer, LowpassFilter::Response& self); TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool enable, bool manual, float frequency); TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut); diff --git a/src/mip/definitions/commands_aiding.cpp b/src/mip/definitions/commands_aiding.cpp index 739a6baf6..6b1505cc7 100644 --- a/src/mip/definitions/commands_aiding.cpp +++ b/src/mip/definitions/commands_aiding.cpp @@ -1,14 +1,14 @@ #include "commands_aiding.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -24,7 +24,7 @@ using namespace ::mip::C; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const Time& self) +void insert(::microstrain::Buffer& serializer, const Time& self) { insert(serializer, self.timebase); @@ -33,7 +33,7 @@ void insert(Serializer& serializer, const Time& self) insert(serializer, self.nanoseconds); } -void extract(Serializer& serializer, Time& self) +void extract(::microstrain::Buffer& serializer, Time& self) { extract(serializer, self.timebase); @@ -48,7 +48,7 @@ void extract(Serializer& serializer, Time& self) // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const FrameConfig& self) +void insert(::microstrain::Buffer& serializer, const FrameConfig& self) { insert(serializer, self.function); @@ -78,7 +78,7 @@ void insert(Serializer& serializer, const FrameConfig& self) } } } -void extract(Serializer& serializer, FrameConfig& self) +void extract(::microstrain::Buffer& serializer, FrameConfig& self) { extract(serializer, self.function); @@ -109,7 +109,7 @@ void extract(Serializer& serializer, FrameConfig& self) } } -void insert(Serializer& serializer, const FrameConfig::Response& self) +void insert(::microstrain::Buffer& serializer, const FrameConfig::Response& self) { insert(serializer, self.frame_id); @@ -131,7 +131,7 @@ void insert(Serializer& serializer, const FrameConfig::Response& self) } } -void extract(Serializer& serializer, FrameConfig::Response& self) +void extract(::microstrain::Buffer& serializer, FrameConfig::Response& self) { extract(serializer, self.frame_id); @@ -157,7 +157,7 @@ void extract(Serializer& serializer, FrameConfig::Response& self) TypedResult writeFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool trackingEnabled, const float* translation, const FrameConfig::Rotation& rotation) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, frameId); @@ -182,12 +182,12 @@ TypedResult writeFrameConfig(C::mip_interface& device, uint8_t fram } assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, frameId); @@ -197,11 +197,11 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_FRAME_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_FRAME_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, frameId); @@ -232,40 +232,40 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frameId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, frameId); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frameId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, frameId); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t frameId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, frameId); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AidingEchoControl& self) +void insert(::microstrain::Buffer& serializer, const AidingEchoControl& self) { insert(serializer, self.function); @@ -275,7 +275,7 @@ void insert(Serializer& serializer, const AidingEchoControl& self) } } -void extract(Serializer& serializer, AidingEchoControl& self) +void extract(::microstrain::Buffer& serializer, AidingEchoControl& self) { extract(serializer, self.function); @@ -286,12 +286,12 @@ void extract(Serializer& serializer, AidingEchoControl& self) } } -void insert(Serializer& serializer, const AidingEchoControl::Response& self) +void insert(::microstrain::Buffer& serializer, const AidingEchoControl::Response& self) { insert(serializer, self.mode); } -void extract(Serializer& serializer, AidingEchoControl::Response& self) +void extract(::microstrain::Buffer& serializer, AidingEchoControl::Response& self) { extract(serializer, self.mode); @@ -300,29 +300,29 @@ void extract(Serializer& serializer, AidingEchoControl::Response& self) TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ECHO_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -335,34 +335,34 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A TypedResult saveAidingEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAidingEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAidingEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const EcefPos& self) +void insert(::microstrain::Buffer& serializer, const EcefPos& self) { insert(serializer, self.time); @@ -377,7 +377,7 @@ void insert(Serializer& serializer, const EcefPos& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, EcefPos& self) +void extract(::microstrain::Buffer& serializer, EcefPos& self) { extract(serializer, self.time); @@ -396,7 +396,7 @@ void extract(Serializer& serializer, EcefPos& self) TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -414,9 +414,9 @@ TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const LlhPos& self) +void insert(::microstrain::Buffer& serializer, const LlhPos& self) { insert(serializer, self.time); @@ -434,7 +434,7 @@ void insert(Serializer& serializer, const LlhPos& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, LlhPos& self) +void extract(::microstrain::Buffer& serializer, LlhPos& self) { extract(serializer, self.time); @@ -456,7 +456,7 @@ void extract(Serializer& serializer, LlhPos& self) TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -476,9 +476,9 @@ TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const Height& self) +void insert(::microstrain::Buffer& serializer, const Height& self) { insert(serializer, self.time); @@ -491,7 +491,7 @@ void insert(Serializer& serializer, const Height& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, Height& self) +void extract(::microstrain::Buffer& serializer, Height& self) { extract(serializer, self.time); @@ -508,7 +508,7 @@ void extract(Serializer& serializer, Height& self) TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -522,9 +522,9 @@ TypedResult height(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABS, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const EcefVel& self) +void insert(::microstrain::Buffer& serializer, const EcefVel& self) { insert(serializer, self.time); @@ -539,7 +539,7 @@ void insert(Serializer& serializer, const EcefVel& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, EcefVel& self) +void extract(::microstrain::Buffer& serializer, EcefVel& self) { extract(serializer, self.time); @@ -558,7 +558,7 @@ void extract(Serializer& serializer, EcefVel& self) TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -576,9 +576,9 @@ TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const NedVel& self) +void insert(::microstrain::Buffer& serializer, const NedVel& self) { insert(serializer, self.time); @@ -593,7 +593,7 @@ void insert(Serializer& serializer, const NedVel& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, NedVel& self) +void extract(::microstrain::Buffer& serializer, NedVel& self) { extract(serializer, self.time); @@ -612,7 +612,7 @@ void extract(Serializer& serializer, NedVel& self) TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -630,9 +630,9 @@ TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const VehicleFixedFrameVelocity& self) +void insert(::microstrain::Buffer& serializer, const VehicleFixedFrameVelocity& self) { insert(serializer, self.time); @@ -647,7 +647,7 @@ void insert(Serializer& serializer, const VehicleFixedFrameVelocity& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, VehicleFixedFrameVelocity& self) +void extract(::microstrain::Buffer& serializer, VehicleFixedFrameVelocity& self) { extract(serializer, self.time); @@ -666,7 +666,7 @@ void extract(Serializer& serializer, VehicleFixedFrameVelocity& self) TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -684,9 +684,9 @@ TypedResult vehicleFixedFrameVelocity(C::mip_interfac assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ODOM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ODOM, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const TrueHeading& self) +void insert(::microstrain::Buffer& serializer, const TrueHeading& self) { insert(serializer, self.time); @@ -699,7 +699,7 @@ void insert(Serializer& serializer, const TrueHeading& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, TrueHeading& self) +void extract(::microstrain::Buffer& serializer, TrueHeading& self) { extract(serializer, self.time); @@ -716,7 +716,7 @@ void extract(Serializer& serializer, TrueHeading& self) TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -730,9 +730,9 @@ TypedResult trueHeading(C::mip_interface& device, const Time& time, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_TRUE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_TRUE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const MagneticField& self) +void insert(::microstrain::Buffer& serializer, const MagneticField& self) { insert(serializer, self.time); @@ -747,7 +747,7 @@ void insert(Serializer& serializer, const MagneticField& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagneticField& self) +void extract(::microstrain::Buffer& serializer, MagneticField& self) { extract(serializer, self.time); @@ -766,7 +766,7 @@ void extract(Serializer& serializer, MagneticField& self) TypedResult magneticField(C::mip_interface& device, const Time& time, uint8_t frameId, const float* magneticField, const float* uncertainty, MagneticField::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -784,9 +784,9 @@ TypedResult magneticField(C::mip_interface& device, const Time& t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_FIELD, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_FIELD, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const Pressure& self) +void insert(::microstrain::Buffer& serializer, const Pressure& self) { insert(serializer, self.time); @@ -799,7 +799,7 @@ void insert(Serializer& serializer, const Pressure& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, Pressure& self) +void extract(::microstrain::Buffer& serializer, Pressure& self) { extract(serializer, self.time); @@ -816,7 +816,7 @@ void extract(Serializer& serializer, Pressure& self) TypedResult pressure(C::mip_interface& device, const Time& time, uint8_t frameId, float pressure, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -830,7 +830,7 @@ TypedResult pressure(C::mip_interface& device, const Time& time, uint8 assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE, buffer, (uint8_t)serializer.length()); } } // namespace commands_aiding diff --git a/src/mip/definitions/commands_aiding.hpp b/src/mip/definitions/commands_aiding.hpp index 85ef6e274..be1d6d877 100644 --- a/src/mip/definitions/commands_aiding.hpp +++ b/src/mip/definitions/commands_aiding.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -73,8 +73,8 @@ struct Time uint64_t nanoseconds = 0; ///< Nanoseconds since the timebase epoch. }; -void insert(Serializer& serializer, const Time& self); -void extract(Serializer& serializer, Time& self); +void insert(::microstrain::Buffer& serializer, const Time& self); +void extract(::microstrain::Buffer& serializer, Time& self); //////////////////////////////////////////////////////////////////////////////// @@ -188,11 +188,11 @@ struct FrameConfig } }; }; -void insert(Serializer& serializer, const FrameConfig& self); -void extract(Serializer& serializer, FrameConfig& self); +void insert(::microstrain::Buffer& serializer, const FrameConfig& self); +void extract(::microstrain::Buffer& serializer, FrameConfig& self); -void insert(Serializer& serializer, const FrameConfig::Response& self); -void extract(Serializer& serializer, FrameConfig::Response& self); +void insert(::microstrain::Buffer& serializer, const FrameConfig::Response& self); +void extract(::microstrain::Buffer& serializer, FrameConfig::Response& self); TypedResult writeFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool trackingEnabled, const float* translation, const FrameConfig::Rotation& rotation); TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut); @@ -271,11 +271,11 @@ struct AidingEchoControl } }; }; -void insert(Serializer& serializer, const AidingEchoControl& self); -void extract(Serializer& serializer, AidingEchoControl& self); +void insert(::microstrain::Buffer& serializer, const AidingEchoControl& self); +void extract(::microstrain::Buffer& serializer, AidingEchoControl& self); -void insert(Serializer& serializer, const AidingEchoControl::Response& self); -void extract(Serializer& serializer, AidingEchoControl::Response& self); +void insert(::microstrain::Buffer& serializer, const AidingEchoControl::Response& self); +void extract(::microstrain::Buffer& serializer, AidingEchoControl::Response& self); TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode); TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut); @@ -350,8 +350,8 @@ struct EcefPos } typedef void Response; }; -void insert(Serializer& serializer, const EcefPos& self); -void extract(Serializer& serializer, EcefPos& self); +void insert(::microstrain::Buffer& serializer, const EcefPos& self); +void extract(::microstrain::Buffer& serializer, EcefPos& self); TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags); @@ -425,8 +425,8 @@ struct LlhPos } typedef void Response; }; -void insert(Serializer& serializer, const LlhPos& self); -void extract(Serializer& serializer, LlhPos& self); +void insert(::microstrain::Buffer& serializer, const LlhPos& self); +void extract(::microstrain::Buffer& serializer, LlhPos& self); TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags); @@ -466,8 +466,8 @@ struct Height } typedef void Response; }; -void insert(Serializer& serializer, const Height& self); -void extract(Serializer& serializer, Height& self); +void insert(::microstrain::Buffer& serializer, const Height& self); +void extract(::microstrain::Buffer& serializer, Height& self); TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags); @@ -538,8 +538,8 @@ struct EcefVel } typedef void Response; }; -void insert(Serializer& serializer, const EcefVel& self); -void extract(Serializer& serializer, EcefVel& self); +void insert(::microstrain::Buffer& serializer, const EcefVel& self); +void extract(::microstrain::Buffer& serializer, EcefVel& self); TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags); @@ -610,8 +610,8 @@ struct NedVel } typedef void Response; }; -void insert(Serializer& serializer, const NedVel& self); -void extract(Serializer& serializer, NedVel& self); +void insert(::microstrain::Buffer& serializer, const NedVel& self); +void extract(::microstrain::Buffer& serializer, NedVel& self); TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags); @@ -683,8 +683,8 @@ struct VehicleFixedFrameVelocity } typedef void Response; }; -void insert(Serializer& serializer, const VehicleFixedFrameVelocity& self); -void extract(Serializer& serializer, VehicleFixedFrameVelocity& self); +void insert(::microstrain::Buffer& serializer, const VehicleFixedFrameVelocity& self); +void extract(::microstrain::Buffer& serializer, VehicleFixedFrameVelocity& self); TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags); @@ -723,8 +723,8 @@ struct TrueHeading } typedef void Response; }; -void insert(Serializer& serializer, const TrueHeading& self); -void extract(Serializer& serializer, TrueHeading& self); +void insert(::microstrain::Buffer& serializer, const TrueHeading& self); +void extract(::microstrain::Buffer& serializer, TrueHeading& self); TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); @@ -795,8 +795,8 @@ struct MagneticField } typedef void Response; }; -void insert(Serializer& serializer, const MagneticField& self); -void extract(Serializer& serializer, MagneticField& self); +void insert(::microstrain::Buffer& serializer, const MagneticField& self); +void extract(::microstrain::Buffer& serializer, MagneticField& self); TypedResult magneticField(C::mip_interface& device, const Time& time, uint8_t frameId, const float* magneticField, const float* uncertainty, MagneticField::ValidFlags validFlags); @@ -836,8 +836,8 @@ struct Pressure } typedef void Response; }; -void insert(Serializer& serializer, const Pressure& self); -void extract(Serializer& serializer, Pressure& self); +void insert(::microstrain::Buffer& serializer, const Pressure& self); +void extract(::microstrain::Buffer& serializer, Pressure& self); TypedResult pressure(C::mip_interface& device, const Time& time, uint8_t frameId, float pressure, float uncertainty, uint16_t validFlags); diff --git a/src/mip/definitions/commands_base.cpp b/src/mip/definitions/commands_base.cpp index 1190f9486..0a7748b1e 100644 --- a/src/mip/definitions/commands_base.cpp +++ b/src/mip/definitions/commands_base.cpp @@ -1,30 +1,29 @@ #include "commands_base.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; - namespace C { struct mip_interface; } // namespace C namespace commands_base { -using ::mip::insert; -using ::mip::extract; +using ::microstrain::Buffer; +using ::microstrain::insert; +using ::microstrain::extract; using namespace ::mip::C; //////////////////////////////////////////////////////////////////////////////// // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const BaseDeviceInfo& self) +void insert(::microstrain::Buffer& serializer, const BaseDeviceInfo& self) { insert(serializer, self.firmware_version); @@ -44,7 +43,7 @@ void insert(Serializer& serializer, const BaseDeviceInfo& self) insert(serializer, self.device_options[i]); } -void extract(Serializer& serializer, BaseDeviceInfo& self) +void extract(::microstrain::Buffer& serializer, BaseDeviceInfo& self) { extract(serializer, self.firmware_version); @@ -70,12 +69,12 @@ void extract(Serializer& serializer, BaseDeviceInfo& self) // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const Ping& self) +void insert(::microstrain::Buffer& serializer, const Ping& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, Ping& self) +void extract(::microstrain::Buffer& serializer, Ping& self) { (void)serializer; (void)self; @@ -85,12 +84,12 @@ TypedResult ping(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PING, NULL, 0); } -void insert(Serializer& serializer, const SetIdle& self) +void insert(::microstrain::Buffer& serializer, const SetIdle& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, SetIdle& self) +void extract(::microstrain::Buffer& serializer, SetIdle& self) { (void)serializer; (void)self; @@ -100,23 +99,23 @@ TypedResult setIdle(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_TO_IDLE, NULL, 0); } -void insert(Serializer& serializer, const GetDeviceInfo& self) +void insert(::microstrain::Buffer& serializer, const GetDeviceInfo& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetDeviceInfo& self) +void extract(::microstrain::Buffer& serializer, GetDeviceInfo& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetDeviceInfo::Response& self) +void insert(::microstrain::Buffer& serializer, const GetDeviceInfo::Response& self) { insert(serializer, self.device_info); } -void extract(Serializer& serializer, GetDeviceInfo::Response& self) +void extract(::microstrain::Buffer& serializer, GetDeviceInfo::Response& self) { extract(serializer, self.device_info); @@ -131,7 +130,7 @@ TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInf if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(deviceInfoOut); extract(deserializer, *deviceInfoOut); @@ -141,24 +140,24 @@ TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInf } return result; } -void insert(Serializer& serializer, const GetDeviceDescriptors& self) +void insert(::microstrain::Buffer& serializer, const GetDeviceDescriptors& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetDeviceDescriptors& self) +void extract(::microstrain::Buffer& serializer, GetDeviceDescriptors& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetDeviceDescriptors::Response& self) +void insert(::microstrain::Buffer& serializer, const GetDeviceDescriptors::Response& self) { for(unsigned int i=0; i < self.descriptors_count; i++) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, GetDeviceDescriptors::Response& self) +void extract(::microstrain::Buffer& serializer, GetDeviceDescriptors::Response& self) { for(self.descriptors_count = 0; (self.descriptors_count < sizeof(self.descriptors)/sizeof(self.descriptors[0])) && (serializer.remaining() > 0); (self.descriptors_count)++) extract(serializer, self.descriptors[self.descriptors_count]); @@ -174,7 +173,7 @@ TypedResult getDeviceDescriptors(C::mip_interface& device, if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) extract(deserializer, descriptorsOut[*descriptorsOutCount]); @@ -184,23 +183,23 @@ TypedResult getDeviceDescriptors(C::mip_interface& device, } return result; } -void insert(Serializer& serializer, const BuiltInTest& self) +void insert(::microstrain::Buffer& serializer, const BuiltInTest& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, BuiltInTest& self) +void extract(::microstrain::Buffer& serializer, BuiltInTest& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const BuiltInTest::Response& self) +void insert(::microstrain::Buffer& serializer, const BuiltInTest::Response& self) { insert(serializer, self.result); } -void extract(Serializer& serializer, BuiltInTest::Response& self) +void extract(::microstrain::Buffer& serializer, BuiltInTest::Response& self) { extract(serializer, self.result); @@ -215,7 +214,7 @@ TypedResult builtInTest(C::mip_interface& device, uint32_t* resultO if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(resultOut); extract(deserializer, *resultOut); @@ -225,12 +224,12 @@ TypedResult builtInTest(C::mip_interface& device, uint32_t* resultO } return result; } -void insert(Serializer& serializer, const Resume& self) +void insert(::microstrain::Buffer& serializer, const Resume& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, Resume& self) +void extract(::microstrain::Buffer& serializer, Resume& self) { (void)serializer; (void)self; @@ -240,24 +239,24 @@ TypedResult resume(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESUME, NULL, 0); } -void insert(Serializer& serializer, const GetExtendedDescriptors& self) +void insert(::microstrain::Buffer& serializer, const GetExtendedDescriptors& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetExtendedDescriptors& self) +void extract(::microstrain::Buffer& serializer, GetExtendedDescriptors& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetExtendedDescriptors::Response& self) +void insert(::microstrain::Buffer& serializer, const GetExtendedDescriptors::Response& self) { for(unsigned int i=0; i < self.descriptors_count; i++) insert(serializer, self.descriptors[i]); } -void extract(Serializer& serializer, GetExtendedDescriptors::Response& self) +void extract(::microstrain::Buffer& serializer, GetExtendedDescriptors::Response& self) { for(self.descriptors_count = 0; (self.descriptors_count < sizeof(self.descriptors)/sizeof(self.descriptors[0])) && (serializer.remaining() > 0); (self.descriptors_count)++) extract(serializer, self.descriptors[self.descriptors_count]); @@ -273,7 +272,7 @@ TypedResult getExtendedDescriptors(C::mip_interface& dev if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) extract(deserializer, descriptorsOut[*descriptorsOutCount]); @@ -283,24 +282,24 @@ TypedResult getExtendedDescriptors(C::mip_interface& dev } return result; } -void insert(Serializer& serializer, const ContinuousBit& self) +void insert(::microstrain::Buffer& serializer, const ContinuousBit& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, ContinuousBit& self) +void extract(::microstrain::Buffer& serializer, ContinuousBit& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const ContinuousBit::Response& self) +void insert(::microstrain::Buffer& serializer, const ContinuousBit::Response& self) { for(unsigned int i=0; i < 16; i++) insert(serializer, self.result[i]); } -void extract(Serializer& serializer, ContinuousBit::Response& self) +void extract(::microstrain::Buffer& serializer, ContinuousBit::Response& self) { for(unsigned int i=0; i < 16; i++) extract(serializer, self.result[i]); @@ -316,7 +315,7 @@ TypedResult continuousBit(C::mip_interface& device, uint8_t* resu if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(resultOut || (16 == 0)); for(unsigned int i=0; i < 16; i++) @@ -327,7 +326,7 @@ TypedResult continuousBit(C::mip_interface& device, uint8_t* resu } return result; } -void insert(Serializer& serializer, const CommSpeed& self) +void insert(::microstrain::Buffer& serializer, const CommSpeed& self) { insert(serializer, self.function); @@ -339,7 +338,7 @@ void insert(Serializer& serializer, const CommSpeed& self) } } -void extract(Serializer& serializer, CommSpeed& self) +void extract(::microstrain::Buffer& serializer, CommSpeed& self) { extract(serializer, self.function); @@ -352,14 +351,14 @@ void extract(Serializer& serializer, CommSpeed& self) } } -void insert(Serializer& serializer, const CommSpeed::Response& self) +void insert(::microstrain::Buffer& serializer, const CommSpeed::Response& self) { insert(serializer, self.port); insert(serializer, self.baud); } -void extract(Serializer& serializer, CommSpeed::Response& self) +void extract(::microstrain::Buffer& serializer, CommSpeed::Response& self) { extract(serializer, self.port); @@ -370,7 +369,7 @@ void extract(Serializer& serializer, CommSpeed::Response& self) TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, port); @@ -379,12 +378,12 @@ TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); } TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, port); @@ -392,11 +391,11 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_COMM_SPEED, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length(), REPLY_COMM_SPEED, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, port); @@ -411,40 +410,40 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, port); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); } TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, port); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); } TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, port); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GpsTimeUpdate& self) +void insert(::microstrain::Buffer& serializer, const GpsTimeUpdate& self) { insert(serializer, self.function); @@ -456,7 +455,7 @@ void insert(Serializer& serializer, const GpsTimeUpdate& self) } } -void extract(Serializer& serializer, GpsTimeUpdate& self) +void extract(::microstrain::Buffer& serializer, GpsTimeUpdate& self) { extract(serializer, self.function); @@ -472,7 +471,7 @@ void extract(Serializer& serializer, GpsTimeUpdate& self) TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, fieldId); @@ -481,14 +480,14 @@ TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeU assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SoftReset& self) +void insert(::microstrain::Buffer& serializer, const SoftReset& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, SoftReset& self) +void extract(::microstrain::Buffer& serializer, SoftReset& self) { (void)serializer; (void)self; diff --git a/src/mip/definitions/commands_base.hpp b/src/mip/definitions/commands_base.hpp index 65a17e7e4..003a44734 100644 --- a/src/mip/definitions/commands_base.hpp +++ b/src/mip/definitions/commands_base.hpp @@ -8,8 +8,13 @@ #include #include +namespace microstrain +{ +class Buffer; +} + namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -68,8 +73,8 @@ struct BaseDeviceInfo char device_options[16] = {0}; }; -void insert(Serializer& serializer, const BaseDeviceInfo& self); -void extract(Serializer& serializer, BaseDeviceInfo& self); +void insert(::microstrain::Buffer& serializer, const BaseDeviceInfo& self); +void extract(::microstrain::Buffer& serializer, BaseDeviceInfo& self); enum class TimeFormat : uint8_t { @@ -217,8 +222,8 @@ struct Ping } typedef void Response; }; -void insert(Serializer& serializer, const Ping& self); -void extract(Serializer& serializer, Ping& self); +void insert(::microstrain::Buffer& serializer, const Ping& self); +void extract(::microstrain::Buffer& serializer, Ping& self); TypedResult ping(C::mip_interface& device); @@ -257,8 +262,8 @@ struct SetIdle } typedef void Response; }; -void insert(Serializer& serializer, const SetIdle& self); -void extract(Serializer& serializer, SetIdle& self); +void insert(::microstrain::Buffer& serializer, const SetIdle& self); +void extract(::microstrain::Buffer& serializer, SetIdle& self); TypedResult setIdle(C::mip_interface& device); @@ -311,11 +316,11 @@ struct GetDeviceInfo } }; }; -void insert(Serializer& serializer, const GetDeviceInfo& self); -void extract(Serializer& serializer, GetDeviceInfo& self); +void insert(::microstrain::Buffer& serializer, const GetDeviceInfo& self); +void extract(::microstrain::Buffer& serializer, GetDeviceInfo& self); -void insert(Serializer& serializer, const GetDeviceInfo::Response& self); -void extract(Serializer& serializer, GetDeviceInfo::Response& self); +void insert(::microstrain::Buffer& serializer, const GetDeviceInfo::Response& self); +void extract(::microstrain::Buffer& serializer, GetDeviceInfo::Response& self); TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut); @@ -372,11 +377,11 @@ struct GetDeviceDescriptors } }; }; -void insert(Serializer& serializer, const GetDeviceDescriptors& self); -void extract(Serializer& serializer, GetDeviceDescriptors& self); +void insert(::microstrain::Buffer& serializer, const GetDeviceDescriptors& self); +void extract(::microstrain::Buffer& serializer, GetDeviceDescriptors& self); -void insert(Serializer& serializer, const GetDeviceDescriptors::Response& self); -void extract(Serializer& serializer, GetDeviceDescriptors::Response& self); +void insert(::microstrain::Buffer& serializer, const GetDeviceDescriptors::Response& self); +void extract(::microstrain::Buffer& serializer, GetDeviceDescriptors::Response& self); TypedResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); @@ -434,11 +439,11 @@ struct BuiltInTest } }; }; -void insert(Serializer& serializer, const BuiltInTest& self); -void extract(Serializer& serializer, BuiltInTest& self); +void insert(::microstrain::Buffer& serializer, const BuiltInTest& self); +void extract(::microstrain::Buffer& serializer, BuiltInTest& self); -void insert(Serializer& serializer, const BuiltInTest::Response& self); -void extract(Serializer& serializer, BuiltInTest::Response& self); +void insert(::microstrain::Buffer& serializer, const BuiltInTest::Response& self); +void extract(::microstrain::Buffer& serializer, BuiltInTest::Response& self); TypedResult builtInTest(C::mip_interface& device, uint32_t* resultOut); @@ -475,8 +480,8 @@ struct Resume } typedef void Response; }; -void insert(Serializer& serializer, const Resume& self); -void extract(Serializer& serializer, Resume& self); +void insert(::microstrain::Buffer& serializer, const Resume& self); +void extract(::microstrain::Buffer& serializer, Resume& self); TypedResult resume(C::mip_interface& device); @@ -533,11 +538,11 @@ struct GetExtendedDescriptors } }; }; -void insert(Serializer& serializer, const GetExtendedDescriptors& self); -void extract(Serializer& serializer, GetExtendedDescriptors& self); +void insert(::microstrain::Buffer& serializer, const GetExtendedDescriptors& self); +void extract(::microstrain::Buffer& serializer, GetExtendedDescriptors& self); -void insert(Serializer& serializer, const GetExtendedDescriptors::Response& self); -void extract(Serializer& serializer, GetExtendedDescriptors::Response& self); +void insert(::microstrain::Buffer& serializer, const GetExtendedDescriptors::Response& self); +void extract(::microstrain::Buffer& serializer, GetExtendedDescriptors::Response& self); TypedResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); @@ -592,11 +597,11 @@ struct ContinuousBit } }; }; -void insert(Serializer& serializer, const ContinuousBit& self); -void extract(Serializer& serializer, ContinuousBit& self); +void insert(::microstrain::Buffer& serializer, const ContinuousBit& self); +void extract(::microstrain::Buffer& serializer, ContinuousBit& self); -void insert(Serializer& serializer, const ContinuousBit::Response& self); -void extract(Serializer& serializer, ContinuousBit::Response& self); +void insert(::microstrain::Buffer& serializer, const ContinuousBit::Response& self); +void extract(::microstrain::Buffer& serializer, ContinuousBit::Response& self); TypedResult continuousBit(C::mip_interface& device, uint8_t* resultOut); @@ -681,11 +686,11 @@ struct CommSpeed } }; }; -void insert(Serializer& serializer, const CommSpeed& self); -void extract(Serializer& serializer, CommSpeed& self); +void insert(::microstrain::Buffer& serializer, const CommSpeed& self); +void extract(::microstrain::Buffer& serializer, CommSpeed& self); -void insert(Serializer& serializer, const CommSpeed::Response& self); -void extract(Serializer& serializer, CommSpeed::Response& self); +void insert(::microstrain::Buffer& serializer, const CommSpeed::Response& self); +void extract(::microstrain::Buffer& serializer, CommSpeed::Response& self); TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud); TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut); @@ -749,8 +754,8 @@ struct GpsTimeUpdate typedef void Response; }; -void insert(Serializer& serializer, const GpsTimeUpdate& self); -void extract(Serializer& serializer, GpsTimeUpdate& self); +void insert(::microstrain::Buffer& serializer, const GpsTimeUpdate& self); +void extract(::microstrain::Buffer& serializer, GpsTimeUpdate& self); TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value); @@ -787,8 +792,8 @@ struct SoftReset } typedef void Response; }; -void insert(Serializer& serializer, const SoftReset& self); -void extract(Serializer& serializer, SoftReset& self); +void insert(::microstrain::Buffer& serializer, const SoftReset& self); +void extract(::microstrain::Buffer& serializer, SoftReset& self); TypedResult softReset(C::mip_interface& device); diff --git a/src/mip/definitions/commands_filter.cpp b/src/mip/definitions/commands_filter.cpp index a838cee97..ce9640252 100644 --- a/src/mip/definitions/commands_filter.cpp +++ b/src/mip/definitions/commands_filter.cpp @@ -1,14 +1,14 @@ #include "commands_filter.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -16,6 +16,7 @@ struct mip_interface; namespace commands_filter { +using ::microstrain::Buffer; using ::mip::insert; using ::mip::extract; using namespace ::mip::C; @@ -29,12 +30,12 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const Reset& self) +void insert(::microstrain::Buffer& serializer, const Reset& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, Reset& self) +void extract(::microstrain::Buffer& serializer, Reset& self) { (void)serializer; (void)self; @@ -44,7 +45,7 @@ TypedResult reset(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESET_FILTER, NULL, 0); } -void insert(Serializer& serializer, const SetInitialAttitude& self) +void insert(::microstrain::Buffer& serializer, const SetInitialAttitude& self) { insert(serializer, self.roll); @@ -53,7 +54,7 @@ void insert(Serializer& serializer, const SetInitialAttitude& self) insert(serializer, self.heading); } -void extract(Serializer& serializer, SetInitialAttitude& self) +void extract(::microstrain::Buffer& serializer, SetInitialAttitude& self) { extract(serializer, self.roll); @@ -66,7 +67,7 @@ void extract(Serializer& serializer, SetInitialAttitude& self) TypedResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, roll); @@ -76,9 +77,9 @@ TypedResult setInitialAttitude(C::mip_interface& device, flo assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_ATTITUDE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_ATTITUDE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const EstimationControl& self) +void insert(::microstrain::Buffer& serializer, const EstimationControl& self) { insert(serializer, self.function); @@ -88,7 +89,7 @@ void insert(Serializer& serializer, const EstimationControl& self) } } -void extract(Serializer& serializer, EstimationControl& self) +void extract(::microstrain::Buffer& serializer, EstimationControl& self) { extract(serializer, self.function); @@ -99,12 +100,12 @@ void extract(Serializer& serializer, EstimationControl& self) } } -void insert(Serializer& serializer, const EstimationControl::Response& self) +void insert(::microstrain::Buffer& serializer, const EstimationControl::Response& self) { insert(serializer, self.enable); } -void extract(Serializer& serializer, EstimationControl::Response& self) +void extract(::microstrain::Buffer& serializer, EstimationControl::Response& self) { extract(serializer, self.enable); @@ -113,29 +114,29 @@ void extract(Serializer& serializer, EstimationControl::Response& self) TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); } TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length(), REPLY_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -148,34 +149,34 @@ TypedResult readEstimationControl(C::mip_interface& device, E TypedResult saveEstimationControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); } TypedResult loadEstimationControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultEstimationControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ExternalGnssUpdate& self) +void insert(::microstrain::Buffer& serializer, const ExternalGnssUpdate& self) { insert(serializer, self.gps_time); @@ -197,7 +198,7 @@ void insert(Serializer& serializer, const ExternalGnssUpdate& self) insert(serializer, self.vel_uncertainty[i]); } -void extract(Serializer& serializer, ExternalGnssUpdate& self) +void extract(::microstrain::Buffer& serializer, ExternalGnssUpdate& self) { extract(serializer, self.gps_time); @@ -223,7 +224,7 @@ void extract(Serializer& serializer, ExternalGnssUpdate& self) TypedResult externalGnssUpdate(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, double latitude, double longitude, double height, const float* velocity, const float* posUncertainty, const float* velUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, gpsTime); @@ -249,9 +250,9 @@ TypedResult externalGnssUpdate(C::mip_interface& device, dou assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ExternalHeadingUpdate& self) +void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdate& self) { insert(serializer, self.heading); @@ -260,7 +261,7 @@ void insert(Serializer& serializer, const ExternalHeadingUpdate& self) insert(serializer, self.type); } -void extract(Serializer& serializer, ExternalHeadingUpdate& self) +void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdate& self) { extract(serializer, self.heading); @@ -273,7 +274,7 @@ void extract(Serializer& serializer, ExternalHeadingUpdate& self) TypedResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, heading); @@ -283,9 +284,9 @@ TypedResult externalHeadingUpdate(C::mip_interface& devic assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ExternalHeadingUpdateWithTime& self) +void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdateWithTime& self) { insert(serializer, self.gps_time); @@ -298,7 +299,7 @@ void insert(Serializer& serializer, const ExternalHeadingUpdateWithTime& self) insert(serializer, self.type); } -void extract(Serializer& serializer, ExternalHeadingUpdateWithTime& self) +void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdateWithTime& self) { extract(serializer, self.gps_time); @@ -315,7 +316,7 @@ void extract(Serializer& serializer, ExternalHeadingUpdateWithTime& self) TypedResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, gpsTime); @@ -329,9 +330,9 @@ TypedResult externalHeadingUpdateWithTime(C::mip_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const TareOrientation& self) +void insert(::microstrain::Buffer& serializer, const TareOrientation& self) { insert(serializer, self.function); @@ -341,7 +342,7 @@ void insert(Serializer& serializer, const TareOrientation& self) } } -void extract(Serializer& serializer, TareOrientation& self) +void extract(::microstrain::Buffer& serializer, TareOrientation& self) { extract(serializer, self.function); @@ -352,12 +353,12 @@ void extract(Serializer& serializer, TareOrientation& self) } } -void insert(Serializer& serializer, const TareOrientation::Response& self) +void insert(::microstrain::Buffer& serializer, const TareOrientation::Response& self) { insert(serializer, self.axes); } -void extract(Serializer& serializer, TareOrientation::Response& self) +void extract(::microstrain::Buffer& serializer, TareOrientation::Response& self) { extract(serializer, self.axes); @@ -366,29 +367,29 @@ void extract(Serializer& serializer, TareOrientation::Response& self) TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, axes); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); } TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_TARE_ORIENTATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length(), REPLY_TARE_ORIENTATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(axesOut); extract(deserializer, *axesOut); @@ -401,34 +402,34 @@ TypedResult readTareOrientation(C::mip_interface& device, TareO TypedResult saveTareOrientation(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); } TypedResult loadTareOrientation(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultTareOrientation(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const VehicleDynamicsMode& self) +void insert(::microstrain::Buffer& serializer, const VehicleDynamicsMode& self) { insert(serializer, self.function); @@ -438,7 +439,7 @@ void insert(Serializer& serializer, const VehicleDynamicsMode& self) } } -void extract(Serializer& serializer, VehicleDynamicsMode& self) +void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode& self) { extract(serializer, self.function); @@ -449,12 +450,12 @@ void extract(Serializer& serializer, VehicleDynamicsMode& self) } } -void insert(Serializer& serializer, const VehicleDynamicsMode::Response& self) +void insert(::microstrain::Buffer& serializer, const VehicleDynamicsMode::Response& self) { insert(serializer, self.mode); } -void extract(Serializer& serializer, VehicleDynamicsMode::Response& self) +void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode::Response& self) { extract(serializer, self.mode); @@ -463,29 +464,29 @@ void extract(Serializer& serializer, VehicleDynamicsMode::Response& self) TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); } TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length(), REPLY_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -498,34 +499,34 @@ TypedResult readVehicleDynamicsMode(C::mip_interface& devic TypedResult saveVehicleDynamicsMode(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); } TypedResult loadVehicleDynamicsMode(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); } TypedResult defaultVehicleDynamicsMode(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SensorToVehicleRotationEuler& self) +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEuler& self) { insert(serializer, self.function); @@ -539,7 +540,7 @@ void insert(Serializer& serializer, const SensorToVehicleRotationEuler& self) } } -void extract(Serializer& serializer, SensorToVehicleRotationEuler& self) +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler& self) { extract(serializer, self.function); @@ -554,7 +555,7 @@ void extract(Serializer& serializer, SensorToVehicleRotationEuler& self) } } -void insert(Serializer& serializer, const SensorToVehicleRotationEuler::Response& self) +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEuler::Response& self) { insert(serializer, self.roll); @@ -563,7 +564,7 @@ void insert(Serializer& serializer, const SensorToVehicleRotationEuler::Response insert(serializer, self.yaw); } -void extract(Serializer& serializer, SensorToVehicleRotationEuler::Response& self) +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler::Response& self) { extract(serializer, self.roll); @@ -576,7 +577,7 @@ void extract(Serializer& serializer, SensorToVehicleRotationEuler::Response& sel TypedResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, roll); @@ -587,22 +588,22 @@ TypedResult writeSensorToVehicleRotationEuler(C::m assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); } TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(rollOut); extract(deserializer, *rollOut); @@ -621,34 +622,34 @@ TypedResult readSensorToVehicleRotationEuler(C::mi TypedResult saveSensorToVehicleRotationEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); } TypedResult loadSensorToVehicleRotationEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensorToVehicleRotationEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SensorToVehicleRotationDcm& self) +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationDcm& self) { insert(serializer, self.function); @@ -659,7 +660,7 @@ void insert(Serializer& serializer, const SensorToVehicleRotationDcm& self) } } -void extract(Serializer& serializer, SensorToVehicleRotationDcm& self) +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm& self) { extract(serializer, self.function); @@ -671,13 +672,13 @@ void extract(Serializer& serializer, SensorToVehicleRotationDcm& self) } } -void insert(Serializer& serializer, const SensorToVehicleRotationDcm::Response& self) +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationDcm::Response& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.dcm[i]); } -void extract(Serializer& serializer, SensorToVehicleRotationDcm::Response& self) +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm::Response& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.dcm[i]); @@ -687,7 +688,7 @@ void extract(Serializer& serializer, SensorToVehicleRotationDcm::Response& self) TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(dcm || (9 == 0)); @@ -696,22 +697,22 @@ TypedResult writeSensorToVehicleRotationDcm(C::mip_i assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); } TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(dcmOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -725,34 +726,34 @@ TypedResult readSensorToVehicleRotationDcm(C::mip_in TypedResult saveSensorToVehicleRotationDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); } TypedResult loadSensorToVehicleRotationDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensorToVehicleRotationDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SensorToVehicleRotationQuaternion& self) +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationQuaternion& self) { insert(serializer, self.function); @@ -763,7 +764,7 @@ void insert(Serializer& serializer, const SensorToVehicleRotationQuaternion& sel } } -void extract(Serializer& serializer, SensorToVehicleRotationQuaternion& self) +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternion& self) { extract(serializer, self.function); @@ -775,13 +776,13 @@ void extract(Serializer& serializer, SensorToVehicleRotationQuaternion& self) } } -void insert(Serializer& serializer, const SensorToVehicleRotationQuaternion::Response& self) +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationQuaternion::Response& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.quat[i]); } -void extract(Serializer& serializer, SensorToVehicleRotationQuaternion::Response& self) +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternion::Response& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.quat[i]); @@ -791,7 +792,7 @@ void extract(Serializer& serializer, SensorToVehicleRotationQuaternion::Response TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(quat || (4 == 0)); @@ -800,22 +801,22 @@ TypedResult writeSensorToVehicleRotationQuate assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); } TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(quatOut || (4 == 0)); for(unsigned int i=0; i < 4; i++) @@ -829,34 +830,34 @@ TypedResult readSensorToVehicleRotationQuater TypedResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); } TypedResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SensorToVehicleOffset& self) +void insert(::microstrain::Buffer& serializer, const SensorToVehicleOffset& self) { insert(serializer, self.function); @@ -867,7 +868,7 @@ void insert(Serializer& serializer, const SensorToVehicleOffset& self) } } -void extract(Serializer& serializer, SensorToVehicleOffset& self) +void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset& self) { extract(serializer, self.function); @@ -879,13 +880,13 @@ void extract(Serializer& serializer, SensorToVehicleOffset& self) } } -void insert(Serializer& serializer, const SensorToVehicleOffset::Response& self) +void insert(::microstrain::Buffer& serializer, const SensorToVehicleOffset::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset[i]); } -void extract(Serializer& serializer, SensorToVehicleOffset::Response& self) +void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset[i]); @@ -895,7 +896,7 @@ void extract(Serializer& serializer, SensorToVehicleOffset::Response& self) TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (3 == 0)); @@ -904,22 +905,22 @@ TypedResult writeSensorToVehicleOffset(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(offsetOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -933,34 +934,34 @@ TypedResult readSensorToVehicleOffset(C::mip_interface& d TypedResult saveSensorToVehicleOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult loadSensorToVehicleOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensorToVehicleOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AntennaOffset& self) +void insert(::microstrain::Buffer& serializer, const AntennaOffset& self) { insert(serializer, self.function); @@ -971,7 +972,7 @@ void insert(Serializer& serializer, const AntennaOffset& self) } } -void extract(Serializer& serializer, AntennaOffset& self) +void extract(::microstrain::Buffer& serializer, AntennaOffset& self) { extract(serializer, self.function); @@ -983,13 +984,13 @@ void extract(Serializer& serializer, AntennaOffset& self) } } -void insert(Serializer& serializer, const AntennaOffset::Response& self) +void insert(::microstrain::Buffer& serializer, const AntennaOffset::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset[i]); } -void extract(Serializer& serializer, AntennaOffset::Response& self) +void extract(::microstrain::Buffer& serializer, AntennaOffset::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset[i]); @@ -999,7 +1000,7 @@ void extract(Serializer& serializer, AntennaOffset::Response& self) TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (3 == 0)); @@ -1008,22 +1009,22 @@ TypedResult writeAntennaOffset(C::mip_interface& device, const fl assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ANTENNA_OFFSET, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(offsetOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1037,34 +1038,34 @@ TypedResult readAntennaOffset(C::mip_interface& device, float* of TypedResult saveAntennaOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult loadAntennaOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult defaultAntennaOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GnssSource& self) +void insert(::microstrain::Buffer& serializer, const GnssSource& self) { insert(serializer, self.function); @@ -1074,7 +1075,7 @@ void insert(Serializer& serializer, const GnssSource& self) } } -void extract(Serializer& serializer, GnssSource& self) +void extract(::microstrain::Buffer& serializer, GnssSource& self) { extract(serializer, self.function); @@ -1085,12 +1086,12 @@ void extract(Serializer& serializer, GnssSource& self) } } -void insert(Serializer& serializer, const GnssSource::Response& self) +void insert(::microstrain::Buffer& serializer, const GnssSource::Response& self) { insert(serializer, self.source); } -void extract(Serializer& serializer, GnssSource::Response& self) +void extract(::microstrain::Buffer& serializer, GnssSource::Response& self) { extract(serializer, self.source); @@ -1099,29 +1100,29 @@ void extract(Serializer& serializer, GnssSource::Response& self) TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GNSS_SOURCE_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_GNSS_SOURCE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -1134,34 +1135,34 @@ TypedResult readGnssSource(C::mip_interface& device, GnssSource::Sou TypedResult saveGnssSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadGnssSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultGnssSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const HeadingSource& self) +void insert(::microstrain::Buffer& serializer, const HeadingSource& self) { insert(serializer, self.function); @@ -1171,7 +1172,7 @@ void insert(Serializer& serializer, const HeadingSource& self) } } -void extract(Serializer& serializer, HeadingSource& self) +void extract(::microstrain::Buffer& serializer, HeadingSource& self) { extract(serializer, self.function); @@ -1182,12 +1183,12 @@ void extract(Serializer& serializer, HeadingSource& self) } } -void insert(Serializer& serializer, const HeadingSource::Response& self) +void insert(::microstrain::Buffer& serializer, const HeadingSource::Response& self) { insert(serializer, self.source); } -void extract(Serializer& serializer, HeadingSource::Response& self) +void extract(::microstrain::Buffer& serializer, HeadingSource::Response& self) { extract(serializer, self.source); @@ -1196,29 +1197,29 @@ void extract(Serializer& serializer, HeadingSource::Response& self) TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_HEADING_UPDATE_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_HEADING_UPDATE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -1231,34 +1232,34 @@ TypedResult readHeadingSource(C::mip_interface& device, HeadingSo TypedResult saveHeadingSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadHeadingSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultHeadingSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AutoInitControl& self) +void insert(::microstrain::Buffer& serializer, const AutoInitControl& self) { insert(serializer, self.function); @@ -1268,7 +1269,7 @@ void insert(Serializer& serializer, const AutoInitControl& self) } } -void extract(Serializer& serializer, AutoInitControl& self) +void extract(::microstrain::Buffer& serializer, AutoInitControl& self) { extract(serializer, self.function); @@ -1279,12 +1280,12 @@ void extract(Serializer& serializer, AutoInitControl& self) } } -void insert(Serializer& serializer, const AutoInitControl::Response& self) +void insert(::microstrain::Buffer& serializer, const AutoInitControl::Response& self) { insert(serializer, self.enable); } -void extract(Serializer& serializer, AutoInitControl::Response& self) +void extract(::microstrain::Buffer& serializer, AutoInitControl::Response& self) { extract(serializer, self.enable); @@ -1293,29 +1294,29 @@ void extract(Serializer& serializer, AutoInitControl::Response& self) TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_AUTOINIT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_AUTOINIT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -1328,34 +1329,34 @@ TypedResult readAutoInitControl(C::mip_interface& device, uint8 TypedResult saveAutoInitControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAutoInitControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAutoInitControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AccelNoise& self) +void insert(::microstrain::Buffer& serializer, const AccelNoise& self) { insert(serializer, self.function); @@ -1366,7 +1367,7 @@ void insert(Serializer& serializer, const AccelNoise& self) } } -void extract(Serializer& serializer, AccelNoise& self) +void extract(::microstrain::Buffer& serializer, AccelNoise& self) { extract(serializer, self.function); @@ -1378,13 +1379,13 @@ void extract(Serializer& serializer, AccelNoise& self) } } -void insert(Serializer& serializer, const AccelNoise::Response& self) +void insert(::microstrain::Buffer& serializer, const AccelNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(Serializer& serializer, AccelNoise::Response& self) +void extract(::microstrain::Buffer& serializer, AccelNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -1394,7 +1395,7 @@ void extract(Serializer& serializer, AccelNoise::Response& self) TypedResult writeAccelNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -1403,22 +1404,22 @@ TypedResult writeAccelNoise(C::mip_interface& device, const float* n assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ACCEL_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1432,34 +1433,34 @@ TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut TypedResult saveAccelNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadAccelNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultAccelNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GyroNoise& self) +void insert(::microstrain::Buffer& serializer, const GyroNoise& self) { insert(serializer, self.function); @@ -1470,7 +1471,7 @@ void insert(Serializer& serializer, const GyroNoise& self) } } -void extract(Serializer& serializer, GyroNoise& self) +void extract(::microstrain::Buffer& serializer, GyroNoise& self) { extract(serializer, self.function); @@ -1482,13 +1483,13 @@ void extract(Serializer& serializer, GyroNoise& self) } } -void insert(Serializer& serializer, const GyroNoise::Response& self) +void insert(::microstrain::Buffer& serializer, const GyroNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(Serializer& serializer, GyroNoise::Response& self) +void extract(::microstrain::Buffer& serializer, GyroNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -1498,7 +1499,7 @@ void extract(Serializer& serializer, GyroNoise::Response& self) TypedResult writeGyroNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -1507,22 +1508,22 @@ TypedResult writeGyroNoise(C::mip_interface& device, const float* noi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length(), REPLY_GYRO_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1536,34 +1537,34 @@ TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) TypedResult saveGyroNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadGyroNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultGyroNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AccelBiasModel& self) +void insert(::microstrain::Buffer& serializer, const AccelBiasModel& self) { insert(serializer, self.function); @@ -1577,7 +1578,7 @@ void insert(Serializer& serializer, const AccelBiasModel& self) } } -void extract(Serializer& serializer, AccelBiasModel& self) +void extract(::microstrain::Buffer& serializer, AccelBiasModel& self) { extract(serializer, self.function); @@ -1592,7 +1593,7 @@ void extract(Serializer& serializer, AccelBiasModel& self) } } -void insert(Serializer& serializer, const AccelBiasModel::Response& self) +void insert(::microstrain::Buffer& serializer, const AccelBiasModel::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.beta[i]); @@ -1601,7 +1602,7 @@ void insert(Serializer& serializer, const AccelBiasModel::Response& self) insert(serializer, self.noise[i]); } -void extract(Serializer& serializer, AccelBiasModel::Response& self) +void extract(::microstrain::Buffer& serializer, AccelBiasModel::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.beta[i]); @@ -1614,7 +1615,7 @@ void extract(Serializer& serializer, AccelBiasModel::Response& self) TypedResult writeAccelBiasModel(C::mip_interface& device, const float* beta, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(beta || (3 == 0)); @@ -1627,22 +1628,22 @@ TypedResult writeAccelBiasModel(C::mip_interface& device, const assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ACCEL_BIAS_MODEL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(betaOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1660,34 +1661,34 @@ TypedResult readAccelBiasModel(C::mip_interface& device, float* TypedResult saveAccelBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult loadAccelBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAccelBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GyroBiasModel& self) +void insert(::microstrain::Buffer& serializer, const GyroBiasModel& self) { insert(serializer, self.function); @@ -1701,7 +1702,7 @@ void insert(Serializer& serializer, const GyroBiasModel& self) } } -void extract(Serializer& serializer, GyroBiasModel& self) +void extract(::microstrain::Buffer& serializer, GyroBiasModel& self) { extract(serializer, self.function); @@ -1716,7 +1717,7 @@ void extract(Serializer& serializer, GyroBiasModel& self) } } -void insert(Serializer& serializer, const GyroBiasModel::Response& self) +void insert(::microstrain::Buffer& serializer, const GyroBiasModel::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.beta[i]); @@ -1725,7 +1726,7 @@ void insert(Serializer& serializer, const GyroBiasModel::Response& self) insert(serializer, self.noise[i]); } -void extract(Serializer& serializer, GyroBiasModel::Response& self) +void extract(::microstrain::Buffer& serializer, GyroBiasModel::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.beta[i]); @@ -1738,7 +1739,7 @@ void extract(Serializer& serializer, GyroBiasModel::Response& self) TypedResult writeGyroBiasModel(C::mip_interface& device, const float* beta, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(beta || (3 == 0)); @@ -1751,22 +1752,22 @@ TypedResult writeGyroBiasModel(C::mip_interface& device, const fl assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_BIAS_MODEL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(betaOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1784,34 +1785,34 @@ TypedResult readGyroBiasModel(C::mip_interface& device, float* be TypedResult saveGyroBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult loadGyroBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult defaultGyroBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AltitudeAiding& self) +void insert(::microstrain::Buffer& serializer, const AltitudeAiding& self) { insert(serializer, self.function); @@ -1821,7 +1822,7 @@ void insert(Serializer& serializer, const AltitudeAiding& self) } } -void extract(Serializer& serializer, AltitudeAiding& self) +void extract(::microstrain::Buffer& serializer, AltitudeAiding& self) { extract(serializer, self.function); @@ -1832,12 +1833,12 @@ void extract(Serializer& serializer, AltitudeAiding& self) } } -void insert(Serializer& serializer, const AltitudeAiding::Response& self) +void insert(::microstrain::Buffer& serializer, const AltitudeAiding::Response& self) { insert(serializer, self.selector); } -void extract(Serializer& serializer, AltitudeAiding::Response& self) +void extract(::microstrain::Buffer& serializer, AltitudeAiding::Response& self) { extract(serializer, self.selector); @@ -1846,29 +1847,29 @@ void extract(Serializer& serializer, AltitudeAiding::Response& self) TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, selector); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(selectorOut); extract(deserializer, *selectorOut); @@ -1881,34 +1882,34 @@ TypedResult readAltitudeAiding(C::mip_interface& device, Altitud TypedResult saveAltitudeAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAltitudeAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAltitudeAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const PitchRollAiding& self) +void insert(::microstrain::Buffer& serializer, const PitchRollAiding& self) { insert(serializer, self.function); @@ -1918,7 +1919,7 @@ void insert(Serializer& serializer, const PitchRollAiding& self) } } -void extract(Serializer& serializer, PitchRollAiding& self) +void extract(::microstrain::Buffer& serializer, PitchRollAiding& self) { extract(serializer, self.function); @@ -1929,12 +1930,12 @@ void extract(Serializer& serializer, PitchRollAiding& self) } } -void insert(Serializer& serializer, const PitchRollAiding::Response& self) +void insert(::microstrain::Buffer& serializer, const PitchRollAiding::Response& self) { insert(serializer, self.source); } -void extract(Serializer& serializer, PitchRollAiding::Response& self) +void extract(::microstrain::Buffer& serializer, PitchRollAiding::Response& self) { extract(serializer, self.source); @@ -1943,29 +1944,29 @@ void extract(Serializer& serializer, PitchRollAiding::Response& self) TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -1978,34 +1979,34 @@ TypedResult readPitchRollAiding(C::mip_interface& device, Pitch TypedResult savePitchRollAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadPitchRollAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultPitchRollAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AutoZupt& self) +void insert(::microstrain::Buffer& serializer, const AutoZupt& self) { insert(serializer, self.function); @@ -2017,7 +2018,7 @@ void insert(Serializer& serializer, const AutoZupt& self) } } -void extract(Serializer& serializer, AutoZupt& self) +void extract(::microstrain::Buffer& serializer, AutoZupt& self) { extract(serializer, self.function); @@ -2030,14 +2031,14 @@ void extract(Serializer& serializer, AutoZupt& self) } } -void insert(Serializer& serializer, const AutoZupt::Response& self) +void insert(::microstrain::Buffer& serializer, const AutoZupt::Response& self) { insert(serializer, self.enable); insert(serializer, self.threshold); } -void extract(Serializer& serializer, AutoZupt::Response& self) +void extract(::microstrain::Buffer& serializer, AutoZupt::Response& self) { extract(serializer, self.enable); @@ -2048,7 +2049,7 @@ void extract(Serializer& serializer, AutoZupt::Response& self) TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -2057,22 +2058,22 @@ TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, fl assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ZUPT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -2088,34 +2089,34 @@ TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, TypedResult saveAutoZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAutoZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAutoZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AutoAngularZupt& self) +void insert(::microstrain::Buffer& serializer, const AutoAngularZupt& self) { insert(serializer, self.function); @@ -2127,7 +2128,7 @@ void insert(Serializer& serializer, const AutoAngularZupt& self) } } -void extract(Serializer& serializer, AutoAngularZupt& self) +void extract(::microstrain::Buffer& serializer, AutoAngularZupt& self) { extract(serializer, self.function); @@ -2140,14 +2141,14 @@ void extract(Serializer& serializer, AutoAngularZupt& self) } } -void insert(Serializer& serializer, const AutoAngularZupt::Response& self) +void insert(::microstrain::Buffer& serializer, const AutoAngularZupt::Response& self) { insert(serializer, self.enable); insert(serializer, self.threshold); } -void extract(Serializer& serializer, AutoAngularZupt::Response& self) +void extract(::microstrain::Buffer& serializer, AutoAngularZupt::Response& self) { extract(serializer, self.enable); @@ -2158,7 +2159,7 @@ void extract(Serializer& serializer, AutoAngularZupt::Response& self) TypedResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -2167,22 +2168,22 @@ TypedResult writeAutoAngularZupt(C::mip_interface& device, uint assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -2198,39 +2199,39 @@ TypedResult readAutoAngularZupt(C::mip_interface& device, uint8 TypedResult saveAutoAngularZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAutoAngularZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAutoAngularZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const CommandedZupt& self) +void insert(::microstrain::Buffer& serializer, const CommandedZupt& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, CommandedZupt& self) +void extract(::microstrain::Buffer& serializer, CommandedZupt& self) { (void)serializer; (void)self; @@ -2240,12 +2241,12 @@ TypedResult commandedZupt(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMMANDED_ZUPT, NULL, 0); } -void insert(Serializer& serializer, const CommandedAngularZupt& self) +void insert(::microstrain::Buffer& serializer, const CommandedAngularZupt& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, CommandedAngularZupt& self) +void extract(::microstrain::Buffer& serializer, CommandedAngularZupt& self) { (void)serializer; (void)self; @@ -2255,12 +2256,12 @@ TypedResult commandedAngularZupt(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMMANDED_ANGULAR_ZUPT, NULL, 0); } -void insert(Serializer& serializer, const MagCaptureAutoCal& self) +void insert(::microstrain::Buffer& serializer, const MagCaptureAutoCal& self) { insert(serializer, self.function); } -void extract(Serializer& serializer, MagCaptureAutoCal& self) +void extract(::microstrain::Buffer& serializer, MagCaptureAutoCal& self) { extract(serializer, self.function); @@ -2269,24 +2270,24 @@ void extract(Serializer& serializer, MagCaptureAutoCal& self) TypedResult writeMagCaptureAutoCal(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)serializer.length()); } TypedResult saveMagCaptureAutoCal(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GravityNoise& self) +void insert(::microstrain::Buffer& serializer, const GravityNoise& self) { insert(serializer, self.function); @@ -2297,7 +2298,7 @@ void insert(Serializer& serializer, const GravityNoise& self) } } -void extract(Serializer& serializer, GravityNoise& self) +void extract(::microstrain::Buffer& serializer, GravityNoise& self) { extract(serializer, self.function); @@ -2309,13 +2310,13 @@ void extract(Serializer& serializer, GravityNoise& self) } } -void insert(Serializer& serializer, const GravityNoise::Response& self) +void insert(::microstrain::Buffer& serializer, const GravityNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(Serializer& serializer, GravityNoise::Response& self) +void extract(::microstrain::Buffer& serializer, GravityNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -2325,7 +2326,7 @@ void extract(Serializer& serializer, GravityNoise::Response& self) TypedResult writeGravityNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -2334,22 +2335,22 @@ TypedResult writeGravityNoise(C::mip_interface& device, const floa assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GRAVITY_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length(), REPLY_GRAVITY_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2363,34 +2364,34 @@ TypedResult readGravityNoise(C::mip_interface& device, float* nois TypedResult saveGravityNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadGravityNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultGravityNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const PressureAltitudeNoise& self) +void insert(::microstrain::Buffer& serializer, const PressureAltitudeNoise& self) { insert(serializer, self.function); @@ -2400,7 +2401,7 @@ void insert(Serializer& serializer, const PressureAltitudeNoise& self) } } -void extract(Serializer& serializer, PressureAltitudeNoise& self) +void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise& self) { extract(serializer, self.function); @@ -2411,12 +2412,12 @@ void extract(Serializer& serializer, PressureAltitudeNoise& self) } } -void insert(Serializer& serializer, const PressureAltitudeNoise::Response& self) +void insert(::microstrain::Buffer& serializer, const PressureAltitudeNoise::Response& self) { insert(serializer, self.noise); } -void extract(Serializer& serializer, PressureAltitudeNoise::Response& self) +void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise::Response& self) { extract(serializer, self.noise); @@ -2425,29 +2426,29 @@ void extract(Serializer& serializer, PressureAltitudeNoise::Response& self) TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, noise); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_PRESSURE_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length(), REPLY_PRESSURE_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(noiseOut); extract(deserializer, *noiseOut); @@ -2460,34 +2461,34 @@ TypedResult readPressureAltitudeNoise(C::mip_interface& d TypedResult savePressureAltitudeNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadPressureAltitudeNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultPressureAltitudeNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const HardIronOffsetNoise& self) +void insert(::microstrain::Buffer& serializer, const HardIronOffsetNoise& self) { insert(serializer, self.function); @@ -2498,7 +2499,7 @@ void insert(Serializer& serializer, const HardIronOffsetNoise& self) } } -void extract(Serializer& serializer, HardIronOffsetNoise& self) +void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise& self) { extract(serializer, self.function); @@ -2510,13 +2511,13 @@ void extract(Serializer& serializer, HardIronOffsetNoise& self) } } -void insert(Serializer& serializer, const HardIronOffsetNoise::Response& self) +void insert(::microstrain::Buffer& serializer, const HardIronOffsetNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(Serializer& serializer, HardIronOffsetNoise::Response& self) +void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -2526,7 +2527,7 @@ void extract(Serializer& serializer, HardIronOffsetNoise::Response& self) TypedResult writeHardIronOffsetNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -2535,22 +2536,22 @@ TypedResult writeHardIronOffsetNoise(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length(), REPLY_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2564,34 +2565,34 @@ TypedResult readHardIronOffsetNoise(C::mip_interface& devic TypedResult saveHardIronOffsetNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadHardIronOffsetNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultHardIronOffsetNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SoftIronMatrixNoise& self) +void insert(::microstrain::Buffer& serializer, const SoftIronMatrixNoise& self) { insert(serializer, self.function); @@ -2602,7 +2603,7 @@ void insert(Serializer& serializer, const SoftIronMatrixNoise& self) } } -void extract(Serializer& serializer, SoftIronMatrixNoise& self) +void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise& self) { extract(serializer, self.function); @@ -2614,13 +2615,13 @@ void extract(Serializer& serializer, SoftIronMatrixNoise& self) } } -void insert(Serializer& serializer, const SoftIronMatrixNoise::Response& self) +void insert(::microstrain::Buffer& serializer, const SoftIronMatrixNoise::Response& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.noise[i]); } -void extract(Serializer& serializer, SoftIronMatrixNoise::Response& self) +void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise::Response& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.noise[i]); @@ -2630,7 +2631,7 @@ void extract(Serializer& serializer, SoftIronMatrixNoise::Response& self) TypedResult writeSoftIronMatrixNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (9 == 0)); @@ -2639,22 +2640,22 @@ TypedResult writeSoftIronMatrixNoise(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length(), REPLY_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(noiseOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -2668,34 +2669,34 @@ TypedResult readSoftIronMatrixNoise(C::mip_interface& devic TypedResult saveSoftIronMatrixNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadSoftIronMatrixNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultSoftIronMatrixNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const MagNoise& self) +void insert(::microstrain::Buffer& serializer, const MagNoise& self) { insert(serializer, self.function); @@ -2706,7 +2707,7 @@ void insert(Serializer& serializer, const MagNoise& self) } } -void extract(Serializer& serializer, MagNoise& self) +void extract(::microstrain::Buffer& serializer, MagNoise& self) { extract(serializer, self.function); @@ -2718,13 +2719,13 @@ void extract(Serializer& serializer, MagNoise& self) } } -void insert(Serializer& serializer, const MagNoise::Response& self) +void insert(::microstrain::Buffer& serializer, const MagNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(Serializer& serializer, MagNoise::Response& self) +void extract(::microstrain::Buffer& serializer, MagNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -2734,7 +2735,7 @@ void extract(Serializer& serializer, MagNoise::Response& self) TypedResult writeMagNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -2743,22 +2744,22 @@ TypedResult writeMagNoise(C::mip_interface& device, const float* noise assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MAG_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length(), REPLY_MAG_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2772,34 +2773,34 @@ TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) TypedResult saveMagNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadMagNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const InclinationSource& self) +void insert(::microstrain::Buffer& serializer, const InclinationSource& self) { insert(serializer, self.function); @@ -2811,7 +2812,7 @@ void insert(Serializer& serializer, const InclinationSource& self) } } -void extract(Serializer& serializer, InclinationSource& self) +void extract(::microstrain::Buffer& serializer, InclinationSource& self) { extract(serializer, self.function); @@ -2824,14 +2825,14 @@ void extract(Serializer& serializer, InclinationSource& self) } } -void insert(Serializer& serializer, const InclinationSource::Response& self) +void insert(::microstrain::Buffer& serializer, const InclinationSource::Response& self) { insert(serializer, self.source); insert(serializer, self.inclination); } -void extract(Serializer& serializer, InclinationSource::Response& self) +void extract(::microstrain::Buffer& serializer, InclinationSource::Response& self) { extract(serializer, self.source); @@ -2842,7 +2843,7 @@ void extract(Serializer& serializer, InclinationSource::Response& self) TypedResult writeInclinationSource(C::mip_interface& device, FilterMagParamSource source, float inclination) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -2851,22 +2852,22 @@ TypedResult writeInclinationSource(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_INCLINATION_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_INCLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -2882,34 +2883,34 @@ TypedResult readInclinationSource(C::mip_interface& device, F TypedResult saveInclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult loadInclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult defaultInclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const MagneticDeclinationSource& self) +void insert(::microstrain::Buffer& serializer, const MagneticDeclinationSource& self) { insert(serializer, self.function); @@ -2921,7 +2922,7 @@ void insert(Serializer& serializer, const MagneticDeclinationSource& self) } } -void extract(Serializer& serializer, MagneticDeclinationSource& self) +void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource& self) { extract(serializer, self.function); @@ -2934,14 +2935,14 @@ void extract(Serializer& serializer, MagneticDeclinationSource& self) } } -void insert(Serializer& serializer, const MagneticDeclinationSource::Response& self) +void insert(::microstrain::Buffer& serializer, const MagneticDeclinationSource::Response& self) { insert(serializer, self.source); insert(serializer, self.declination); } -void extract(Serializer& serializer, MagneticDeclinationSource::Response& self) +void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource::Response& self) { extract(serializer, self.source); @@ -2952,7 +2953,7 @@ void extract(Serializer& serializer, MagneticDeclinationSource::Response& self) TypedResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource source, float declination) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -2961,22 +2962,22 @@ TypedResult writeMagneticDeclinationSource(C::mip_int assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_DECLINATION_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_DECLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -2992,34 +2993,34 @@ TypedResult readMagneticDeclinationSource(C::mip_inte TypedResult saveMagneticDeclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult loadMagneticDeclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagneticDeclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const MagFieldMagnitudeSource& self) +void insert(::microstrain::Buffer& serializer, const MagFieldMagnitudeSource& self) { insert(serializer, self.function); @@ -3031,7 +3032,7 @@ void insert(Serializer& serializer, const MagFieldMagnitudeSource& self) } } -void extract(Serializer& serializer, MagFieldMagnitudeSource& self) +void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource& self) { extract(serializer, self.function); @@ -3044,14 +3045,14 @@ void extract(Serializer& serializer, MagFieldMagnitudeSource& self) } } -void insert(Serializer& serializer, const MagFieldMagnitudeSource::Response& self) +void insert(::microstrain::Buffer& serializer, const MagFieldMagnitudeSource::Response& self) { insert(serializer, self.source); insert(serializer, self.magnitude); } -void extract(Serializer& serializer, MagFieldMagnitudeSource::Response& self) +void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource::Response& self) { extract(serializer, self.source); @@ -3062,7 +3063,7 @@ void extract(Serializer& serializer, MagFieldMagnitudeSource::Response& self) TypedResult writeMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource source, float magnitude) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -3071,22 +3072,22 @@ TypedResult writeMagFieldMagnitudeSource(C::mip_interfa assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -3102,34 +3103,34 @@ TypedResult readMagFieldMagnitudeSource(C::mip_interfac TypedResult saveMagFieldMagnitudeSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult loadMagFieldMagnitudeSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagFieldMagnitudeSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ReferencePosition& self) +void insert(::microstrain::Buffer& serializer, const ReferencePosition& self) { insert(serializer, self.function); @@ -3145,7 +3146,7 @@ void insert(Serializer& serializer, const ReferencePosition& self) } } -void extract(Serializer& serializer, ReferencePosition& self) +void extract(::microstrain::Buffer& serializer, ReferencePosition& self) { extract(serializer, self.function); @@ -3162,7 +3163,7 @@ void extract(Serializer& serializer, ReferencePosition& self) } } -void insert(Serializer& serializer, const ReferencePosition::Response& self) +void insert(::microstrain::Buffer& serializer, const ReferencePosition::Response& self) { insert(serializer, self.enable); @@ -3173,7 +3174,7 @@ void insert(Serializer& serializer, const ReferencePosition::Response& self) insert(serializer, self.altitude); } -void extract(Serializer& serializer, ReferencePosition::Response& self) +void extract(::microstrain::Buffer& serializer, ReferencePosition::Response& self) { extract(serializer, self.enable); @@ -3188,7 +3189,7 @@ void extract(Serializer& serializer, ReferencePosition::Response& self) TypedResult writeReferencePosition(C::mip_interface& device, bool enable, double latitude, double longitude, double altitude) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -3201,22 +3202,22 @@ TypedResult writeReferencePosition(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); } TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_REFERENCE_POSITION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length(), REPLY_REFERENCE_POSITION, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -3238,34 +3239,34 @@ TypedResult readReferencePosition(C::mip_interface& device, b TypedResult saveReferencePosition(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); } TypedResult loadReferencePosition(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); } TypedResult defaultReferencePosition(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self) +void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self) { insert(serializer, self.function); @@ -3287,7 +3288,7 @@ void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement } } -void extract(Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self) +void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self) { extract(serializer, self.function); @@ -3310,7 +3311,7 @@ void extract(Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& sel } } -void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self) +void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self) { insert(serializer, self.adaptive_measurement); @@ -3327,7 +3328,7 @@ void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement insert(serializer, self.minimum_uncertainty); } -void extract(Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self) +void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self) { extract(serializer, self.adaptive_measurement); @@ -3348,7 +3349,7 @@ void extract(Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Res TypedResult writeAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, adaptiveMeasurement); @@ -3367,22 +3368,22 @@ TypedResult writeAccelMagnitudeErrorAdap assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(adaptiveMeasurementOut); extract(deserializer, *adaptiveMeasurementOut); @@ -3413,34 +3414,34 @@ TypedResult readAccelMagnitudeErrorAdapt TypedResult saveAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self) +void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self) { insert(serializer, self.function); @@ -3462,7 +3463,7 @@ void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& } } -void extract(Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self) +void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self) { extract(serializer, self.function); @@ -3485,7 +3486,7 @@ void extract(Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self) } } -void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self) +void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self) { insert(serializer, self.adaptive_measurement); @@ -3502,7 +3503,7 @@ void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement:: insert(serializer, self.minimum_uncertainty); } -void extract(Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self) +void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self) { extract(serializer, self.adaptive_measurement); @@ -3523,7 +3524,7 @@ void extract(Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Respo TypedResult writeMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, adaptiveMeasurement); @@ -3542,22 +3543,22 @@ TypedResult writeMagMagnitudeErrorAdaptive assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(adaptiveMeasurementOut); extract(deserializer, *adaptiveMeasurementOut); @@ -3588,34 +3589,34 @@ TypedResult readMagMagnitudeErrorAdaptiveM TypedResult saveMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self) +void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self) { insert(serializer, self.function); @@ -3633,7 +3634,7 @@ void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& s } } -void extract(Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement& self) +void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurement& self) { extract(serializer, self.function); @@ -3652,7 +3653,7 @@ void extract(Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement& self) } } -void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self) +void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self) { insert(serializer, self.enable); @@ -3665,7 +3666,7 @@ void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement::R insert(serializer, self.minimum_uncertainty); } -void extract(Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self) +void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self) { extract(serializer, self.enable); @@ -3682,7 +3683,7 @@ void extract(Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement::Respon TypedResult writeMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool enable, float frequency, float highLimit, float highLimitUncertainty, float minimumUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -3697,22 +3698,22 @@ TypedResult writeMagDipAngleErrorAdaptiveMe assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -3737,34 +3738,34 @@ TypedResult readMagDipAngleErrorAdaptiveMea TypedResult saveMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AidingMeasurementEnable& self) +void insert(::microstrain::Buffer& serializer, const AidingMeasurementEnable& self) { insert(serializer, self.function); @@ -3776,7 +3777,7 @@ void insert(Serializer& serializer, const AidingMeasurementEnable& self) } } -void extract(Serializer& serializer, AidingMeasurementEnable& self) +void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable& self) { extract(serializer, self.function); @@ -3789,14 +3790,14 @@ void extract(Serializer& serializer, AidingMeasurementEnable& self) } } -void insert(Serializer& serializer, const AidingMeasurementEnable::Response& self) +void insert(::microstrain::Buffer& serializer, const AidingMeasurementEnable::Response& self) { insert(serializer, self.aiding_source); insert(serializer, self.enable); } -void extract(Serializer& serializer, AidingMeasurementEnable::Response& self) +void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable::Response& self) { extract(serializer, self.aiding_source); @@ -3807,7 +3808,7 @@ void extract(Serializer& serializer, AidingMeasurementEnable::Response& self) TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, aidingSource); @@ -3816,12 +3817,12 @@ TypedResult writeAidingMeasurementEnable(C::mip_interfa assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); } TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, aidingSource); @@ -3829,11 +3830,11 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length(), REPLY_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, aidingSource); @@ -3848,45 +3849,45 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac TypedResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, aidingSource); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); } TypedResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, aidingSource); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); } TypedResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, aidingSource); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const Run& self) +void insert(::microstrain::Buffer& serializer, const Run& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, Run& self) +void extract(::microstrain::Buffer& serializer, Run& self) { (void)serializer; (void)self; @@ -3896,7 +3897,7 @@ TypedResult run(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RUN, NULL, 0); } -void insert(Serializer& serializer, const KinematicConstraint& self) +void insert(::microstrain::Buffer& serializer, const KinematicConstraint& self) { insert(serializer, self.function); @@ -3910,7 +3911,7 @@ void insert(Serializer& serializer, const KinematicConstraint& self) } } -void extract(Serializer& serializer, KinematicConstraint& self) +void extract(::microstrain::Buffer& serializer, KinematicConstraint& self) { extract(serializer, self.function); @@ -3925,7 +3926,7 @@ void extract(Serializer& serializer, KinematicConstraint& self) } } -void insert(Serializer& serializer, const KinematicConstraint::Response& self) +void insert(::microstrain::Buffer& serializer, const KinematicConstraint::Response& self) { insert(serializer, self.acceleration_constraint_selection); @@ -3934,7 +3935,7 @@ void insert(Serializer& serializer, const KinematicConstraint::Response& self) insert(serializer, self.angular_constraint_selection); } -void extract(Serializer& serializer, KinematicConstraint::Response& self) +void extract(::microstrain::Buffer& serializer, KinematicConstraint::Response& self) { extract(serializer, self.acceleration_constraint_selection); @@ -3947,7 +3948,7 @@ void extract(Serializer& serializer, KinematicConstraint::Response& self) TypedResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, accelerationConstraintSelection); @@ -3958,22 +3959,22 @@ TypedResult writeKinematicConstraint(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); } TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_KINEMATIC_CONSTRAINT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length(), REPLY_KINEMATIC_CONSTRAINT, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(accelerationConstraintSelectionOut); extract(deserializer, *accelerationConstraintSelectionOut); @@ -3992,34 +3993,34 @@ TypedResult readKinematicConstraint(C::mip_interface& devic TypedResult saveKinematicConstraint(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); } TypedResult loadKinematicConstraint(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); } TypedResult defaultKinematicConstraint(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const InitializationConfiguration& self) +void insert(::microstrain::Buffer& serializer, const InitializationConfiguration& self) { insert(serializer, self.function); @@ -4047,7 +4048,7 @@ void insert(Serializer& serializer, const InitializationConfiguration& self) } } -void extract(Serializer& serializer, InitializationConfiguration& self) +void extract(::microstrain::Buffer& serializer, InitializationConfiguration& self) { extract(serializer, self.function); @@ -4076,7 +4077,7 @@ void extract(Serializer& serializer, InitializationConfiguration& self) } } -void insert(Serializer& serializer, const InitializationConfiguration::Response& self) +void insert(::microstrain::Buffer& serializer, const InitializationConfiguration::Response& self) { insert(serializer, self.wait_for_run_command); @@ -4099,7 +4100,7 @@ void insert(Serializer& serializer, const InitializationConfiguration::Response& insert(serializer, self.reference_frame_selector); } -void extract(Serializer& serializer, InitializationConfiguration::Response& self) +void extract(::microstrain::Buffer& serializer, InitializationConfiguration::Response& self) { extract(serializer, self.wait_for_run_command); @@ -4126,7 +4127,7 @@ void extract(Serializer& serializer, InitializationConfiguration::Response& self TypedResult writeInitializationConfiguration(C::mip_interface& device, uint8_t waitForRunCommand, InitializationConfiguration::InitialConditionSource initialCondSrc, InitializationConfiguration::AlignmentSelector autoHeadingAlignmentSelector, float initialHeading, float initialPitch, float initialRoll, const float* initialPosition, const float* initialVelocity, FilterReferenceFrame referenceFrameSelector) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, waitForRunCommand); @@ -4153,22 +4154,22 @@ TypedResult writeInitializationConfiguration(C::mip assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_INITIALIZATION_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_INITIALIZATION_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(waitForRunCommandOut); extract(deserializer, *waitForRunCommandOut); @@ -4207,34 +4208,34 @@ TypedResult readInitializationConfiguration(C::mip_ TypedResult saveInitializationConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult loadInitializationConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultInitializationConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const AdaptiveFilterOptions& self) +void insert(::microstrain::Buffer& serializer, const AdaptiveFilterOptions& self) { insert(serializer, self.function); @@ -4246,7 +4247,7 @@ void insert(Serializer& serializer, const AdaptiveFilterOptions& self) } } -void extract(Serializer& serializer, AdaptiveFilterOptions& self) +void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions& self) { extract(serializer, self.function); @@ -4259,14 +4260,14 @@ void extract(Serializer& serializer, AdaptiveFilterOptions& self) } } -void insert(Serializer& serializer, const AdaptiveFilterOptions::Response& self) +void insert(::microstrain::Buffer& serializer, const AdaptiveFilterOptions::Response& self) { insert(serializer, self.level); insert(serializer, self.time_limit); } -void extract(Serializer& serializer, AdaptiveFilterOptions::Response& self) +void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions::Response& self) { extract(serializer, self.level); @@ -4277,7 +4278,7 @@ void extract(Serializer& serializer, AdaptiveFilterOptions::Response& self) TypedResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, level); @@ -4286,22 +4287,22 @@ TypedResult writeAdaptiveFilterOptions(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); } TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length(), REPLY_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(levelOut); extract(deserializer, *levelOut); @@ -4317,34 +4318,34 @@ TypedResult readAdaptiveFilterOptions(C::mip_interface& d TypedResult saveAdaptiveFilterOptions(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); } TypedResult loadAdaptiveFilterOptions(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); } TypedResult defaultAdaptiveFilterOptions(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const MultiAntennaOffset& self) +void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset& self) { insert(serializer, self.function); @@ -4357,7 +4358,7 @@ void insert(Serializer& serializer, const MultiAntennaOffset& self) } } -void extract(Serializer& serializer, MultiAntennaOffset& self) +void extract(::microstrain::Buffer& serializer, MultiAntennaOffset& self) { extract(serializer, self.function); @@ -4371,7 +4372,7 @@ void extract(Serializer& serializer, MultiAntennaOffset& self) } } -void insert(Serializer& serializer, const MultiAntennaOffset::Response& self) +void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset::Response& self) { insert(serializer, self.receiver_id); @@ -4379,7 +4380,7 @@ void insert(Serializer& serializer, const MultiAntennaOffset::Response& self) insert(serializer, self.antenna_offset[i]); } -void extract(Serializer& serializer, MultiAntennaOffset::Response& self) +void extract(::microstrain::Buffer& serializer, MultiAntennaOffset::Response& self) { extract(serializer, self.receiver_id); @@ -4391,7 +4392,7 @@ void extract(Serializer& serializer, MultiAntennaOffset::Response& self) TypedResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, receiverId); @@ -4402,12 +4403,12 @@ TypedResult writeMultiAntennaOffset(C::mip_interface& device assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, receiverId); @@ -4415,11 +4416,11 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_MULTI_ANTENNA_OFFSET, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_MULTI_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, receiverId); @@ -4435,40 +4436,40 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, TypedResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, receiverId); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, receiverId); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, receiverId); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const RelPosConfiguration& self) +void insert(::microstrain::Buffer& serializer, const RelPosConfiguration& self) { insert(serializer, self.function); @@ -4483,7 +4484,7 @@ void insert(Serializer& serializer, const RelPosConfiguration& self) } } -void extract(Serializer& serializer, RelPosConfiguration& self) +void extract(::microstrain::Buffer& serializer, RelPosConfiguration& self) { extract(serializer, self.function); @@ -4499,7 +4500,7 @@ void extract(Serializer& serializer, RelPosConfiguration& self) } } -void insert(Serializer& serializer, const RelPosConfiguration::Response& self) +void insert(::microstrain::Buffer& serializer, const RelPosConfiguration::Response& self) { insert(serializer, self.source); @@ -4509,7 +4510,7 @@ void insert(Serializer& serializer, const RelPosConfiguration::Response& self) insert(serializer, self.reference_coordinates[i]); } -void extract(Serializer& serializer, RelPosConfiguration::Response& self) +void extract(::microstrain::Buffer& serializer, RelPosConfiguration::Response& self) { extract(serializer, self.source); @@ -4523,7 +4524,7 @@ void extract(Serializer& serializer, RelPosConfiguration::Response& self) TypedResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -4536,22 +4537,22 @@ TypedResult writeRelPosConfiguration(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_REL_POS_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_REL_POS_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -4571,34 +4572,34 @@ TypedResult readRelPosConfiguration(C::mip_interface& devic TypedResult saveRelPosConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult loadRelPosConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultRelPosConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const RefPointLeverArm& self) +void insert(::microstrain::Buffer& serializer, const RefPointLeverArm& self) { insert(serializer, self.function); @@ -4611,7 +4612,7 @@ void insert(Serializer& serializer, const RefPointLeverArm& self) } } -void extract(Serializer& serializer, RefPointLeverArm& self) +void extract(::microstrain::Buffer& serializer, RefPointLeverArm& self) { extract(serializer, self.function); @@ -4625,7 +4626,7 @@ void extract(Serializer& serializer, RefPointLeverArm& self) } } -void insert(Serializer& serializer, const RefPointLeverArm::Response& self) +void insert(::microstrain::Buffer& serializer, const RefPointLeverArm::Response& self) { insert(serializer, self.ref_point_sel); @@ -4633,7 +4634,7 @@ void insert(Serializer& serializer, const RefPointLeverArm::Response& self) insert(serializer, self.lever_arm_offset[i]); } -void extract(Serializer& serializer, RefPointLeverArm::Response& self) +void extract(::microstrain::Buffer& serializer, RefPointLeverArm::Response& self) { extract(serializer, self.ref_point_sel); @@ -4645,7 +4646,7 @@ void extract(Serializer& serializer, RefPointLeverArm::Response& self) TypedResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, refPointSel); @@ -4656,22 +4657,22 @@ TypedResult writeRefPointLeverArm(C::mip_interface& device, Re assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); } TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_REF_POINT_LEVER_ARM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length(), REPLY_REF_POINT_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(refPointSelOut); extract(deserializer, *refPointSelOut); @@ -4688,34 +4689,34 @@ TypedResult readRefPointLeverArm(C::mip_interface& device, Ref TypedResult saveRefPointLeverArm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); } TypedResult loadRefPointLeverArm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); } TypedResult defaultRefPointLeverArm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SpeedMeasurement& self) +void insert(::microstrain::Buffer& serializer, const SpeedMeasurement& self) { insert(serializer, self.source); @@ -4726,7 +4727,7 @@ void insert(Serializer& serializer, const SpeedMeasurement& self) insert(serializer, self.speed_uncertainty); } -void extract(Serializer& serializer, SpeedMeasurement& self) +void extract(::microstrain::Buffer& serializer, SpeedMeasurement& self) { extract(serializer, self.source); @@ -4741,7 +4742,7 @@ void extract(Serializer& serializer, SpeedMeasurement& self) TypedResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, source); @@ -4753,9 +4754,9 @@ TypedResult speedMeasurement(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_MEASUREMENT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_MEASUREMENT, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SpeedLeverArm& self) +void insert(::microstrain::Buffer& serializer, const SpeedLeverArm& self) { insert(serializer, self.function); @@ -4768,7 +4769,7 @@ void insert(Serializer& serializer, const SpeedLeverArm& self) } } -void extract(Serializer& serializer, SpeedLeverArm& self) +void extract(::microstrain::Buffer& serializer, SpeedLeverArm& self) { extract(serializer, self.function); @@ -4782,7 +4783,7 @@ void extract(Serializer& serializer, SpeedLeverArm& self) } } -void insert(Serializer& serializer, const SpeedLeverArm::Response& self) +void insert(::microstrain::Buffer& serializer, const SpeedLeverArm::Response& self) { insert(serializer, self.source); @@ -4790,7 +4791,7 @@ void insert(Serializer& serializer, const SpeedLeverArm::Response& self) insert(serializer, self.lever_arm_offset[i]); } -void extract(Serializer& serializer, SpeedLeverArm::Response& self) +void extract(::microstrain::Buffer& serializer, SpeedLeverArm::Response& self) { extract(serializer, self.source); @@ -4802,7 +4803,7 @@ void extract(Serializer& serializer, SpeedLeverArm::Response& self) TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -4813,12 +4814,12 @@ TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); } TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, source); @@ -4826,11 +4827,11 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SPEED_LEVER_ARM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length(), REPLY_SPEED_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); extract(deserializer, source); @@ -4846,40 +4847,40 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, source); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); } TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, source); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); } TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, source); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const WheeledVehicleConstraintControl& self) +void insert(::microstrain::Buffer& serializer, const WheeledVehicleConstraintControl& self) { insert(serializer, self.function); @@ -4889,7 +4890,7 @@ void insert(Serializer& serializer, const WheeledVehicleConstraintControl& self) } } -void extract(Serializer& serializer, WheeledVehicleConstraintControl& self) +void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl& self) { extract(serializer, self.function); @@ -4900,12 +4901,12 @@ void extract(Serializer& serializer, WheeledVehicleConstraintControl& self) } } -void insert(Serializer& serializer, const WheeledVehicleConstraintControl::Response& self) +void insert(::microstrain::Buffer& serializer, const WheeledVehicleConstraintControl::Response& self) { insert(serializer, self.enable); } -void extract(Serializer& serializer, WheeledVehicleConstraintControl::Response& self) +void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl::Response& self) { extract(serializer, self.enable); @@ -4914,29 +4915,29 @@ void extract(Serializer& serializer, WheeledVehicleConstraintControl::Response& TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -4949,34 +4950,34 @@ TypedResult readWheeledVehicleConstraintControl TypedResult saveWheeledVehicleConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadWheeledVehicleConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultWheeledVehicleConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const VerticalGyroConstraintControl& self) +void insert(::microstrain::Buffer& serializer, const VerticalGyroConstraintControl& self) { insert(serializer, self.function); @@ -4986,7 +4987,7 @@ void insert(Serializer& serializer, const VerticalGyroConstraintControl& self) } } -void extract(Serializer& serializer, VerticalGyroConstraintControl& self) +void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl& self) { extract(serializer, self.function); @@ -4997,12 +4998,12 @@ void extract(Serializer& serializer, VerticalGyroConstraintControl& self) } } -void insert(Serializer& serializer, const VerticalGyroConstraintControl::Response& self) +void insert(::microstrain::Buffer& serializer, const VerticalGyroConstraintControl::Response& self) { insert(serializer, self.enable); } -void extract(Serializer& serializer, VerticalGyroConstraintControl::Response& self) +void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl::Response& self) { extract(serializer, self.enable); @@ -5011,29 +5012,29 @@ void extract(Serializer& serializer, VerticalGyroConstraintControl::Response& se TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -5046,34 +5047,34 @@ TypedResult readVerticalGyroConstraintControl(C:: TypedResult saveVerticalGyroConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadVerticalGyroConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultVerticalGyroConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GnssAntennaCalControl& self) +void insert(::microstrain::Buffer& serializer, const GnssAntennaCalControl& self) { insert(serializer, self.function); @@ -5085,7 +5086,7 @@ void insert(Serializer& serializer, const GnssAntennaCalControl& self) } } -void extract(Serializer& serializer, GnssAntennaCalControl& self) +void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl& self) { extract(serializer, self.function); @@ -5098,14 +5099,14 @@ void extract(Serializer& serializer, GnssAntennaCalControl& self) } } -void insert(Serializer& serializer, const GnssAntennaCalControl::Response& self) +void insert(::microstrain::Buffer& serializer, const GnssAntennaCalControl::Response& self) { insert(serializer, self.enable); insert(serializer, self.max_offset); } -void extract(Serializer& serializer, GnssAntennaCalControl::Response& self) +void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl::Response& self) { extract(serializer, self.enable); @@ -5116,7 +5117,7 @@ void extract(Serializer& serializer, GnssAntennaCalControl::Response& self) TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -5125,22 +5126,22 @@ TypedResult writeGnssAntennaCalControl(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -5156,39 +5157,39 @@ TypedResult readGnssAntennaCalControl(C::mip_interface& d TypedResult saveGnssAntennaCalControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadGnssAntennaCalControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultGnssAntennaCalControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const SetInitialHeading& self) +void insert(::microstrain::Buffer& serializer, const SetInitialHeading& self) { insert(serializer, self.heading); } -void extract(Serializer& serializer, SetInitialHeading& self) +void extract(::microstrain::Buffer& serializer, SetInitialHeading& self) { extract(serializer, self.heading); @@ -5197,13 +5198,13 @@ void extract(Serializer& serializer, SetInitialHeading& self) TypedResult setInitialHeading(C::mip_interface& device, float heading) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, heading); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_HEADING, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_HEADING, buffer, (uint8_t)serializer.length()); } } // namespace commands_filter diff --git a/src/mip/definitions/commands_filter.hpp b/src/mip/definitions/commands_filter.hpp index 8f54608a1..fe38fd00f 100644 --- a/src/mip/definitions/commands_filter.hpp +++ b/src/mip/definitions/commands_filter.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -212,8 +212,8 @@ struct Reset } typedef void Response; }; -void insert(Serializer& serializer, const Reset& self); -void extract(Serializer& serializer, Reset& self); +void insert(::microstrain::Buffer& serializer, const Reset& self); +void extract(::microstrain::Buffer& serializer, Reset& self); TypedResult reset(C::mip_interface& device); @@ -262,8 +262,8 @@ struct SetInitialAttitude } typedef void Response; }; -void insert(Serializer& serializer, const SetInitialAttitude& self); -void extract(Serializer& serializer, SetInitialAttitude& self); +void insert(::microstrain::Buffer& serializer, const SetInitialAttitude& self); +void extract(::microstrain::Buffer& serializer, SetInitialAttitude& self); TypedResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading); @@ -384,11 +384,11 @@ struct EstimationControl } }; }; -void insert(Serializer& serializer, const EstimationControl& self); -void extract(Serializer& serializer, EstimationControl& self); +void insert(::microstrain::Buffer& serializer, const EstimationControl& self); +void extract(::microstrain::Buffer& serializer, EstimationControl& self); -void insert(Serializer& serializer, const EstimationControl::Response& self); -void extract(Serializer& serializer, EstimationControl::Response& self); +void insert(::microstrain::Buffer& serializer, const EstimationControl::Response& self); +void extract(::microstrain::Buffer& serializer, EstimationControl::Response& self); TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable); TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut); @@ -439,8 +439,8 @@ struct ExternalGnssUpdate } typedef void Response; }; -void insert(Serializer& serializer, const ExternalGnssUpdate& self); -void extract(Serializer& serializer, ExternalGnssUpdate& self); +void insert(::microstrain::Buffer& serializer, const ExternalGnssUpdate& self); +void extract(::microstrain::Buffer& serializer, ExternalGnssUpdate& self); TypedResult externalGnssUpdate(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, double latitude, double longitude, double height, const float* velocity, const float* posUncertainty, const float* velUncertainty); @@ -490,8 +490,8 @@ struct ExternalHeadingUpdate } typedef void Response; }; -void insert(Serializer& serializer, const ExternalHeadingUpdate& self); -void extract(Serializer& serializer, ExternalHeadingUpdate& self); +void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdate& self); +void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdate& self); TypedResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type); @@ -547,8 +547,8 @@ struct ExternalHeadingUpdateWithTime } typedef void Response; }; -void insert(Serializer& serializer, const ExternalHeadingUpdateWithTime& self); -void extract(Serializer& serializer, ExternalHeadingUpdateWithTime& self); +void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdateWithTime& self); +void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdateWithTime& self); TypedResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type); @@ -651,11 +651,11 @@ struct TareOrientation } }; }; -void insert(Serializer& serializer, const TareOrientation& self); -void extract(Serializer& serializer, TareOrientation& self); +void insert(::microstrain::Buffer& serializer, const TareOrientation& self); +void extract(::microstrain::Buffer& serializer, TareOrientation& self); -void insert(Serializer& serializer, const TareOrientation::Response& self); -void extract(Serializer& serializer, TareOrientation::Response& self); +void insert(::microstrain::Buffer& serializer, const TareOrientation::Response& self); +void extract(::microstrain::Buffer& serializer, TareOrientation::Response& self); TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes); TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut); @@ -735,11 +735,11 @@ struct VehicleDynamicsMode } }; }; -void insert(Serializer& serializer, const VehicleDynamicsMode& self); -void extract(Serializer& serializer, VehicleDynamicsMode& self); +void insert(::microstrain::Buffer& serializer, const VehicleDynamicsMode& self); +void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode& self); -void insert(Serializer& serializer, const VehicleDynamicsMode::Response& self); -void extract(Serializer& serializer, VehicleDynamicsMode::Response& self); +void insert(::microstrain::Buffer& serializer, const VehicleDynamicsMode::Response& self); +void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode::Response& self); TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode); TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut); @@ -837,11 +837,11 @@ struct SensorToVehicleRotationEuler } }; }; -void insert(Serializer& serializer, const SensorToVehicleRotationEuler& self); -void extract(Serializer& serializer, SensorToVehicleRotationEuler& self); +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEuler& self); +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler& self); -void insert(Serializer& serializer, const SensorToVehicleRotationEuler::Response& self); -void extract(Serializer& serializer, SensorToVehicleRotationEuler::Response& self); +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEuler::Response& self); +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler::Response& self); TypedResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw); TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut); @@ -941,11 +941,11 @@ struct SensorToVehicleRotationDcm } }; }; -void insert(Serializer& serializer, const SensorToVehicleRotationDcm& self); -void extract(Serializer& serializer, SensorToVehicleRotationDcm& self); +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationDcm& self); +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm& self); -void insert(Serializer& serializer, const SensorToVehicleRotationDcm::Response& self); -void extract(Serializer& serializer, SensorToVehicleRotationDcm::Response& self); +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationDcm::Response& self); +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm::Response& self); TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm); TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut); @@ -1044,11 +1044,11 @@ struct SensorToVehicleRotationQuaternion } }; }; -void insert(Serializer& serializer, const SensorToVehicleRotationQuaternion& self); -void extract(Serializer& serializer, SensorToVehicleRotationQuaternion& self); +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationQuaternion& self); +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternion& self); -void insert(Serializer& serializer, const SensorToVehicleRotationQuaternion::Response& self); -void extract(Serializer& serializer, SensorToVehicleRotationQuaternion::Response& self); +void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationQuaternion::Response& self); +void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternion::Response& self); TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat); TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut); @@ -1128,11 +1128,11 @@ struct SensorToVehicleOffset } }; }; -void insert(Serializer& serializer, const SensorToVehicleOffset& self); -void extract(Serializer& serializer, SensorToVehicleOffset& self); +void insert(::microstrain::Buffer& serializer, const SensorToVehicleOffset& self); +void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset& self); -void insert(Serializer& serializer, const SensorToVehicleOffset::Response& self); -void extract(Serializer& serializer, SensorToVehicleOffset::Response& self); +void insert(::microstrain::Buffer& serializer, const SensorToVehicleOffset::Response& self); +void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset::Response& self); TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset); TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut); @@ -1209,11 +1209,11 @@ struct AntennaOffset } }; }; -void insert(Serializer& serializer, const AntennaOffset& self); -void extract(Serializer& serializer, AntennaOffset& self); +void insert(::microstrain::Buffer& serializer, const AntennaOffset& self); +void extract(::microstrain::Buffer& serializer, AntennaOffset& self); -void insert(Serializer& serializer, const AntennaOffset::Response& self); -void extract(Serializer& serializer, AntennaOffset::Response& self); +void insert(::microstrain::Buffer& serializer, const AntennaOffset::Response& self); +void extract(::microstrain::Buffer& serializer, AntennaOffset::Response& self); TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset); TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut); @@ -1297,11 +1297,11 @@ struct GnssSource } }; }; -void insert(Serializer& serializer, const GnssSource& self); -void extract(Serializer& serializer, GnssSource& self); +void insert(::microstrain::Buffer& serializer, const GnssSource& self); +void extract(::microstrain::Buffer& serializer, GnssSource& self); -void insert(Serializer& serializer, const GnssSource::Response& self); -void extract(Serializer& serializer, GnssSource::Response& self); +void insert(::microstrain::Buffer& serializer, const GnssSource::Response& self); +void extract(::microstrain::Buffer& serializer, GnssSource::Response& self); TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source); TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut); @@ -1396,11 +1396,11 @@ struct HeadingSource } }; }; -void insert(Serializer& serializer, const HeadingSource& self); -void extract(Serializer& serializer, HeadingSource& self); +void insert(::microstrain::Buffer& serializer, const HeadingSource& self); +void extract(::microstrain::Buffer& serializer, HeadingSource& self); -void insert(Serializer& serializer, const HeadingSource::Response& self); -void extract(Serializer& serializer, HeadingSource::Response& self); +void insert(::microstrain::Buffer& serializer, const HeadingSource::Response& self); +void extract(::microstrain::Buffer& serializer, HeadingSource::Response& self); TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source); TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut); @@ -1480,11 +1480,11 @@ struct AutoInitControl } }; }; -void insert(Serializer& serializer, const AutoInitControl& self); -void extract(Serializer& serializer, AutoInitControl& self); +void insert(::microstrain::Buffer& serializer, const AutoInitControl& self); +void extract(::microstrain::Buffer& serializer, AutoInitControl& self); -void insert(Serializer& serializer, const AutoInitControl::Response& self); -void extract(Serializer& serializer, AutoInitControl::Response& self); +void insert(::microstrain::Buffer& serializer, const AutoInitControl::Response& self); +void extract(::microstrain::Buffer& serializer, AutoInitControl::Response& self); TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable); TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut); @@ -1562,11 +1562,11 @@ struct AccelNoise } }; }; -void insert(Serializer& serializer, const AccelNoise& self); -void extract(Serializer& serializer, AccelNoise& self); +void insert(::microstrain::Buffer& serializer, const AccelNoise& self); +void extract(::microstrain::Buffer& serializer, AccelNoise& self); -void insert(Serializer& serializer, const AccelNoise::Response& self); -void extract(Serializer& serializer, AccelNoise::Response& self); +void insert(::microstrain::Buffer& serializer, const AccelNoise::Response& self); +void extract(::microstrain::Buffer& serializer, AccelNoise::Response& self); TypedResult writeAccelNoise(C::mip_interface& device, const float* noise); TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut); @@ -1644,11 +1644,11 @@ struct GyroNoise } }; }; -void insert(Serializer& serializer, const GyroNoise& self); -void extract(Serializer& serializer, GyroNoise& self); +void insert(::microstrain::Buffer& serializer, const GyroNoise& self); +void extract(::microstrain::Buffer& serializer, GyroNoise& self); -void insert(Serializer& serializer, const GyroNoise::Response& self); -void extract(Serializer& serializer, GyroNoise::Response& self); +void insert(::microstrain::Buffer& serializer, const GyroNoise::Response& self); +void extract(::microstrain::Buffer& serializer, GyroNoise::Response& self); TypedResult writeGyroNoise(C::mip_interface& device, const float* noise); TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut); @@ -1725,11 +1725,11 @@ struct AccelBiasModel } }; }; -void insert(Serializer& serializer, const AccelBiasModel& self); -void extract(Serializer& serializer, AccelBiasModel& self); +void insert(::microstrain::Buffer& serializer, const AccelBiasModel& self); +void extract(::microstrain::Buffer& serializer, AccelBiasModel& self); -void insert(Serializer& serializer, const AccelBiasModel::Response& self); -void extract(Serializer& serializer, AccelBiasModel::Response& self); +void insert(::microstrain::Buffer& serializer, const AccelBiasModel::Response& self); +void extract(::microstrain::Buffer& serializer, AccelBiasModel::Response& self); TypedResult writeAccelBiasModel(C::mip_interface& device, const float* beta, const float* noise); TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut); @@ -1806,11 +1806,11 @@ struct GyroBiasModel } }; }; -void insert(Serializer& serializer, const GyroBiasModel& self); -void extract(Serializer& serializer, GyroBiasModel& self); +void insert(::microstrain::Buffer& serializer, const GyroBiasModel& self); +void extract(::microstrain::Buffer& serializer, GyroBiasModel& self); -void insert(Serializer& serializer, const GyroBiasModel::Response& self); -void extract(Serializer& serializer, GyroBiasModel::Response& self); +void insert(::microstrain::Buffer& serializer, const GyroBiasModel::Response& self); +void extract(::microstrain::Buffer& serializer, GyroBiasModel::Response& self); TypedResult writeGyroBiasModel(C::mip_interface& device, const float* beta, const float* noise); TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut); @@ -1892,11 +1892,11 @@ struct AltitudeAiding } }; }; -void insert(Serializer& serializer, const AltitudeAiding& self); -void extract(Serializer& serializer, AltitudeAiding& self); +void insert(::microstrain::Buffer& serializer, const AltitudeAiding& self); +void extract(::microstrain::Buffer& serializer, AltitudeAiding& self); -void insert(Serializer& serializer, const AltitudeAiding::Response& self); -void extract(Serializer& serializer, AltitudeAiding::Response& self); +void insert(::microstrain::Buffer& serializer, const AltitudeAiding::Response& self); +void extract(::microstrain::Buffer& serializer, AltitudeAiding::Response& self); TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector); TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut); @@ -1975,11 +1975,11 @@ struct PitchRollAiding } }; }; -void insert(Serializer& serializer, const PitchRollAiding& self); -void extract(Serializer& serializer, PitchRollAiding& self); +void insert(::microstrain::Buffer& serializer, const PitchRollAiding& self); +void extract(::microstrain::Buffer& serializer, PitchRollAiding& self); -void insert(Serializer& serializer, const PitchRollAiding::Response& self); -void extract(Serializer& serializer, PitchRollAiding::Response& self); +void insert(::microstrain::Buffer& serializer, const PitchRollAiding::Response& self); +void extract(::microstrain::Buffer& serializer, PitchRollAiding::Response& self); TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source); TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut); @@ -2054,11 +2054,11 @@ struct AutoZupt } }; }; -void insert(Serializer& serializer, const AutoZupt& self); -void extract(Serializer& serializer, AutoZupt& self); +void insert(::microstrain::Buffer& serializer, const AutoZupt& self); +void extract(::microstrain::Buffer& serializer, AutoZupt& self); -void insert(Serializer& serializer, const AutoZupt::Response& self); -void extract(Serializer& serializer, AutoZupt::Response& self); +void insert(::microstrain::Buffer& serializer, const AutoZupt::Response& self); +void extract(::microstrain::Buffer& serializer, AutoZupt::Response& self); TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold); TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut); @@ -2134,11 +2134,11 @@ struct AutoAngularZupt } }; }; -void insert(Serializer& serializer, const AutoAngularZupt& self); -void extract(Serializer& serializer, AutoAngularZupt& self); +void insert(::microstrain::Buffer& serializer, const AutoAngularZupt& self); +void extract(::microstrain::Buffer& serializer, AutoAngularZupt& self); -void insert(Serializer& serializer, const AutoAngularZupt::Response& self); -void extract(Serializer& serializer, AutoAngularZupt::Response& self); +void insert(::microstrain::Buffer& serializer, const AutoAngularZupt::Response& self); +void extract(::microstrain::Buffer& serializer, AutoAngularZupt::Response& self); TypedResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold); TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut); @@ -2177,8 +2177,8 @@ struct CommandedZupt } typedef void Response; }; -void insert(Serializer& serializer, const CommandedZupt& self); -void extract(Serializer& serializer, CommandedZupt& self); +void insert(::microstrain::Buffer& serializer, const CommandedZupt& self); +void extract(::microstrain::Buffer& serializer, CommandedZupt& self); TypedResult commandedZupt(C::mip_interface& device); @@ -2213,8 +2213,8 @@ struct CommandedAngularZupt } typedef void Response; }; -void insert(Serializer& serializer, const CommandedAngularZupt& self); -void extract(Serializer& serializer, CommandedAngularZupt& self); +void insert(::microstrain::Buffer& serializer, const CommandedAngularZupt& self); +void extract(::microstrain::Buffer& serializer, CommandedAngularZupt& self); TypedResult commandedAngularZupt(C::mip_interface& device); @@ -2265,8 +2265,8 @@ struct MagCaptureAutoCal typedef void Response; }; -void insert(Serializer& serializer, const MagCaptureAutoCal& self); -void extract(Serializer& serializer, MagCaptureAutoCal& self); +void insert(::microstrain::Buffer& serializer, const MagCaptureAutoCal& self); +void extract(::microstrain::Buffer& serializer, MagCaptureAutoCal& self); TypedResult writeMagCaptureAutoCal(C::mip_interface& device); TypedResult saveMagCaptureAutoCal(C::mip_interface& device); @@ -2340,11 +2340,11 @@ struct GravityNoise } }; }; -void insert(Serializer& serializer, const GravityNoise& self); -void extract(Serializer& serializer, GravityNoise& self); +void insert(::microstrain::Buffer& serializer, const GravityNoise& self); +void extract(::microstrain::Buffer& serializer, GravityNoise& self); -void insert(Serializer& serializer, const GravityNoise::Response& self); -void extract(Serializer& serializer, GravityNoise::Response& self); +void insert(::microstrain::Buffer& serializer, const GravityNoise::Response& self); +void extract(::microstrain::Buffer& serializer, GravityNoise::Response& self); TypedResult writeGravityNoise(C::mip_interface& device, const float* noise); TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut); @@ -2421,11 +2421,11 @@ struct PressureAltitudeNoise } }; }; -void insert(Serializer& serializer, const PressureAltitudeNoise& self); -void extract(Serializer& serializer, PressureAltitudeNoise& self); +void insert(::microstrain::Buffer& serializer, const PressureAltitudeNoise& self); +void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise& self); -void insert(Serializer& serializer, const PressureAltitudeNoise::Response& self); -void extract(Serializer& serializer, PressureAltitudeNoise::Response& self); +void insert(::microstrain::Buffer& serializer, const PressureAltitudeNoise::Response& self); +void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise::Response& self); TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise); TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut); @@ -2504,11 +2504,11 @@ struct HardIronOffsetNoise } }; }; -void insert(Serializer& serializer, const HardIronOffsetNoise& self); -void extract(Serializer& serializer, HardIronOffsetNoise& self); +void insert(::microstrain::Buffer& serializer, const HardIronOffsetNoise& self); +void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise& self); -void insert(Serializer& serializer, const HardIronOffsetNoise::Response& self); -void extract(Serializer& serializer, HardIronOffsetNoise::Response& self); +void insert(::microstrain::Buffer& serializer, const HardIronOffsetNoise::Response& self); +void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise::Response& self); TypedResult writeHardIronOffsetNoise(C::mip_interface& device, const float* noise); TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut); @@ -2586,11 +2586,11 @@ struct SoftIronMatrixNoise } }; }; -void insert(Serializer& serializer, const SoftIronMatrixNoise& self); -void extract(Serializer& serializer, SoftIronMatrixNoise& self); +void insert(::microstrain::Buffer& serializer, const SoftIronMatrixNoise& self); +void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise& self); -void insert(Serializer& serializer, const SoftIronMatrixNoise::Response& self); -void extract(Serializer& serializer, SoftIronMatrixNoise::Response& self); +void insert(::microstrain::Buffer& serializer, const SoftIronMatrixNoise::Response& self); +void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise::Response& self); TypedResult writeSoftIronMatrixNoise(C::mip_interface& device, const float* noise); TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut); @@ -2668,11 +2668,11 @@ struct MagNoise } }; }; -void insert(Serializer& serializer, const MagNoise& self); -void extract(Serializer& serializer, MagNoise& self); +void insert(::microstrain::Buffer& serializer, const MagNoise& self); +void extract(::microstrain::Buffer& serializer, MagNoise& self); -void insert(Serializer& serializer, const MagNoise::Response& self); -void extract(Serializer& serializer, MagNoise::Response& self); +void insert(::microstrain::Buffer& serializer, const MagNoise::Response& self); +void extract(::microstrain::Buffer& serializer, MagNoise::Response& self); TypedResult writeMagNoise(C::mip_interface& device, const float* noise); TypedResult readMagNoise(C::mip_interface& device, float* noiseOut); @@ -2750,11 +2750,11 @@ struct InclinationSource } }; }; -void insert(Serializer& serializer, const InclinationSource& self); -void extract(Serializer& serializer, InclinationSource& self); +void insert(::microstrain::Buffer& serializer, const InclinationSource& self); +void extract(::microstrain::Buffer& serializer, InclinationSource& self); -void insert(Serializer& serializer, const InclinationSource::Response& self); -void extract(Serializer& serializer, InclinationSource::Response& self); +void insert(::microstrain::Buffer& serializer, const InclinationSource::Response& self); +void extract(::microstrain::Buffer& serializer, InclinationSource::Response& self); TypedResult writeInclinationSource(C::mip_interface& device, FilterMagParamSource source, float inclination); TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut); @@ -2832,11 +2832,11 @@ struct MagneticDeclinationSource } }; }; -void insert(Serializer& serializer, const MagneticDeclinationSource& self); -void extract(Serializer& serializer, MagneticDeclinationSource& self); +void insert(::microstrain::Buffer& serializer, const MagneticDeclinationSource& self); +void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource& self); -void insert(Serializer& serializer, const MagneticDeclinationSource::Response& self); -void extract(Serializer& serializer, MagneticDeclinationSource::Response& self); +void insert(::microstrain::Buffer& serializer, const MagneticDeclinationSource::Response& self); +void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource::Response& self); TypedResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource source, float declination); TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut); @@ -2913,11 +2913,11 @@ struct MagFieldMagnitudeSource } }; }; -void insert(Serializer& serializer, const MagFieldMagnitudeSource& self); -void extract(Serializer& serializer, MagFieldMagnitudeSource& self); +void insert(::microstrain::Buffer& serializer, const MagFieldMagnitudeSource& self); +void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource& self); -void insert(Serializer& serializer, const MagFieldMagnitudeSource::Response& self); -void extract(Serializer& serializer, MagFieldMagnitudeSource::Response& self); +void insert(::microstrain::Buffer& serializer, const MagFieldMagnitudeSource::Response& self); +void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource::Response& self); TypedResult writeMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource source, float magnitude); TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut); @@ -2998,11 +2998,11 @@ struct ReferencePosition } }; }; -void insert(Serializer& serializer, const ReferencePosition& self); -void extract(Serializer& serializer, ReferencePosition& self); +void insert(::microstrain::Buffer& serializer, const ReferencePosition& self); +void extract(::microstrain::Buffer& serializer, ReferencePosition& self); -void insert(Serializer& serializer, const ReferencePosition::Response& self); -void extract(Serializer& serializer, ReferencePosition::Response& self); +void insert(::microstrain::Buffer& serializer, const ReferencePosition::Response& self); +void extract(::microstrain::Buffer& serializer, ReferencePosition::Response& self); TypedResult writeReferencePosition(C::mip_interface& device, bool enable, double latitude, double longitude, double altitude); TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut); @@ -3099,11 +3099,11 @@ struct AccelMagnitudeErrorAdaptiveMeasurement } }; }; -void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self); -void extract(Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self); +void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self); +void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self); -void insert(Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self); -void extract(Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self); +void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self); +void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self); TypedResult writeAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty); TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut); @@ -3195,11 +3195,11 @@ struct MagMagnitudeErrorAdaptiveMeasurement } }; }; -void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self); -void extract(Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self); +void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self); +void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self); -void insert(Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self); -void extract(Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self); +void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self); +void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self); TypedResult writeMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty); TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut); @@ -3289,11 +3289,11 @@ struct MagDipAngleErrorAdaptiveMeasurement } }; }; -void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self); -void extract(Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement& self); +void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self); +void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurement& self); -void insert(Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self); -void extract(Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self); +void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self); +void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self); TypedResult writeMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool enable, float frequency, float highLimit, float highLimitUncertainty, float minimumUncertainty); TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut); @@ -3384,11 +3384,11 @@ struct AidingMeasurementEnable } }; }; -void insert(Serializer& serializer, const AidingMeasurementEnable& self); -void extract(Serializer& serializer, AidingMeasurementEnable& self); +void insert(::microstrain::Buffer& serializer, const AidingMeasurementEnable& self); +void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable& self); -void insert(Serializer& serializer, const AidingMeasurementEnable::Response& self); -void extract(Serializer& serializer, AidingMeasurementEnable::Response& self); +void insert(::microstrain::Buffer& serializer, const AidingMeasurementEnable::Response& self); +void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable::Response& self); TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable); TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut); @@ -3429,8 +3429,8 @@ struct Run } typedef void Response; }; -void insert(Serializer& serializer, const Run& self); -void extract(Serializer& serializer, Run& self); +void insert(::microstrain::Buffer& serializer, const Run& self); +void extract(::microstrain::Buffer& serializer, Run& self); TypedResult run(C::mip_interface& device); @@ -3504,11 +3504,11 @@ struct KinematicConstraint } }; }; -void insert(Serializer& serializer, const KinematicConstraint& self); -void extract(Serializer& serializer, KinematicConstraint& self); +void insert(::microstrain::Buffer& serializer, const KinematicConstraint& self); +void extract(::microstrain::Buffer& serializer, KinematicConstraint& self); -void insert(Serializer& serializer, const KinematicConstraint::Response& self); -void extract(Serializer& serializer, KinematicConstraint::Response& self); +void insert(::microstrain::Buffer& serializer, const KinematicConstraint::Response& self); +void extract(::microstrain::Buffer& serializer, KinematicConstraint::Response& self); TypedResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection); TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut); @@ -3642,11 +3642,11 @@ struct InitializationConfiguration } }; }; -void insert(Serializer& serializer, const InitializationConfiguration& self); -void extract(Serializer& serializer, InitializationConfiguration& self); +void insert(::microstrain::Buffer& serializer, const InitializationConfiguration& self); +void extract(::microstrain::Buffer& serializer, InitializationConfiguration& self); -void insert(Serializer& serializer, const InitializationConfiguration::Response& self); -void extract(Serializer& serializer, InitializationConfiguration::Response& self); +void insert(::microstrain::Buffer& serializer, const InitializationConfiguration::Response& self); +void extract(::microstrain::Buffer& serializer, InitializationConfiguration::Response& self); TypedResult writeInitializationConfiguration(C::mip_interface& device, uint8_t waitForRunCommand, InitializationConfiguration::InitialConditionSource initialCondSrc, InitializationConfiguration::AlignmentSelector autoHeadingAlignmentSelector, float initialHeading, float initialPitch, float initialRoll, const float* initialPosition, const float* initialVelocity, FilterReferenceFrame referenceFrameSelector); TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut); @@ -3720,11 +3720,11 @@ struct AdaptiveFilterOptions } }; }; -void insert(Serializer& serializer, const AdaptiveFilterOptions& self); -void extract(Serializer& serializer, AdaptiveFilterOptions& self); +void insert(::microstrain::Buffer& serializer, const AdaptiveFilterOptions& self); +void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions& self); -void insert(Serializer& serializer, const AdaptiveFilterOptions::Response& self); -void extract(Serializer& serializer, AdaptiveFilterOptions::Response& self); +void insert(::microstrain::Buffer& serializer, const AdaptiveFilterOptions::Response& self); +void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions::Response& self); TypedResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit); TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut); @@ -3802,11 +3802,11 @@ struct MultiAntennaOffset } }; }; -void insert(Serializer& serializer, const MultiAntennaOffset& self); -void extract(Serializer& serializer, MultiAntennaOffset& self); +void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset& self); +void extract(::microstrain::Buffer& serializer, MultiAntennaOffset& self); -void insert(Serializer& serializer, const MultiAntennaOffset::Response& self); -void extract(Serializer& serializer, MultiAntennaOffset::Response& self); +void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset::Response& self); +void extract(::microstrain::Buffer& serializer, MultiAntennaOffset::Response& self); TypedResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset); TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut); @@ -3882,11 +3882,11 @@ struct RelPosConfiguration } }; }; -void insert(Serializer& serializer, const RelPosConfiguration& self); -void extract(Serializer& serializer, RelPosConfiguration& self); +void insert(::microstrain::Buffer& serializer, const RelPosConfiguration& self); +void extract(::microstrain::Buffer& serializer, RelPosConfiguration& self); -void insert(Serializer& serializer, const RelPosConfiguration::Response& self); -void extract(Serializer& serializer, RelPosConfiguration::Response& self); +void insert(::microstrain::Buffer& serializer, const RelPosConfiguration::Response& self); +void extract(::microstrain::Buffer& serializer, RelPosConfiguration::Response& self); TypedResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates); TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut); @@ -3972,11 +3972,11 @@ struct RefPointLeverArm } }; }; -void insert(Serializer& serializer, const RefPointLeverArm& self); -void extract(Serializer& serializer, RefPointLeverArm& self); +void insert(::microstrain::Buffer& serializer, const RefPointLeverArm& self); +void extract(::microstrain::Buffer& serializer, RefPointLeverArm& self); -void insert(Serializer& serializer, const RefPointLeverArm::Response& self); -void extract(Serializer& serializer, RefPointLeverArm::Response& self); +void insert(::microstrain::Buffer& serializer, const RefPointLeverArm::Response& self); +void extract(::microstrain::Buffer& serializer, RefPointLeverArm::Response& self); TypedResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset); TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut); @@ -4021,8 +4021,8 @@ struct SpeedMeasurement } typedef void Response; }; -void insert(Serializer& serializer, const SpeedMeasurement& self); -void extract(Serializer& serializer, SpeedMeasurement& self); +void insert(::microstrain::Buffer& serializer, const SpeedMeasurement& self); +void extract(::microstrain::Buffer& serializer, SpeedMeasurement& self); TypedResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty); @@ -4099,11 +4099,11 @@ struct SpeedLeverArm } }; }; -void insert(Serializer& serializer, const SpeedLeverArm& self); -void extract(Serializer& serializer, SpeedLeverArm& self); +void insert(::microstrain::Buffer& serializer, const SpeedLeverArm& self); +void extract(::microstrain::Buffer& serializer, SpeedLeverArm& self); -void insert(Serializer& serializer, const SpeedLeverArm::Response& self); -void extract(Serializer& serializer, SpeedLeverArm::Response& self); +void insert(::microstrain::Buffer& serializer, const SpeedLeverArm::Response& self); +void extract(::microstrain::Buffer& serializer, SpeedLeverArm::Response& self); TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset); TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut); @@ -4181,11 +4181,11 @@ struct WheeledVehicleConstraintControl } }; }; -void insert(Serializer& serializer, const WheeledVehicleConstraintControl& self); -void extract(Serializer& serializer, WheeledVehicleConstraintControl& self); +void insert(::microstrain::Buffer& serializer, const WheeledVehicleConstraintControl& self); +void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl& self); -void insert(Serializer& serializer, const WheeledVehicleConstraintControl::Response& self); -void extract(Serializer& serializer, WheeledVehicleConstraintControl::Response& self); +void insert(::microstrain::Buffer& serializer, const WheeledVehicleConstraintControl::Response& self); +void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl::Response& self); TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable); TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut); @@ -4261,11 +4261,11 @@ struct VerticalGyroConstraintControl } }; }; -void insert(Serializer& serializer, const VerticalGyroConstraintControl& self); -void extract(Serializer& serializer, VerticalGyroConstraintControl& self); +void insert(::microstrain::Buffer& serializer, const VerticalGyroConstraintControl& self); +void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl& self); -void insert(Serializer& serializer, const VerticalGyroConstraintControl::Response& self); -void extract(Serializer& serializer, VerticalGyroConstraintControl::Response& self); +void insert(::microstrain::Buffer& serializer, const VerticalGyroConstraintControl::Response& self); +void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl::Response& self); TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable); TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut); @@ -4341,11 +4341,11 @@ struct GnssAntennaCalControl } }; }; -void insert(Serializer& serializer, const GnssAntennaCalControl& self); -void extract(Serializer& serializer, GnssAntennaCalControl& self); +void insert(::microstrain::Buffer& serializer, const GnssAntennaCalControl& self); +void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl& self); -void insert(Serializer& serializer, const GnssAntennaCalControl::Response& self); -void extract(Serializer& serializer, GnssAntennaCalControl::Response& self); +void insert(::microstrain::Buffer& serializer, const GnssAntennaCalControl::Response& self); +void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl::Response& self); TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset); TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut); @@ -4388,8 +4388,8 @@ struct SetInitialHeading } typedef void Response; }; -void insert(Serializer& serializer, const SetInitialHeading& self); -void extract(Serializer& serializer, SetInitialHeading& self); +void insert(::microstrain::Buffer& serializer, const SetInitialHeading& self); +void extract(::microstrain::Buffer& serializer, SetInitialHeading& self); TypedResult setInitialHeading(C::mip_interface& device, float heading); diff --git a/src/mip/definitions/commands_gnss.cpp b/src/mip/definitions/commands_gnss.cpp index c0f6b434f..e9aab9854 100644 --- a/src/mip/definitions/commands_gnss.cpp +++ b/src/mip/definitions/commands_gnss.cpp @@ -1,14 +1,14 @@ #include "commands_gnss.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -29,18 +29,18 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const ReceiverInfo& self) +void insert(::microstrain::Buffer& serializer, const ReceiverInfo& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, ReceiverInfo& self) +void extract(::microstrain::Buffer& serializer, ReceiverInfo& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const ReceiverInfo::Response& self) +void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Response& self) { insert(serializer, self.num_receivers); @@ -48,7 +48,7 @@ void insert(Serializer& serializer, const ReceiverInfo::Response& self) insert(serializer, self.receiver_info[i]); } -void extract(Serializer& serializer, ReceiverInfo::Response& self) +void extract(::microstrain::Buffer& serializer, ReceiverInfo::Response& self) { C::extract_count(&serializer, &self.num_receivers, sizeof(self.receiver_info)/sizeof(self.receiver_info[0])); for(unsigned int i=0; i < self.num_receivers; i++) @@ -56,7 +56,7 @@ void extract(Serializer& serializer, ReceiverInfo::Response& self) } -void insert(Serializer& serializer, const ReceiverInfo::Info& self) +void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Info& self) { insert(serializer, self.receiver_id); @@ -66,7 +66,7 @@ void insert(Serializer& serializer, const ReceiverInfo::Info& self) insert(serializer, self.description[i]); } -void extract(Serializer& serializer, ReceiverInfo::Info& self) +void extract(::microstrain::Buffer& serializer, ReceiverInfo::Info& self) { extract(serializer, self.receiver_id); @@ -86,7 +86,7 @@ TypedResult receiverInfo(C::mip_interface& device, uint8_t* numRec if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); C::extract_count(&deserializer, numReceiversOut, numReceiversOutMax); assert(receiverInfoOut || (numReceiversOut == 0)); @@ -98,7 +98,7 @@ TypedResult receiverInfo(C::mip_interface& device, uint8_t* numRec } return result; } -void insert(Serializer& serializer, const SignalConfiguration& self) +void insert(::microstrain::Buffer& serializer, const SignalConfiguration& self) { insert(serializer, self.function); @@ -117,7 +117,7 @@ void insert(Serializer& serializer, const SignalConfiguration& self) } } -void extract(Serializer& serializer, SignalConfiguration& self) +void extract(::microstrain::Buffer& serializer, SignalConfiguration& self) { extract(serializer, self.function); @@ -137,7 +137,7 @@ void extract(Serializer& serializer, SignalConfiguration& self) } } -void insert(Serializer& serializer, const SignalConfiguration::Response& self) +void insert(::microstrain::Buffer& serializer, const SignalConfiguration::Response& self) { insert(serializer, self.gps_enable); @@ -151,7 +151,7 @@ void insert(Serializer& serializer, const SignalConfiguration::Response& self) insert(serializer, self.reserved[i]); } -void extract(Serializer& serializer, SignalConfiguration::Response& self) +void extract(::microstrain::Buffer& serializer, SignalConfiguration::Response& self) { extract(serializer, self.gps_enable); @@ -169,7 +169,7 @@ void extract(Serializer& serializer, SignalConfiguration::Response& self) TypedResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, gpsEnable); @@ -186,22 +186,22 @@ TypedResult writeSignalConfiguration(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SIGNAL_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_SIGNAL_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(gpsEnableOut); extract(deserializer, *gpsEnableOut); @@ -227,34 +227,34 @@ TypedResult readSignalConfiguration(C::mip_interface& devic TypedResult saveSignalConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult loadSignalConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultSignalConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const RtkDongleConfiguration& self) +void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration& self) { insert(serializer, self.function); @@ -267,7 +267,7 @@ void insert(Serializer& serializer, const RtkDongleConfiguration& self) } } -void extract(Serializer& serializer, RtkDongleConfiguration& self) +void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration& self) { extract(serializer, self.function); @@ -281,7 +281,7 @@ void extract(Serializer& serializer, RtkDongleConfiguration& self) } } -void insert(Serializer& serializer, const RtkDongleConfiguration::Response& self) +void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration::Response& self) { insert(serializer, self.enable); @@ -289,7 +289,7 @@ void insert(Serializer& serializer, const RtkDongleConfiguration::Response& self insert(serializer, self.reserved[i]); } -void extract(Serializer& serializer, RtkDongleConfiguration::Response& self) +void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration::Response& self) { extract(serializer, self.enable); @@ -301,7 +301,7 @@ void extract(Serializer& serializer, RtkDongleConfiguration::Response& self) TypedResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -312,22 +312,22 @@ TypedResult writeRtkDongleConfiguration(C::mip_interface assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -344,32 +344,32 @@ TypedResult readRtkDongleConfiguration(C::mip_interface& TypedResult saveRtkDongleConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult loadRtkDongleConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultRtkDongleConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); } } // namespace commands_gnss diff --git a/src/mip/definitions/commands_gnss.hpp b/src/mip/definitions/commands_gnss.hpp index 7f3471d7d..d739b187b 100644 --- a/src/mip/definitions/commands_gnss.hpp +++ b/src/mip/definitions/commands_gnss.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -114,14 +114,14 @@ struct ReceiverInfo } }; }; -void insert(Serializer& serializer, const ReceiverInfo& self); -void extract(Serializer& serializer, ReceiverInfo& self); +void insert(::microstrain::Buffer& serializer, const ReceiverInfo& self); +void extract(::microstrain::Buffer& serializer, ReceiverInfo& self); -void insert(Serializer& serializer, const ReceiverInfo::Info& self); -void extract(Serializer& serializer, ReceiverInfo::Info& self); +void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Info& self); +void extract(::microstrain::Buffer& serializer, ReceiverInfo::Info& self); -void insert(Serializer& serializer, const ReceiverInfo::Response& self); -void extract(Serializer& serializer, ReceiverInfo::Response& self); +void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Response& self); +void extract(::microstrain::Buffer& serializer, ReceiverInfo::Response& self); TypedResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8_t numReceiversOutMax, ReceiverInfo::Info* receiverInfoOut); @@ -198,11 +198,11 @@ struct SignalConfiguration } }; }; -void insert(Serializer& serializer, const SignalConfiguration& self); -void extract(Serializer& serializer, SignalConfiguration& self); +void insert(::microstrain::Buffer& serializer, const SignalConfiguration& self); +void extract(::microstrain::Buffer& serializer, SignalConfiguration& self); -void insert(Serializer& serializer, const SignalConfiguration::Response& self); -void extract(Serializer& serializer, SignalConfiguration::Response& self); +void insert(::microstrain::Buffer& serializer, const SignalConfiguration::Response& self); +void extract(::microstrain::Buffer& serializer, SignalConfiguration::Response& self); TypedResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved); TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut); @@ -277,11 +277,11 @@ struct RtkDongleConfiguration } }; }; -void insert(Serializer& serializer, const RtkDongleConfiguration& self); -void extract(Serializer& serializer, RtkDongleConfiguration& self); +void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration& self); +void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration& self); -void insert(Serializer& serializer, const RtkDongleConfiguration::Response& self); -void extract(Serializer& serializer, RtkDongleConfiguration::Response& self); +void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration::Response& self); +void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration::Response& self); TypedResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved); TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut); diff --git a/src/mip/definitions/commands_rtk.cpp b/src/mip/definitions/commands_rtk.cpp index 3306403e3..1540615fd 100644 --- a/src/mip/definitions/commands_rtk.cpp +++ b/src/mip/definitions/commands_rtk.cpp @@ -1,14 +1,14 @@ #include "commands_rtk.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -29,23 +29,23 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const GetStatusFlags& self) +void insert(::microstrain::Buffer& serializer, const GetStatusFlags& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetStatusFlags& self) +void extract(::microstrain::Buffer& serializer, GetStatusFlags& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetStatusFlags::Response& self) +void insert(::microstrain::Buffer& serializer, const GetStatusFlags::Response& self) { insert(serializer, self.flags); } -void extract(Serializer& serializer, GetStatusFlags::Response& self) +void extract(::microstrain::Buffer& serializer, GetStatusFlags::Response& self) { extract(serializer, self.flags); @@ -60,7 +60,7 @@ TypedResult getStatusFlags(C::mip_interface& device, GetStatusFl if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(flagsOut); extract(deserializer, *flagsOut); @@ -70,24 +70,24 @@ TypedResult getStatusFlags(C::mip_interface& device, GetStatusFl } return result; } -void insert(Serializer& serializer, const GetImei& self) +void insert(::microstrain::Buffer& serializer, const GetImei& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetImei& self) +void extract(::microstrain::Buffer& serializer, GetImei& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetImei::Response& self) +void insert(::microstrain::Buffer& serializer, const GetImei::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.IMEI[i]); } -void extract(Serializer& serializer, GetImei::Response& self) +void extract(::microstrain::Buffer& serializer, GetImei::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.IMEI[i]); @@ -103,7 +103,7 @@ TypedResult getImei(C::mip_interface& device, char* imeiOut) if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(imeiOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -114,24 +114,24 @@ TypedResult getImei(C::mip_interface& device, char* imeiOut) } return result; } -void insert(Serializer& serializer, const GetImsi& self) +void insert(::microstrain::Buffer& serializer, const GetImsi& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetImsi& self) +void extract(::microstrain::Buffer& serializer, GetImsi& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetImsi::Response& self) +void insert(::microstrain::Buffer& serializer, const GetImsi::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.IMSI[i]); } -void extract(Serializer& serializer, GetImsi::Response& self) +void extract(::microstrain::Buffer& serializer, GetImsi::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.IMSI[i]); @@ -147,7 +147,7 @@ TypedResult getImsi(C::mip_interface& device, char* imsiOut) if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(imsiOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -158,24 +158,24 @@ TypedResult getImsi(C::mip_interface& device, char* imsiOut) } return result; } -void insert(Serializer& serializer, const GetIccid& self) +void insert(::microstrain::Buffer& serializer, const GetIccid& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetIccid& self) +void extract(::microstrain::Buffer& serializer, GetIccid& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetIccid::Response& self) +void insert(::microstrain::Buffer& serializer, const GetIccid::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.ICCID[i]); } -void extract(Serializer& serializer, GetIccid::Response& self) +void extract(::microstrain::Buffer& serializer, GetIccid::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.ICCID[i]); @@ -191,7 +191,7 @@ TypedResult getIccid(C::mip_interface& device, char* iccidOut) if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(iccidOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -202,7 +202,7 @@ TypedResult getIccid(C::mip_interface& device, char* iccidOut) } return result; } -void insert(Serializer& serializer, const ConnectedDeviceType& self) +void insert(::microstrain::Buffer& serializer, const ConnectedDeviceType& self) { insert(serializer, self.function); @@ -212,7 +212,7 @@ void insert(Serializer& serializer, const ConnectedDeviceType& self) } } -void extract(Serializer& serializer, ConnectedDeviceType& self) +void extract(::microstrain::Buffer& serializer, ConnectedDeviceType& self) { extract(serializer, self.function); @@ -223,12 +223,12 @@ void extract(Serializer& serializer, ConnectedDeviceType& self) } } -void insert(Serializer& serializer, const ConnectedDeviceType::Response& self) +void insert(::microstrain::Buffer& serializer, const ConnectedDeviceType::Response& self) { insert(serializer, self.devType); } -void extract(Serializer& serializer, ConnectedDeviceType::Response& self) +void extract(::microstrain::Buffer& serializer, ConnectedDeviceType::Response& self) { extract(serializer, self.devType); @@ -237,29 +237,29 @@ void extract(Serializer& serializer, ConnectedDeviceType::Response& self) TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, devtype); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); } TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_CONNECTED_DEVICE_TYPE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length(), REPLY_CONNECTED_DEVICE_TYPE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(devtypeOut); extract(deserializer, *devtypeOut); @@ -272,51 +272,51 @@ TypedResult readConnectedDeviceType(C::mip_interface& devic TypedResult saveConnectedDeviceType(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); } TypedResult loadConnectedDeviceType(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); } TypedResult defaultConnectedDeviceType(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const GetActCode& self) +void insert(::microstrain::Buffer& serializer, const GetActCode& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetActCode& self) +void extract(::microstrain::Buffer& serializer, GetActCode& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetActCode::Response& self) +void insert(::microstrain::Buffer& serializer, const GetActCode::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.ActivationCode[i]); } -void extract(Serializer& serializer, GetActCode::Response& self) +void extract(::microstrain::Buffer& serializer, GetActCode::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.ActivationCode[i]); @@ -332,7 +332,7 @@ TypedResult getActCode(C::mip_interface& device, char* activationcod if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(activationcodeOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -343,24 +343,24 @@ TypedResult getActCode(C::mip_interface& device, char* activationcod } return result; } -void insert(Serializer& serializer, const GetModemFirmwareVersion& self) +void insert(::microstrain::Buffer& serializer, const GetModemFirmwareVersion& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetModemFirmwareVersion& self) +void extract(::microstrain::Buffer& serializer, GetModemFirmwareVersion& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetModemFirmwareVersion::Response& self) +void insert(::microstrain::Buffer& serializer, const GetModemFirmwareVersion::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.ModemFirmwareVersion[i]); } -void extract(Serializer& serializer, GetModemFirmwareVersion::Response& self) +void extract(::microstrain::Buffer& serializer, GetModemFirmwareVersion::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.ModemFirmwareVersion[i]); @@ -376,7 +376,7 @@ TypedResult getModemFirmwareVersion(C::mip_interface& d if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(modemfirmwareversionOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -387,18 +387,18 @@ TypedResult getModemFirmwareVersion(C::mip_interface& d } return result; } -void insert(Serializer& serializer, const GetRssi& self) +void insert(::microstrain::Buffer& serializer, const GetRssi& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, GetRssi& self) +void extract(::microstrain::Buffer& serializer, GetRssi& self) { (void)serializer; (void)self; } -void insert(Serializer& serializer, const GetRssi::Response& self) +void insert(::microstrain::Buffer& serializer, const GetRssi::Response& self) { insert(serializer, self.valid); @@ -407,7 +407,7 @@ void insert(Serializer& serializer, const GetRssi::Response& self) insert(serializer, self.signalQuality); } -void extract(Serializer& serializer, GetRssi::Response& self) +void extract(::microstrain::Buffer& serializer, GetRssi::Response& self) { extract(serializer, self.valid); @@ -426,7 +426,7 @@ TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(validOut); extract(deserializer, *validOut); @@ -442,14 +442,14 @@ TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* } return result; } -void insert(Serializer& serializer, const ServiceStatus& self) +void insert(::microstrain::Buffer& serializer, const ServiceStatus& self) { insert(serializer, self.reserved1); insert(serializer, self.reserved2); } -void extract(Serializer& serializer, ServiceStatus& self) +void extract(::microstrain::Buffer& serializer, ServiceStatus& self) { extract(serializer, self.reserved1); @@ -457,7 +457,7 @@ void extract(Serializer& serializer, ServiceStatus& self) } -void insert(Serializer& serializer, const ServiceStatus::Response& self) +void insert(::microstrain::Buffer& serializer, const ServiceStatus::Response& self) { insert(serializer, self.flags); @@ -468,7 +468,7 @@ void insert(Serializer& serializer, const ServiceStatus::Response& self) insert(serializer, self.lastBytesTime); } -void extract(Serializer& serializer, ServiceStatus::Response& self) +void extract(::microstrain::Buffer& serializer, ServiceStatus::Response& self) { extract(serializer, self.flags); @@ -483,7 +483,7 @@ void extract(Serializer& serializer, ServiceStatus::Response& self) TypedResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* receivedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, reserved1); @@ -492,11 +492,11 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SERVICE_STATUS, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_SERVICE_STATUS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SERVICE_STATUS, buffer, (uint8_t)serializer.length(), REPLY_SERVICE_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(flagsOut); extract(deserializer, *flagsOut); @@ -515,12 +515,12 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese } return result; } -void insert(Serializer& serializer, const ProdEraseStorage& self) +void insert(::microstrain::Buffer& serializer, const ProdEraseStorage& self) { insert(serializer, self.media); } -void extract(Serializer& serializer, ProdEraseStorage& self) +void extract(::microstrain::Buffer& serializer, ProdEraseStorage& self) { extract(serializer, self.media); @@ -529,15 +529,15 @@ void extract(Serializer& serializer, ProdEraseStorage& self) TypedResult prodEraseStorage(C::mip_interface& device, MediaSelector media) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, media); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PROD_ERASE_STORAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PROD_ERASE_STORAGE, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const LedControl& self) +void insert(::microstrain::Buffer& serializer, const LedControl& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.primaryColor[i]); @@ -550,7 +550,7 @@ void insert(Serializer& serializer, const LedControl& self) insert(serializer, self.period); } -void extract(Serializer& serializer, LedControl& self) +void extract(::microstrain::Buffer& serializer, LedControl& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.primaryColor[i]); @@ -567,7 +567,7 @@ void extract(Serializer& serializer, LedControl& self) TypedResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); assert(primarycolor || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -583,14 +583,14 @@ TypedResult ledControl(C::mip_interface& device, const uint8_t* prim assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(Serializer& serializer, const ModemHardReset& self) +void insert(::microstrain::Buffer& serializer, const ModemHardReset& self) { (void)serializer; (void)self; } -void extract(Serializer& serializer, ModemHardReset& self) +void extract(::microstrain::Buffer& serializer, ModemHardReset& self) { (void)serializer; (void)self; diff --git a/src/mip/definitions/commands_rtk.hpp b/src/mip/definitions/commands_rtk.hpp index 5ee697759..c99afba94 100644 --- a/src/mip/definitions/commands_rtk.hpp +++ b/src/mip/definitions/commands_rtk.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -237,11 +237,11 @@ struct GetStatusFlags } }; }; -void insert(Serializer& serializer, const GetStatusFlags& self); -void extract(Serializer& serializer, GetStatusFlags& self); +void insert(::microstrain::Buffer& serializer, const GetStatusFlags& self); +void extract(::microstrain::Buffer& serializer, GetStatusFlags& self); -void insert(Serializer& serializer, const GetStatusFlags::Response& self); -void extract(Serializer& serializer, GetStatusFlags::Response& self); +void insert(::microstrain::Buffer& serializer, const GetStatusFlags::Response& self); +void extract(::microstrain::Buffer& serializer, GetStatusFlags::Response& self); TypedResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut); @@ -293,11 +293,11 @@ struct GetImei } }; }; -void insert(Serializer& serializer, const GetImei& self); -void extract(Serializer& serializer, GetImei& self); +void insert(::microstrain::Buffer& serializer, const GetImei& self); +void extract(::microstrain::Buffer& serializer, GetImei& self); -void insert(Serializer& serializer, const GetImei::Response& self); -void extract(Serializer& serializer, GetImei::Response& self); +void insert(::microstrain::Buffer& serializer, const GetImei::Response& self); +void extract(::microstrain::Buffer& serializer, GetImei::Response& self); TypedResult getImei(C::mip_interface& device, char* imeiOut); @@ -349,11 +349,11 @@ struct GetImsi } }; }; -void insert(Serializer& serializer, const GetImsi& self); -void extract(Serializer& serializer, GetImsi& self); +void insert(::microstrain::Buffer& serializer, const GetImsi& self); +void extract(::microstrain::Buffer& serializer, GetImsi& self); -void insert(Serializer& serializer, const GetImsi::Response& self); -void extract(Serializer& serializer, GetImsi::Response& self); +void insert(::microstrain::Buffer& serializer, const GetImsi::Response& self); +void extract(::microstrain::Buffer& serializer, GetImsi::Response& self); TypedResult getImsi(C::mip_interface& device, char* imsiOut); @@ -405,11 +405,11 @@ struct GetIccid } }; }; -void insert(Serializer& serializer, const GetIccid& self); -void extract(Serializer& serializer, GetIccid& self); +void insert(::microstrain::Buffer& serializer, const GetIccid& self); +void extract(::microstrain::Buffer& serializer, GetIccid& self); -void insert(Serializer& serializer, const GetIccid::Response& self); -void extract(Serializer& serializer, GetIccid::Response& self); +void insert(::microstrain::Buffer& serializer, const GetIccid::Response& self); +void extract(::microstrain::Buffer& serializer, GetIccid::Response& self); TypedResult getIccid(C::mip_interface& device, char* iccidOut); @@ -482,11 +482,11 @@ struct ConnectedDeviceType } }; }; -void insert(Serializer& serializer, const ConnectedDeviceType& self); -void extract(Serializer& serializer, ConnectedDeviceType& self); +void insert(::microstrain::Buffer& serializer, const ConnectedDeviceType& self); +void extract(::microstrain::Buffer& serializer, ConnectedDeviceType& self); -void insert(Serializer& serializer, const ConnectedDeviceType::Response& self); -void extract(Serializer& serializer, ConnectedDeviceType::Response& self); +void insert(::microstrain::Buffer& serializer, const ConnectedDeviceType::Response& self); +void extract(::microstrain::Buffer& serializer, ConnectedDeviceType::Response& self); TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype); TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut); @@ -542,11 +542,11 @@ struct GetActCode } }; }; -void insert(Serializer& serializer, const GetActCode& self); -void extract(Serializer& serializer, GetActCode& self); +void insert(::microstrain::Buffer& serializer, const GetActCode& self); +void extract(::microstrain::Buffer& serializer, GetActCode& self); -void insert(Serializer& serializer, const GetActCode::Response& self); -void extract(Serializer& serializer, GetActCode::Response& self); +void insert(::microstrain::Buffer& serializer, const GetActCode::Response& self); +void extract(::microstrain::Buffer& serializer, GetActCode::Response& self); TypedResult getActCode(C::mip_interface& device, char* activationcodeOut); @@ -598,11 +598,11 @@ struct GetModemFirmwareVersion } }; }; -void insert(Serializer& serializer, const GetModemFirmwareVersion& self); -void extract(Serializer& serializer, GetModemFirmwareVersion& self); +void insert(::microstrain::Buffer& serializer, const GetModemFirmwareVersion& self); +void extract(::microstrain::Buffer& serializer, GetModemFirmwareVersion& self); -void insert(Serializer& serializer, const GetModemFirmwareVersion::Response& self); -void extract(Serializer& serializer, GetModemFirmwareVersion::Response& self); +void insert(::microstrain::Buffer& serializer, const GetModemFirmwareVersion::Response& self); +void extract(::microstrain::Buffer& serializer, GetModemFirmwareVersion::Response& self); TypedResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut); @@ -657,11 +657,11 @@ struct GetRssi } }; }; -void insert(Serializer& serializer, const GetRssi& self); -void extract(Serializer& serializer, GetRssi& self); +void insert(::microstrain::Buffer& serializer, const GetRssi& self); +void extract(::microstrain::Buffer& serializer, GetRssi& self); -void insert(Serializer& serializer, const GetRssi::Response& self); -void extract(Serializer& serializer, GetRssi::Response& self); +void insert(::microstrain::Buffer& serializer, const GetRssi::Response& self); +void extract(::microstrain::Buffer& serializer, GetRssi::Response& self); TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut); @@ -750,11 +750,11 @@ struct ServiceStatus } }; }; -void insert(Serializer& serializer, const ServiceStatus& self); -void extract(Serializer& serializer, ServiceStatus& self); +void insert(::microstrain::Buffer& serializer, const ServiceStatus& self); +void extract(::microstrain::Buffer& serializer, ServiceStatus& self); -void insert(Serializer& serializer, const ServiceStatus::Response& self); -void extract(Serializer& serializer, ServiceStatus::Response& self); +void insert(::microstrain::Buffer& serializer, const ServiceStatus::Response& self); +void extract(::microstrain::Buffer& serializer, ServiceStatus::Response& self); TypedResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* receivedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut); @@ -791,8 +791,8 @@ struct ProdEraseStorage } typedef void Response; }; -void insert(Serializer& serializer, const ProdEraseStorage& self); -void extract(Serializer& serializer, ProdEraseStorage& self); +void insert(::microstrain::Buffer& serializer, const ProdEraseStorage& self); +void extract(::microstrain::Buffer& serializer, ProdEraseStorage& self); TypedResult prodEraseStorage(C::mip_interface& device, MediaSelector media); @@ -831,8 +831,8 @@ struct LedControl } typedef void Response; }; -void insert(Serializer& serializer, const LedControl& self); -void extract(Serializer& serializer, LedControl& self); +void insert(::microstrain::Buffer& serializer, const LedControl& self); +void extract(::microstrain::Buffer& serializer, LedControl& self); TypedResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period); @@ -868,8 +868,8 @@ struct ModemHardReset } typedef void Response; }; -void insert(Serializer& serializer, const ModemHardReset& self); -void extract(Serializer& serializer, ModemHardReset& self); +void insert(::microstrain::Buffer& serializer, const ModemHardReset& self); +void extract(::microstrain::Buffer& serializer, ModemHardReset& self); TypedResult modemHardReset(C::mip_interface& device); diff --git a/src/mip/definitions/commands_system.cpp b/src/mip/definitions/commands_system.cpp index 8e5935416..ab25b0c2d 100644 --- a/src/mip/definitions/commands_system.cpp +++ b/src/mip/definitions/commands_system.cpp @@ -1,14 +1,14 @@ #include "commands_system.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -29,7 +29,7 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const CommMode& self) +void insert(::microstrain::Buffer& serializer, const CommMode& self) { insert(serializer, self.function); @@ -39,7 +39,7 @@ void insert(Serializer& serializer, const CommMode& self) } } -void extract(Serializer& serializer, CommMode& self) +void extract(::microstrain::Buffer& serializer, CommMode& self) { extract(serializer, self.function); @@ -50,12 +50,12 @@ void extract(Serializer& serializer, CommMode& self) } } -void insert(Serializer& serializer, const CommMode::Response& self) +void insert(::microstrain::Buffer& serializer, const CommMode::Response& self) { insert(serializer, self.mode); } -void extract(Serializer& serializer, CommMode::Response& self) +void extract(::microstrain::Buffer& serializer, CommMode::Response& self) { extract(serializer, self.mode); @@ -64,29 +64,29 @@ void extract(Serializer& serializer, CommMode::Response& self) TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.length()); } TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer), REPLY_COM_MODE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.length(), REPLY_COM_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { - Serializer deserializer(buffer, responseLength); + Buffer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -99,12 +99,12 @@ TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) TypedResult defaultCommMode(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); + Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.length()); } } // namespace commands_system diff --git a/src/mip/definitions/commands_system.hpp b/src/mip/definitions/commands_system.hpp index 90b1e88fa..306df2492 100644 --- a/src/mip/definitions/commands_system.hpp +++ b/src/mip/definitions/commands_system.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -125,11 +125,11 @@ struct CommMode } }; }; -void insert(Serializer& serializer, const CommMode& self); -void extract(Serializer& serializer, CommMode& self); +void insert(::microstrain::Buffer& serializer, const CommMode& self); +void extract(::microstrain::Buffer& serializer, CommMode& self); -void insert(Serializer& serializer, const CommMode::Response& self); -void extract(Serializer& serializer, CommMode::Response& self); +void insert(::microstrain::Buffer& serializer, const CommMode::Response& self); +void extract(::microstrain::Buffer& serializer, CommMode::Response& self); TypedResult writeCommMode(C::mip_interface& device, uint8_t mode); TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut); diff --git a/src/mip/definitions/common.h b/src/mip/definitions/common.h index 559ce2d9b..28eed1822 100644 --- a/src/mip/definitions/common.h +++ b/src/mip/definitions/common.h @@ -8,12 +8,15 @@ #ifdef __cplusplus +#include "microstrain/common/buffer.hpp" + #include #include #include namespace mip { namespace C { +using namespace ::microstrain::C; extern "C" { #endif // __cplusplus @@ -75,8 +78,8 @@ DECLARE_MIP_VECTOR_TYPE(4, float, mip_quatf) using DescriptorRate = C::mip_descriptor_rate; -inline void insert(microstrain::Serializer& serializer, const DescriptorRate& self) { return C::insert_mip_descriptor_rate(&serializer, &self); } -inline void extract(microstrain::Serializer& serializer, DescriptorRate& self) { return C::extract_mip_descriptor_rate(&serializer, &self); } +inline size_t insert(::microstrain::Buffer& buffer, const DescriptorRate& self) { return buffer.insert(self.descriptor, self.decimation); } +inline size_t extract(::microstrain::Buffer& buffer, DescriptorRate& self) { return buffer.extract(self.descriptor, self.decimation); } ////////////////////////////////////////////////////////////////////////////////// @@ -174,10 +177,10 @@ using Matrix3d = Vector; using Quatf = Vector4f; template -void insert(microstrain::Serializer& serializer, const Vector& v) { for(size_t i=0; i& v) { for(size_t i=0; i -void extract(microstrain::Serializer& serializer, Vector& v) { for(size_t i=0; i& v) { for(size_t i=0; i& v) { for(size_t i //typedef Vector Matrix3f; // //template -//void insert(Serializer& serializer, const Vector& self) +//void insert(Buffer& serializer, const Vector& self) //{ // for(size_t i=0; i -//void extract(Serializer& serializer, Vector& self) +//void extract(Buffer& serializer, Vector& self) //{ // for(size_t i=0; i -//void insert(Serializer& serializer, const Quaternion& self) +//void insert(Buffer& serializer, const Quaternion& self) //{ // insert(serializer, self.w()); // w comes first in mip // insert(serializer, self.x()); @@ -317,7 +320,7 @@ void extract(microstrain::Serializer& serializer, Vector& v) { for(size_t i //} // //template -//void extract(Serializer& serializer, Quaternion& self) +//void extract(Buffer& serializer, Quaternion& self) //{ // extract(serializer, self.w()); // w comes first in mip // extract(serializer, self.x()); diff --git a/src/mip/definitions/data_filter.cpp b/src/mip/definitions/data_filter.cpp index 9ed9f9cb5..03493419c 100644 --- a/src/mip/definitions/data_filter.cpp +++ b/src/mip/definitions/data_filter.cpp @@ -1,14 +1,14 @@ #include "data_filter.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -29,7 +29,7 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const PositionLlh& self) +void insert(::microstrain::Buffer& serializer, const PositionLlh& self) { insert(serializer, self.latitude); @@ -40,7 +40,7 @@ void insert(Serializer& serializer, const PositionLlh& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, PositionLlh& self) +void extract(::microstrain::Buffer& serializer, PositionLlh& self) { extract(serializer, self.latitude); @@ -52,7 +52,7 @@ void extract(Serializer& serializer, PositionLlh& self) } -void insert(Serializer& serializer, const VelocityNed& self) +void insert(::microstrain::Buffer& serializer, const VelocityNed& self) { insert(serializer, self.north); @@ -63,7 +63,7 @@ void insert(Serializer& serializer, const VelocityNed& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, VelocityNed& self) +void extract(::microstrain::Buffer& serializer, VelocityNed& self) { extract(serializer, self.north); @@ -75,7 +75,7 @@ void extract(Serializer& serializer, VelocityNed& self) } -void insert(Serializer& serializer, const AttitudeQuaternion& self) +void insert(::microstrain::Buffer& serializer, const AttitudeQuaternion& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.q[i]); @@ -83,7 +83,7 @@ void insert(Serializer& serializer, const AttitudeQuaternion& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, AttitudeQuaternion& self) +void extract(::microstrain::Buffer& serializer, AttitudeQuaternion& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.q[i]); @@ -92,7 +92,7 @@ void extract(Serializer& serializer, AttitudeQuaternion& self) } -void insert(Serializer& serializer, const AttitudeDcm& self) +void insert(::microstrain::Buffer& serializer, const AttitudeDcm& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.dcm[i]); @@ -100,7 +100,7 @@ void insert(Serializer& serializer, const AttitudeDcm& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, AttitudeDcm& self) +void extract(::microstrain::Buffer& serializer, AttitudeDcm& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.dcm[i]); @@ -109,7 +109,7 @@ void extract(Serializer& serializer, AttitudeDcm& self) } -void insert(Serializer& serializer, const EulerAngles& self) +void insert(::microstrain::Buffer& serializer, const EulerAngles& self) { insert(serializer, self.roll); @@ -120,7 +120,7 @@ void insert(Serializer& serializer, const EulerAngles& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, EulerAngles& self) +void extract(::microstrain::Buffer& serializer, EulerAngles& self) { extract(serializer, self.roll); @@ -132,7 +132,7 @@ void extract(Serializer& serializer, EulerAngles& self) } -void insert(Serializer& serializer, const GyroBias& self) +void insert(::microstrain::Buffer& serializer, const GyroBias& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); @@ -140,7 +140,7 @@ void insert(Serializer& serializer, const GyroBias& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GyroBias& self) +void extract(::microstrain::Buffer& serializer, GyroBias& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -149,7 +149,7 @@ void extract(Serializer& serializer, GyroBias& self) } -void insert(Serializer& serializer, const AccelBias& self) +void insert(::microstrain::Buffer& serializer, const AccelBias& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); @@ -157,7 +157,7 @@ void insert(Serializer& serializer, const AccelBias& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, AccelBias& self) +void extract(::microstrain::Buffer& serializer, AccelBias& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -166,7 +166,7 @@ void extract(Serializer& serializer, AccelBias& self) } -void insert(Serializer& serializer, const PositionLlhUncertainty& self) +void insert(::microstrain::Buffer& serializer, const PositionLlhUncertainty& self) { insert(serializer, self.north); @@ -177,7 +177,7 @@ void insert(Serializer& serializer, const PositionLlhUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, PositionLlhUncertainty& self) +void extract(::microstrain::Buffer& serializer, PositionLlhUncertainty& self) { extract(serializer, self.north); @@ -189,7 +189,7 @@ void extract(Serializer& serializer, PositionLlhUncertainty& self) } -void insert(Serializer& serializer, const VelocityNedUncertainty& self) +void insert(::microstrain::Buffer& serializer, const VelocityNedUncertainty& self) { insert(serializer, self.north); @@ -200,7 +200,7 @@ void insert(Serializer& serializer, const VelocityNedUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, VelocityNedUncertainty& self) +void extract(::microstrain::Buffer& serializer, VelocityNedUncertainty& self) { extract(serializer, self.north); @@ -212,7 +212,7 @@ void extract(Serializer& serializer, VelocityNedUncertainty& self) } -void insert(Serializer& serializer, const EulerAnglesUncertainty& self) +void insert(::microstrain::Buffer& serializer, const EulerAnglesUncertainty& self) { insert(serializer, self.roll); @@ -223,7 +223,7 @@ void insert(Serializer& serializer, const EulerAnglesUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, EulerAnglesUncertainty& self) +void extract(::microstrain::Buffer& serializer, EulerAnglesUncertainty& self) { extract(serializer, self.roll); @@ -235,7 +235,7 @@ void extract(Serializer& serializer, EulerAnglesUncertainty& self) } -void insert(Serializer& serializer, const GyroBiasUncertainty& self) +void insert(::microstrain::Buffer& serializer, const GyroBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias_uncert[i]); @@ -243,7 +243,7 @@ void insert(Serializer& serializer, const GyroBiasUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GyroBiasUncertainty& self) +void extract(::microstrain::Buffer& serializer, GyroBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias_uncert[i]); @@ -252,7 +252,7 @@ void extract(Serializer& serializer, GyroBiasUncertainty& self) } -void insert(Serializer& serializer, const AccelBiasUncertainty& self) +void insert(::microstrain::Buffer& serializer, const AccelBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias_uncert[i]); @@ -260,7 +260,7 @@ void insert(Serializer& serializer, const AccelBiasUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, AccelBiasUncertainty& self) +void extract(::microstrain::Buffer& serializer, AccelBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias_uncert[i]); @@ -269,7 +269,7 @@ void extract(Serializer& serializer, AccelBiasUncertainty& self) } -void insert(Serializer& serializer, const Timestamp& self) +void insert(::microstrain::Buffer& serializer, const Timestamp& self) { insert(serializer, self.tow); @@ -278,7 +278,7 @@ void insert(Serializer& serializer, const Timestamp& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, Timestamp& self) +void extract(::microstrain::Buffer& serializer, Timestamp& self) { extract(serializer, self.tow); @@ -288,7 +288,7 @@ void extract(Serializer& serializer, Timestamp& self) } -void insert(Serializer& serializer, const Status& self) +void insert(::microstrain::Buffer& serializer, const Status& self) { insert(serializer, self.filter_state); @@ -297,7 +297,7 @@ void insert(Serializer& serializer, const Status& self) insert(serializer, self.status_flags); } -void extract(Serializer& serializer, Status& self) +void extract(::microstrain::Buffer& serializer, Status& self) { extract(serializer, self.filter_state); @@ -307,7 +307,7 @@ void extract(Serializer& serializer, Status& self) } -void insert(Serializer& serializer, const LinearAccel& self) +void insert(::microstrain::Buffer& serializer, const LinearAccel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.accel[i]); @@ -315,7 +315,7 @@ void insert(Serializer& serializer, const LinearAccel& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, LinearAccel& self) +void extract(::microstrain::Buffer& serializer, LinearAccel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.accel[i]); @@ -324,7 +324,7 @@ void extract(Serializer& serializer, LinearAccel& self) } -void insert(Serializer& serializer, const GravityVector& self) +void insert(::microstrain::Buffer& serializer, const GravityVector& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.gravity[i]); @@ -332,7 +332,7 @@ void insert(Serializer& serializer, const GravityVector& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GravityVector& self) +void extract(::microstrain::Buffer& serializer, GravityVector& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.gravity[i]); @@ -341,7 +341,7 @@ void extract(Serializer& serializer, GravityVector& self) } -void insert(Serializer& serializer, const CompAccel& self) +void insert(::microstrain::Buffer& serializer, const CompAccel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.accel[i]); @@ -349,7 +349,7 @@ void insert(Serializer& serializer, const CompAccel& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, CompAccel& self) +void extract(::microstrain::Buffer& serializer, CompAccel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.accel[i]); @@ -358,7 +358,7 @@ void extract(Serializer& serializer, CompAccel& self) } -void insert(Serializer& serializer, const CompAngularRate& self) +void insert(::microstrain::Buffer& serializer, const CompAngularRate& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.gyro[i]); @@ -366,7 +366,7 @@ void insert(Serializer& serializer, const CompAngularRate& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, CompAngularRate& self) +void extract(::microstrain::Buffer& serializer, CompAngularRate& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.gyro[i]); @@ -375,7 +375,7 @@ void extract(Serializer& serializer, CompAngularRate& self) } -void insert(Serializer& serializer, const QuaternionAttitudeUncertainty& self) +void insert(::microstrain::Buffer& serializer, const QuaternionAttitudeUncertainty& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.q[i]); @@ -383,7 +383,7 @@ void insert(Serializer& serializer, const QuaternionAttitudeUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, QuaternionAttitudeUncertainty& self) +void extract(::microstrain::Buffer& serializer, QuaternionAttitudeUncertainty& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.q[i]); @@ -392,14 +392,14 @@ void extract(Serializer& serializer, QuaternionAttitudeUncertainty& self) } -void insert(Serializer& serializer, const Wgs84GravityMag& self) +void insert(::microstrain::Buffer& serializer, const Wgs84GravityMag& self) { insert(serializer, self.magnitude); insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, Wgs84GravityMag& self) +void extract(::microstrain::Buffer& serializer, Wgs84GravityMag& self) { extract(serializer, self.magnitude); @@ -407,7 +407,7 @@ void extract(Serializer& serializer, Wgs84GravityMag& self) } -void insert(Serializer& serializer, const HeadingUpdateState& self) +void insert(::microstrain::Buffer& serializer, const HeadingUpdateState& self) { insert(serializer, self.heading); @@ -418,7 +418,7 @@ void insert(Serializer& serializer, const HeadingUpdateState& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, HeadingUpdateState& self) +void extract(::microstrain::Buffer& serializer, HeadingUpdateState& self) { extract(serializer, self.heading); @@ -430,7 +430,7 @@ void extract(Serializer& serializer, HeadingUpdateState& self) } -void insert(Serializer& serializer, const MagneticModel& self) +void insert(::microstrain::Buffer& serializer, const MagneticModel& self) { insert(serializer, self.intensity_north); @@ -445,7 +445,7 @@ void insert(Serializer& serializer, const MagneticModel& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagneticModel& self) +void extract(::microstrain::Buffer& serializer, MagneticModel& self) { extract(serializer, self.intensity_north); @@ -461,7 +461,7 @@ void extract(Serializer& serializer, MagneticModel& self) } -void insert(Serializer& serializer, const AccelScaleFactor& self) +void insert(::microstrain::Buffer& serializer, const AccelScaleFactor& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scale_factor[i]); @@ -469,7 +469,7 @@ void insert(Serializer& serializer, const AccelScaleFactor& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, AccelScaleFactor& self) +void extract(::microstrain::Buffer& serializer, AccelScaleFactor& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scale_factor[i]); @@ -478,7 +478,7 @@ void extract(Serializer& serializer, AccelScaleFactor& self) } -void insert(Serializer& serializer, const AccelScaleFactorUncertainty& self) +void insert(::microstrain::Buffer& serializer, const AccelScaleFactorUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scale_factor_uncert[i]); @@ -486,7 +486,7 @@ void insert(Serializer& serializer, const AccelScaleFactorUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, AccelScaleFactorUncertainty& self) +void extract(::microstrain::Buffer& serializer, AccelScaleFactorUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scale_factor_uncert[i]); @@ -495,7 +495,7 @@ void extract(Serializer& serializer, AccelScaleFactorUncertainty& self) } -void insert(Serializer& serializer, const GyroScaleFactor& self) +void insert(::microstrain::Buffer& serializer, const GyroScaleFactor& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scale_factor[i]); @@ -503,7 +503,7 @@ void insert(Serializer& serializer, const GyroScaleFactor& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GyroScaleFactor& self) +void extract(::microstrain::Buffer& serializer, GyroScaleFactor& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scale_factor[i]); @@ -512,7 +512,7 @@ void extract(Serializer& serializer, GyroScaleFactor& self) } -void insert(Serializer& serializer, const GyroScaleFactorUncertainty& self) +void insert(::microstrain::Buffer& serializer, const GyroScaleFactorUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scale_factor_uncert[i]); @@ -520,7 +520,7 @@ void insert(Serializer& serializer, const GyroScaleFactorUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GyroScaleFactorUncertainty& self) +void extract(::microstrain::Buffer& serializer, GyroScaleFactorUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scale_factor_uncert[i]); @@ -529,7 +529,7 @@ void extract(Serializer& serializer, GyroScaleFactorUncertainty& self) } -void insert(Serializer& serializer, const MagBias& self) +void insert(::microstrain::Buffer& serializer, const MagBias& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); @@ -537,7 +537,7 @@ void insert(Serializer& serializer, const MagBias& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagBias& self) +void extract(::microstrain::Buffer& serializer, MagBias& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -546,7 +546,7 @@ void extract(Serializer& serializer, MagBias& self) } -void insert(Serializer& serializer, const MagBiasUncertainty& self) +void insert(::microstrain::Buffer& serializer, const MagBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias_uncert[i]); @@ -554,7 +554,7 @@ void insert(Serializer& serializer, const MagBiasUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagBiasUncertainty& self) +void extract(::microstrain::Buffer& serializer, MagBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias_uncert[i]); @@ -563,7 +563,7 @@ void extract(Serializer& serializer, MagBiasUncertainty& self) } -void insert(Serializer& serializer, const StandardAtmosphere& self) +void insert(::microstrain::Buffer& serializer, const StandardAtmosphere& self) { insert(serializer, self.geometric_altitude); @@ -578,7 +578,7 @@ void insert(Serializer& serializer, const StandardAtmosphere& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, StandardAtmosphere& self) +void extract(::microstrain::Buffer& serializer, StandardAtmosphere& self) { extract(serializer, self.geometric_altitude); @@ -594,14 +594,14 @@ void extract(Serializer& serializer, StandardAtmosphere& self) } -void insert(Serializer& serializer, const PressureAltitude& self) +void insert(::microstrain::Buffer& serializer, const PressureAltitude& self) { insert(serializer, self.pressure_altitude); insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, PressureAltitude& self) +void extract(::microstrain::Buffer& serializer, PressureAltitude& self) { extract(serializer, self.pressure_altitude); @@ -609,14 +609,14 @@ void extract(Serializer& serializer, PressureAltitude& self) } -void insert(Serializer& serializer, const DensityAltitude& self) +void insert(::microstrain::Buffer& serializer, const DensityAltitude& self) { insert(serializer, self.density_altitude); insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, DensityAltitude& self) +void extract(::microstrain::Buffer& serializer, DensityAltitude& self) { extract(serializer, self.density_altitude); @@ -624,7 +624,7 @@ void extract(Serializer& serializer, DensityAltitude& self) } -void insert(Serializer& serializer, const AntennaOffsetCorrection& self) +void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrection& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset[i]); @@ -632,7 +632,7 @@ void insert(Serializer& serializer, const AntennaOffsetCorrection& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, AntennaOffsetCorrection& self) +void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrection& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset[i]); @@ -641,7 +641,7 @@ void extract(Serializer& serializer, AntennaOffsetCorrection& self) } -void insert(Serializer& serializer, const AntennaOffsetCorrectionUncertainty& self) +void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrectionUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset_uncert[i]); @@ -649,7 +649,7 @@ void insert(Serializer& serializer, const AntennaOffsetCorrectionUncertainty& se insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, AntennaOffsetCorrectionUncertainty& self) +void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrectionUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset_uncert[i]); @@ -658,7 +658,7 @@ void extract(Serializer& serializer, AntennaOffsetCorrectionUncertainty& self) } -void insert(Serializer& serializer, const MultiAntennaOffsetCorrection& self) +void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrection& self) { insert(serializer, self.receiver_id); @@ -668,7 +668,7 @@ void insert(Serializer& serializer, const MultiAntennaOffsetCorrection& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MultiAntennaOffsetCorrection& self) +void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrection& self) { extract(serializer, self.receiver_id); @@ -679,7 +679,7 @@ void extract(Serializer& serializer, MultiAntennaOffsetCorrection& self) } -void insert(Serializer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self) +void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self) { insert(serializer, self.receiver_id); @@ -689,7 +689,7 @@ void insert(Serializer& serializer, const MultiAntennaOffsetCorrectionUncertaint insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MultiAntennaOffsetCorrectionUncertainty& self) +void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrectionUncertainty& self) { extract(serializer, self.receiver_id); @@ -700,7 +700,7 @@ void extract(Serializer& serializer, MultiAntennaOffsetCorrectionUncertainty& se } -void insert(Serializer& serializer, const MagnetometerOffset& self) +void insert(::microstrain::Buffer& serializer, const MagnetometerOffset& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.hard_iron[i]); @@ -708,7 +708,7 @@ void insert(Serializer& serializer, const MagnetometerOffset& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagnetometerOffset& self) +void extract(::microstrain::Buffer& serializer, MagnetometerOffset& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.hard_iron[i]); @@ -717,7 +717,7 @@ void extract(Serializer& serializer, MagnetometerOffset& self) } -void insert(Serializer& serializer, const MagnetometerMatrix& self) +void insert(::microstrain::Buffer& serializer, const MagnetometerMatrix& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.soft_iron[i]); @@ -725,7 +725,7 @@ void insert(Serializer& serializer, const MagnetometerMatrix& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagnetometerMatrix& self) +void extract(::microstrain::Buffer& serializer, MagnetometerMatrix& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.soft_iron[i]); @@ -734,7 +734,7 @@ void extract(Serializer& serializer, MagnetometerMatrix& self) } -void insert(Serializer& serializer, const MagnetometerOffsetUncertainty& self) +void insert(::microstrain::Buffer& serializer, const MagnetometerOffsetUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.hard_iron_uncertainty[i]); @@ -742,7 +742,7 @@ void insert(Serializer& serializer, const MagnetometerOffsetUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagnetometerOffsetUncertainty& self) +void extract(::microstrain::Buffer& serializer, MagnetometerOffsetUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.hard_iron_uncertainty[i]); @@ -751,7 +751,7 @@ void extract(Serializer& serializer, MagnetometerOffsetUncertainty& self) } -void insert(Serializer& serializer, const MagnetometerMatrixUncertainty& self) +void insert(::microstrain::Buffer& serializer, const MagnetometerMatrixUncertainty& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.soft_iron_uncertainty[i]); @@ -759,7 +759,7 @@ void insert(Serializer& serializer, const MagnetometerMatrixUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagnetometerMatrixUncertainty& self) +void extract(::microstrain::Buffer& serializer, MagnetometerMatrixUncertainty& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.soft_iron_uncertainty[i]); @@ -768,7 +768,7 @@ void extract(Serializer& serializer, MagnetometerMatrixUncertainty& self) } -void insert(Serializer& serializer, const MagnetometerCovarianceMatrix& self) +void insert(::microstrain::Buffer& serializer, const MagnetometerCovarianceMatrix& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.covariance[i]); @@ -776,7 +776,7 @@ void insert(Serializer& serializer, const MagnetometerCovarianceMatrix& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagnetometerCovarianceMatrix& self) +void extract(::microstrain::Buffer& serializer, MagnetometerCovarianceMatrix& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.covariance[i]); @@ -785,7 +785,7 @@ void extract(Serializer& serializer, MagnetometerCovarianceMatrix& self) } -void insert(Serializer& serializer, const MagnetometerResidualVector& self) +void insert(::microstrain::Buffer& serializer, const MagnetometerResidualVector& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.residual[i]); @@ -793,7 +793,7 @@ void insert(Serializer& serializer, const MagnetometerResidualVector& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, MagnetometerResidualVector& self) +void extract(::microstrain::Buffer& serializer, MagnetometerResidualVector& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.residual[i]); @@ -802,7 +802,7 @@ void extract(Serializer& serializer, MagnetometerResidualVector& self) } -void insert(Serializer& serializer, const ClockCorrection& self) +void insert(::microstrain::Buffer& serializer, const ClockCorrection& self) { insert(serializer, self.receiver_id); @@ -813,7 +813,7 @@ void insert(Serializer& serializer, const ClockCorrection& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, ClockCorrection& self) +void extract(::microstrain::Buffer& serializer, ClockCorrection& self) { extract(serializer, self.receiver_id); @@ -825,7 +825,7 @@ void extract(Serializer& serializer, ClockCorrection& self) } -void insert(Serializer& serializer, const ClockCorrectionUncertainty& self) +void insert(::microstrain::Buffer& serializer, const ClockCorrectionUncertainty& self) { insert(serializer, self.receiver_id); @@ -836,7 +836,7 @@ void insert(Serializer& serializer, const ClockCorrectionUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, ClockCorrectionUncertainty& self) +void extract(::microstrain::Buffer& serializer, ClockCorrectionUncertainty& self) { extract(serializer, self.receiver_id); @@ -848,7 +848,7 @@ void extract(Serializer& serializer, ClockCorrectionUncertainty& self) } -void insert(Serializer& serializer, const GnssPosAidStatus& self) +void insert(::microstrain::Buffer& serializer, const GnssPosAidStatus& self) { insert(serializer, self.receiver_id); @@ -860,7 +860,7 @@ void insert(Serializer& serializer, const GnssPosAidStatus& self) insert(serializer, self.reserved[i]); } -void extract(Serializer& serializer, GnssPosAidStatus& self) +void extract(::microstrain::Buffer& serializer, GnssPosAidStatus& self) { extract(serializer, self.receiver_id); @@ -873,7 +873,7 @@ void extract(Serializer& serializer, GnssPosAidStatus& self) } -void insert(Serializer& serializer, const GnssAttAidStatus& self) +void insert(::microstrain::Buffer& serializer, const GnssAttAidStatus& self) { insert(serializer, self.time_of_week); @@ -883,7 +883,7 @@ void insert(Serializer& serializer, const GnssAttAidStatus& self) insert(serializer, self.reserved[i]); } -void extract(Serializer& serializer, GnssAttAidStatus& self) +void extract(::microstrain::Buffer& serializer, GnssAttAidStatus& self) { extract(serializer, self.time_of_week); @@ -894,7 +894,7 @@ void extract(Serializer& serializer, GnssAttAidStatus& self) } -void insert(Serializer& serializer, const HeadAidStatus& self) +void insert(::microstrain::Buffer& serializer, const HeadAidStatus& self) { insert(serializer, self.time_of_week); @@ -904,7 +904,7 @@ void insert(Serializer& serializer, const HeadAidStatus& self) insert(serializer, self.reserved[i]); } -void extract(Serializer& serializer, HeadAidStatus& self) +void extract(::microstrain::Buffer& serializer, HeadAidStatus& self) { extract(serializer, self.time_of_week); @@ -915,7 +915,7 @@ void extract(Serializer& serializer, HeadAidStatus& self) } -void insert(Serializer& serializer, const RelPosNed& self) +void insert(::microstrain::Buffer& serializer, const RelPosNed& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.relative_position[i]); @@ -923,7 +923,7 @@ void insert(Serializer& serializer, const RelPosNed& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, RelPosNed& self) +void extract(::microstrain::Buffer& serializer, RelPosNed& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.relative_position[i]); @@ -932,7 +932,7 @@ void extract(Serializer& serializer, RelPosNed& self) } -void insert(Serializer& serializer, const EcefPos& self) +void insert(::microstrain::Buffer& serializer, const EcefPos& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.position_ecef[i]); @@ -940,7 +940,7 @@ void insert(Serializer& serializer, const EcefPos& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, EcefPos& self) +void extract(::microstrain::Buffer& serializer, EcefPos& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.position_ecef[i]); @@ -949,7 +949,7 @@ void extract(Serializer& serializer, EcefPos& self) } -void insert(Serializer& serializer, const EcefVel& self) +void insert(::microstrain::Buffer& serializer, const EcefVel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.velocity_ecef[i]); @@ -957,7 +957,7 @@ void insert(Serializer& serializer, const EcefVel& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, EcefVel& self) +void extract(::microstrain::Buffer& serializer, EcefVel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.velocity_ecef[i]); @@ -966,7 +966,7 @@ void extract(Serializer& serializer, EcefVel& self) } -void insert(Serializer& serializer, const EcefPosUncertainty& self) +void insert(::microstrain::Buffer& serializer, const EcefPosUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.pos_uncertainty[i]); @@ -974,7 +974,7 @@ void insert(Serializer& serializer, const EcefPosUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, EcefPosUncertainty& self) +void extract(::microstrain::Buffer& serializer, EcefPosUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.pos_uncertainty[i]); @@ -983,7 +983,7 @@ void extract(Serializer& serializer, EcefPosUncertainty& self) } -void insert(Serializer& serializer, const EcefVelUncertainty& self) +void insert(::microstrain::Buffer& serializer, const EcefVelUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.vel_uncertainty[i]); @@ -991,7 +991,7 @@ void insert(Serializer& serializer, const EcefVelUncertainty& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, EcefVelUncertainty& self) +void extract(::microstrain::Buffer& serializer, EcefVelUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.vel_uncertainty[i]); @@ -1000,7 +1000,7 @@ void extract(Serializer& serializer, EcefVelUncertainty& self) } -void insert(Serializer& serializer, const AidingMeasurementSummary& self) +void insert(::microstrain::Buffer& serializer, const AidingMeasurementSummary& self) { insert(serializer, self.time_of_week); @@ -1011,7 +1011,7 @@ void insert(Serializer& serializer, const AidingMeasurementSummary& self) insert(serializer, self.indicator); } -void extract(Serializer& serializer, AidingMeasurementSummary& self) +void extract(::microstrain::Buffer& serializer, AidingMeasurementSummary& self) { extract(serializer, self.time_of_week); @@ -1023,14 +1023,14 @@ void extract(Serializer& serializer, AidingMeasurementSummary& self) } -void insert(Serializer& serializer, const OdometerScaleFactorError& self) +void insert(::microstrain::Buffer& serializer, const OdometerScaleFactorError& self) { insert(serializer, self.scale_factor_error); insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, OdometerScaleFactorError& self) +void extract(::microstrain::Buffer& serializer, OdometerScaleFactorError& self) { extract(serializer, self.scale_factor_error); @@ -1038,14 +1038,14 @@ void extract(Serializer& serializer, OdometerScaleFactorError& self) } -void insert(Serializer& serializer, const OdometerScaleFactorErrorUncertainty& self) +void insert(::microstrain::Buffer& serializer, const OdometerScaleFactorErrorUncertainty& self) { insert(serializer, self.scale_factor_error_uncertainty); insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, OdometerScaleFactorErrorUncertainty& self) +void extract(::microstrain::Buffer& serializer, OdometerScaleFactorErrorUncertainty& self) { extract(serializer, self.scale_factor_error_uncertainty); @@ -1053,7 +1053,7 @@ void extract(Serializer& serializer, OdometerScaleFactorErrorUncertainty& self) } -void insert(Serializer& serializer, const GnssDualAntennaStatus& self) +void insert(::microstrain::Buffer& serializer, const GnssDualAntennaStatus& self) { insert(serializer, self.time_of_week); @@ -1068,7 +1068,7 @@ void insert(Serializer& serializer, const GnssDualAntennaStatus& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GnssDualAntennaStatus& self) +void extract(::microstrain::Buffer& serializer, GnssDualAntennaStatus& self) { extract(serializer, self.time_of_week); @@ -1084,7 +1084,7 @@ void extract(Serializer& serializer, GnssDualAntennaStatus& self) } -void insert(Serializer& serializer, const AidingFrameConfigError& self) +void insert(::microstrain::Buffer& serializer, const AidingFrameConfigError& self) { insert(serializer, self.frame_id); @@ -1095,7 +1095,7 @@ void insert(Serializer& serializer, const AidingFrameConfigError& self) insert(serializer, self.attitude[i]); } -void extract(Serializer& serializer, AidingFrameConfigError& self) +void extract(::microstrain::Buffer& serializer, AidingFrameConfigError& self) { extract(serializer, self.frame_id); @@ -1107,7 +1107,7 @@ void extract(Serializer& serializer, AidingFrameConfigError& self) } -void insert(Serializer& serializer, const AidingFrameConfigErrorUncertainty& self) +void insert(::microstrain::Buffer& serializer, const AidingFrameConfigErrorUncertainty& self) { insert(serializer, self.frame_id); @@ -1118,7 +1118,7 @@ void insert(Serializer& serializer, const AidingFrameConfigErrorUncertainty& sel insert(serializer, self.attitude_unc[i]); } -void extract(Serializer& serializer, AidingFrameConfigErrorUncertainty& self) +void extract(::microstrain::Buffer& serializer, AidingFrameConfigErrorUncertainty& self) { extract(serializer, self.frame_id); diff --git a/src/mip/definitions/data_filter.hpp b/src/mip/definitions/data_filter.hpp index 5b2b04fc5..04dd58e77 100644 --- a/src/mip/definitions/data_filter.hpp +++ b/src/mip/definitions/data_filter.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -388,8 +388,8 @@ struct PositionLlh return std::make_tuple(std::ref(latitude),std::ref(longitude),std::ref(ellipsoid_height),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const PositionLlh& self); -void extract(Serializer& serializer, PositionLlh& self); +void insert(::microstrain::Buffer& serializer, const PositionLlh& self); +void extract(::microstrain::Buffer& serializer, PositionLlh& self); ///@} @@ -424,8 +424,8 @@ struct VelocityNed return std::make_tuple(std::ref(north),std::ref(east),std::ref(down),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const VelocityNed& self); -void extract(Serializer& serializer, VelocityNed& self); +void insert(::microstrain::Buffer& serializer, const VelocityNed& self); +void extract(::microstrain::Buffer& serializer, VelocityNed& self); ///@} @@ -466,8 +466,8 @@ struct AttitudeQuaternion return std::make_tuple(std::ref(q[0]),std::ref(q[1]),std::ref(q[2]),std::ref(q[3]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const AttitudeQuaternion& self); -void extract(Serializer& serializer, AttitudeQuaternion& self); +void insert(::microstrain::Buffer& serializer, const AttitudeQuaternion& self); +void extract(::microstrain::Buffer& serializer, AttitudeQuaternion& self); ///@} @@ -510,8 +510,8 @@ struct AttitudeDcm return std::make_tuple(std::ref(dcm[0]),std::ref(dcm[1]),std::ref(dcm[2]),std::ref(dcm[3]),std::ref(dcm[4]),std::ref(dcm[5]),std::ref(dcm[6]),std::ref(dcm[7]),std::ref(dcm[8]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const AttitudeDcm& self); -void extract(Serializer& serializer, AttitudeDcm& self); +void insert(::microstrain::Buffer& serializer, const AttitudeDcm& self); +void extract(::microstrain::Buffer& serializer, AttitudeDcm& self); ///@} @@ -547,8 +547,8 @@ struct EulerAngles return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const EulerAngles& self); -void extract(Serializer& serializer, EulerAngles& self); +void insert(::microstrain::Buffer& serializer, const EulerAngles& self); +void extract(::microstrain::Buffer& serializer, EulerAngles& self); ///@} @@ -581,8 +581,8 @@ struct GyroBias return std::make_tuple(std::ref(bias[0]),std::ref(bias[1]),std::ref(bias[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GyroBias& self); -void extract(Serializer& serializer, GyroBias& self); +void insert(::microstrain::Buffer& serializer, const GyroBias& self); +void extract(::microstrain::Buffer& serializer, GyroBias& self); ///@} @@ -615,8 +615,8 @@ struct AccelBias return std::make_tuple(std::ref(bias[0]),std::ref(bias[1]),std::ref(bias[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const AccelBias& self); -void extract(Serializer& serializer, AccelBias& self); +void insert(::microstrain::Buffer& serializer, const AccelBias& self); +void extract(::microstrain::Buffer& serializer, AccelBias& self); ///@} @@ -651,8 +651,8 @@ struct PositionLlhUncertainty return std::make_tuple(std::ref(north),std::ref(east),std::ref(down),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const PositionLlhUncertainty& self); -void extract(Serializer& serializer, PositionLlhUncertainty& self); +void insert(::microstrain::Buffer& serializer, const PositionLlhUncertainty& self); +void extract(::microstrain::Buffer& serializer, PositionLlhUncertainty& self); ///@} @@ -687,8 +687,8 @@ struct VelocityNedUncertainty return std::make_tuple(std::ref(north),std::ref(east),std::ref(down),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const VelocityNedUncertainty& self); -void extract(Serializer& serializer, VelocityNedUncertainty& self); +void insert(::microstrain::Buffer& serializer, const VelocityNedUncertainty& self); +void extract(::microstrain::Buffer& serializer, VelocityNedUncertainty& self); ///@} @@ -724,8 +724,8 @@ struct EulerAnglesUncertainty return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const EulerAnglesUncertainty& self); -void extract(Serializer& serializer, EulerAnglesUncertainty& self); +void insert(::microstrain::Buffer& serializer, const EulerAnglesUncertainty& self); +void extract(::microstrain::Buffer& serializer, EulerAnglesUncertainty& self); ///@} @@ -758,8 +758,8 @@ struct GyroBiasUncertainty return std::make_tuple(std::ref(bias_uncert[0]),std::ref(bias_uncert[1]),std::ref(bias_uncert[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GyroBiasUncertainty& self); -void extract(Serializer& serializer, GyroBiasUncertainty& self); +void insert(::microstrain::Buffer& serializer, const GyroBiasUncertainty& self); +void extract(::microstrain::Buffer& serializer, GyroBiasUncertainty& self); ///@} @@ -792,8 +792,8 @@ struct AccelBiasUncertainty return std::make_tuple(std::ref(bias_uncert[0]),std::ref(bias_uncert[1]),std::ref(bias_uncert[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const AccelBiasUncertainty& self); -void extract(Serializer& serializer, AccelBiasUncertainty& self); +void insert(::microstrain::Buffer& serializer, const AccelBiasUncertainty& self); +void extract(::microstrain::Buffer& serializer, AccelBiasUncertainty& self); ///@} @@ -833,8 +833,8 @@ struct Timestamp return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const Timestamp& self); -void extract(Serializer& serializer, Timestamp& self); +void insert(::microstrain::Buffer& serializer, const Timestamp& self); +void extract(::microstrain::Buffer& serializer, Timestamp& self); ///@} @@ -868,8 +868,8 @@ struct Status return std::make_tuple(std::ref(filter_state),std::ref(dynamics_mode),std::ref(status_flags)); } }; -void insert(Serializer& serializer, const Status& self); -void extract(Serializer& serializer, Status& self); +void insert(::microstrain::Buffer& serializer, const Status& self); +void extract(::microstrain::Buffer& serializer, Status& self); ///@} @@ -903,8 +903,8 @@ struct LinearAccel return std::make_tuple(std::ref(accel[0]),std::ref(accel[1]),std::ref(accel[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const LinearAccel& self); -void extract(Serializer& serializer, LinearAccel& self); +void insert(::microstrain::Buffer& serializer, const LinearAccel& self); +void extract(::microstrain::Buffer& serializer, LinearAccel& self); ///@} @@ -937,8 +937,8 @@ struct GravityVector return std::make_tuple(std::ref(gravity[0]),std::ref(gravity[1]),std::ref(gravity[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GravityVector& self); -void extract(Serializer& serializer, GravityVector& self); +void insert(::microstrain::Buffer& serializer, const GravityVector& self); +void extract(::microstrain::Buffer& serializer, GravityVector& self); ///@} @@ -971,8 +971,8 @@ struct CompAccel return std::make_tuple(std::ref(accel[0]),std::ref(accel[1]),std::ref(accel[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const CompAccel& self); -void extract(Serializer& serializer, CompAccel& self); +void insert(::microstrain::Buffer& serializer, const CompAccel& self); +void extract(::microstrain::Buffer& serializer, CompAccel& self); ///@} @@ -1005,8 +1005,8 @@ struct CompAngularRate return std::make_tuple(std::ref(gyro[0]),std::ref(gyro[1]),std::ref(gyro[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const CompAngularRate& self); -void extract(Serializer& serializer, CompAngularRate& self); +void insert(::microstrain::Buffer& serializer, const CompAngularRate& self); +void extract(::microstrain::Buffer& serializer, CompAngularRate& self); ///@} @@ -1039,8 +1039,8 @@ struct QuaternionAttitudeUncertainty return std::make_tuple(std::ref(q[0]),std::ref(q[1]),std::ref(q[2]),std::ref(q[3]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const QuaternionAttitudeUncertainty& self); -void extract(Serializer& serializer, QuaternionAttitudeUncertainty& self); +void insert(::microstrain::Buffer& serializer, const QuaternionAttitudeUncertainty& self); +void extract(::microstrain::Buffer& serializer, QuaternionAttitudeUncertainty& self); ///@} @@ -1073,8 +1073,8 @@ struct Wgs84GravityMag return std::make_tuple(std::ref(magnitude),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const Wgs84GravityMag& self); -void extract(Serializer& serializer, Wgs84GravityMag& self); +void insert(::microstrain::Buffer& serializer, const Wgs84GravityMag& self); +void extract(::microstrain::Buffer& serializer, Wgs84GravityMag& self); ///@} @@ -1121,8 +1121,8 @@ struct HeadingUpdateState return std::make_tuple(std::ref(heading),std::ref(heading_1sigma),std::ref(source),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const HeadingUpdateState& self); -void extract(Serializer& serializer, HeadingUpdateState& self); +void insert(::microstrain::Buffer& serializer, const HeadingUpdateState& self); +void extract(::microstrain::Buffer& serializer, HeadingUpdateState& self); ///@} @@ -1160,8 +1160,8 @@ struct MagneticModel return std::make_tuple(std::ref(intensity_north),std::ref(intensity_east),std::ref(intensity_down),std::ref(inclination),std::ref(declination),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MagneticModel& self); -void extract(Serializer& serializer, MagneticModel& self); +void insert(::microstrain::Buffer& serializer, const MagneticModel& self); +void extract(::microstrain::Buffer& serializer, MagneticModel& self); ///@} @@ -1194,8 +1194,8 @@ struct AccelScaleFactor return std::make_tuple(std::ref(scale_factor[0]),std::ref(scale_factor[1]),std::ref(scale_factor[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const AccelScaleFactor& self); -void extract(Serializer& serializer, AccelScaleFactor& self); +void insert(::microstrain::Buffer& serializer, const AccelScaleFactor& self); +void extract(::microstrain::Buffer& serializer, AccelScaleFactor& self); ///@} @@ -1228,8 +1228,8 @@ struct AccelScaleFactorUncertainty return std::make_tuple(std::ref(scale_factor_uncert[0]),std::ref(scale_factor_uncert[1]),std::ref(scale_factor_uncert[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const AccelScaleFactorUncertainty& self); -void extract(Serializer& serializer, AccelScaleFactorUncertainty& self); +void insert(::microstrain::Buffer& serializer, const AccelScaleFactorUncertainty& self); +void extract(::microstrain::Buffer& serializer, AccelScaleFactorUncertainty& self); ///@} @@ -1262,8 +1262,8 @@ struct GyroScaleFactor return std::make_tuple(std::ref(scale_factor[0]),std::ref(scale_factor[1]),std::ref(scale_factor[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GyroScaleFactor& self); -void extract(Serializer& serializer, GyroScaleFactor& self); +void insert(::microstrain::Buffer& serializer, const GyroScaleFactor& self); +void extract(::microstrain::Buffer& serializer, GyroScaleFactor& self); ///@} @@ -1296,8 +1296,8 @@ struct GyroScaleFactorUncertainty return std::make_tuple(std::ref(scale_factor_uncert[0]),std::ref(scale_factor_uncert[1]),std::ref(scale_factor_uncert[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GyroScaleFactorUncertainty& self); -void extract(Serializer& serializer, GyroScaleFactorUncertainty& self); +void insert(::microstrain::Buffer& serializer, const GyroScaleFactorUncertainty& self); +void extract(::microstrain::Buffer& serializer, GyroScaleFactorUncertainty& self); ///@} @@ -1330,8 +1330,8 @@ struct MagBias return std::make_tuple(std::ref(bias[0]),std::ref(bias[1]),std::ref(bias[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MagBias& self); -void extract(Serializer& serializer, MagBias& self); +void insert(::microstrain::Buffer& serializer, const MagBias& self); +void extract(::microstrain::Buffer& serializer, MagBias& self); ///@} @@ -1364,8 +1364,8 @@ struct MagBiasUncertainty return std::make_tuple(std::ref(bias_uncert[0]),std::ref(bias_uncert[1]),std::ref(bias_uncert[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MagBiasUncertainty& self); -void extract(Serializer& serializer, MagBiasUncertainty& self); +void insert(::microstrain::Buffer& serializer, const MagBiasUncertainty& self); +void extract(::microstrain::Buffer& serializer, MagBiasUncertainty& self); ///@} @@ -1404,8 +1404,8 @@ struct StandardAtmosphere return std::make_tuple(std::ref(geometric_altitude),std::ref(geopotential_altitude),std::ref(standard_temperature),std::ref(standard_pressure),std::ref(standard_density),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const StandardAtmosphere& self); -void extract(Serializer& serializer, StandardAtmosphere& self); +void insert(::microstrain::Buffer& serializer, const StandardAtmosphere& self); +void extract(::microstrain::Buffer& serializer, StandardAtmosphere& self); ///@} @@ -1442,8 +1442,8 @@ struct PressureAltitude return std::make_tuple(std::ref(pressure_altitude),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const PressureAltitude& self); -void extract(Serializer& serializer, PressureAltitude& self); +void insert(::microstrain::Buffer& serializer, const PressureAltitude& self); +void extract(::microstrain::Buffer& serializer, PressureAltitude& self); ///@} @@ -1475,8 +1475,8 @@ struct DensityAltitude return std::make_tuple(std::ref(density_altitude),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const DensityAltitude& self); -void extract(Serializer& serializer, DensityAltitude& self); +void insert(::microstrain::Buffer& serializer, const DensityAltitude& self); +void extract(::microstrain::Buffer& serializer, DensityAltitude& self); ///@} @@ -1511,8 +1511,8 @@ struct AntennaOffsetCorrection return std::make_tuple(std::ref(offset[0]),std::ref(offset[1]),std::ref(offset[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const AntennaOffsetCorrection& self); -void extract(Serializer& serializer, AntennaOffsetCorrection& self); +void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrection& self); +void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrection& self); ///@} @@ -1545,8 +1545,8 @@ struct AntennaOffsetCorrectionUncertainty return std::make_tuple(std::ref(offset_uncert[0]),std::ref(offset_uncert[1]),std::ref(offset_uncert[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const AntennaOffsetCorrectionUncertainty& self); -void extract(Serializer& serializer, AntennaOffsetCorrectionUncertainty& self); +void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrectionUncertainty& self); +void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrectionUncertainty& self); ///@} @@ -1582,8 +1582,8 @@ struct MultiAntennaOffsetCorrection return std::make_tuple(std::ref(receiver_id),std::ref(offset[0]),std::ref(offset[1]),std::ref(offset[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MultiAntennaOffsetCorrection& self); -void extract(Serializer& serializer, MultiAntennaOffsetCorrection& self); +void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrection& self); +void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrection& self); ///@} @@ -1617,8 +1617,8 @@ struct MultiAntennaOffsetCorrectionUncertainty return std::make_tuple(std::ref(receiver_id),std::ref(offset_uncert[0]),std::ref(offset_uncert[1]),std::ref(offset_uncert[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self); -void extract(Serializer& serializer, MultiAntennaOffsetCorrectionUncertainty& self); +void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self); +void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrectionUncertainty& self); ///@} @@ -1653,8 +1653,8 @@ struct MagnetometerOffset return std::make_tuple(std::ref(hard_iron[0]),std::ref(hard_iron[1]),std::ref(hard_iron[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MagnetometerOffset& self); -void extract(Serializer& serializer, MagnetometerOffset& self); +void insert(::microstrain::Buffer& serializer, const MagnetometerOffset& self); +void extract(::microstrain::Buffer& serializer, MagnetometerOffset& self); ///@} @@ -1689,8 +1689,8 @@ struct MagnetometerMatrix return std::make_tuple(std::ref(soft_iron[0]),std::ref(soft_iron[1]),std::ref(soft_iron[2]),std::ref(soft_iron[3]),std::ref(soft_iron[4]),std::ref(soft_iron[5]),std::ref(soft_iron[6]),std::ref(soft_iron[7]),std::ref(soft_iron[8]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MagnetometerMatrix& self); -void extract(Serializer& serializer, MagnetometerMatrix& self); +void insert(::microstrain::Buffer& serializer, const MagnetometerMatrix& self); +void extract(::microstrain::Buffer& serializer, MagnetometerMatrix& self); ///@} @@ -1723,8 +1723,8 @@ struct MagnetometerOffsetUncertainty return std::make_tuple(std::ref(hard_iron_uncertainty[0]),std::ref(hard_iron_uncertainty[1]),std::ref(hard_iron_uncertainty[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MagnetometerOffsetUncertainty& self); -void extract(Serializer& serializer, MagnetometerOffsetUncertainty& self); +void insert(::microstrain::Buffer& serializer, const MagnetometerOffsetUncertainty& self); +void extract(::microstrain::Buffer& serializer, MagnetometerOffsetUncertainty& self); ///@} @@ -1757,8 +1757,8 @@ struct MagnetometerMatrixUncertainty return std::make_tuple(std::ref(soft_iron_uncertainty[0]),std::ref(soft_iron_uncertainty[1]),std::ref(soft_iron_uncertainty[2]),std::ref(soft_iron_uncertainty[3]),std::ref(soft_iron_uncertainty[4]),std::ref(soft_iron_uncertainty[5]),std::ref(soft_iron_uncertainty[6]),std::ref(soft_iron_uncertainty[7]),std::ref(soft_iron_uncertainty[8]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MagnetometerMatrixUncertainty& self); -void extract(Serializer& serializer, MagnetometerMatrixUncertainty& self); +void insert(::microstrain::Buffer& serializer, const MagnetometerMatrixUncertainty& self); +void extract(::microstrain::Buffer& serializer, MagnetometerMatrixUncertainty& self); ///@} @@ -1790,8 +1790,8 @@ struct MagnetometerCovarianceMatrix return std::make_tuple(std::ref(covariance[0]),std::ref(covariance[1]),std::ref(covariance[2]),std::ref(covariance[3]),std::ref(covariance[4]),std::ref(covariance[5]),std::ref(covariance[6]),std::ref(covariance[7]),std::ref(covariance[8]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MagnetometerCovarianceMatrix& self); -void extract(Serializer& serializer, MagnetometerCovarianceMatrix& self); +void insert(::microstrain::Buffer& serializer, const MagnetometerCovarianceMatrix& self); +void extract(::microstrain::Buffer& serializer, MagnetometerCovarianceMatrix& self); ///@} @@ -1824,8 +1824,8 @@ struct MagnetometerResidualVector return std::make_tuple(std::ref(residual[0]),std::ref(residual[1]),std::ref(residual[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const MagnetometerResidualVector& self); -void extract(Serializer& serializer, MagnetometerResidualVector& self); +void insert(::microstrain::Buffer& serializer, const MagnetometerResidualVector& self); +void extract(::microstrain::Buffer& serializer, MagnetometerResidualVector& self); ///@} @@ -1860,8 +1860,8 @@ struct ClockCorrection return std::make_tuple(std::ref(receiver_id),std::ref(bias),std::ref(bias_drift),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const ClockCorrection& self); -void extract(Serializer& serializer, ClockCorrection& self); +void insert(::microstrain::Buffer& serializer, const ClockCorrection& self); +void extract(::microstrain::Buffer& serializer, ClockCorrection& self); ///@} @@ -1896,8 +1896,8 @@ struct ClockCorrectionUncertainty return std::make_tuple(std::ref(receiver_id),std::ref(bias_uncertainty),std::ref(bias_drift_uncertainty),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const ClockCorrectionUncertainty& self); -void extract(Serializer& serializer, ClockCorrectionUncertainty& self); +void insert(::microstrain::Buffer& serializer, const ClockCorrectionUncertainty& self); +void extract(::microstrain::Buffer& serializer, ClockCorrectionUncertainty& self); ///@} @@ -1932,8 +1932,8 @@ struct GnssPosAidStatus return std::make_tuple(std::ref(receiver_id),std::ref(time_of_week),std::ref(status),std::ref(reserved)); } }; -void insert(Serializer& serializer, const GnssPosAidStatus& self); -void extract(Serializer& serializer, GnssPosAidStatus& self); +void insert(::microstrain::Buffer& serializer, const GnssPosAidStatus& self); +void extract(::microstrain::Buffer& serializer, GnssPosAidStatus& self); ///@} @@ -1967,8 +1967,8 @@ struct GnssAttAidStatus return std::make_tuple(std::ref(time_of_week),std::ref(status),std::ref(reserved)); } }; -void insert(Serializer& serializer, const GnssAttAidStatus& self); -void extract(Serializer& serializer, GnssAttAidStatus& self); +void insert(::microstrain::Buffer& serializer, const GnssAttAidStatus& self); +void extract(::microstrain::Buffer& serializer, GnssAttAidStatus& self); ///@} @@ -2008,8 +2008,8 @@ struct HeadAidStatus return std::make_tuple(std::ref(time_of_week),std::ref(type),std::ref(reserved)); } }; -void insert(Serializer& serializer, const HeadAidStatus& self); -void extract(Serializer& serializer, HeadAidStatus& self); +void insert(::microstrain::Buffer& serializer, const HeadAidStatus& self); +void extract(::microstrain::Buffer& serializer, HeadAidStatus& self); ///@} @@ -2042,8 +2042,8 @@ struct RelPosNed return std::make_tuple(std::ref(relative_position[0]),std::ref(relative_position[1]),std::ref(relative_position[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const RelPosNed& self); -void extract(Serializer& serializer, RelPosNed& self); +void insert(::microstrain::Buffer& serializer, const RelPosNed& self); +void extract(::microstrain::Buffer& serializer, RelPosNed& self); ///@} @@ -2076,8 +2076,8 @@ struct EcefPos return std::make_tuple(std::ref(position_ecef[0]),std::ref(position_ecef[1]),std::ref(position_ecef[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const EcefPos& self); -void extract(Serializer& serializer, EcefPos& self); +void insert(::microstrain::Buffer& serializer, const EcefPos& self); +void extract(::microstrain::Buffer& serializer, EcefPos& self); ///@} @@ -2110,8 +2110,8 @@ struct EcefVel return std::make_tuple(std::ref(velocity_ecef[0]),std::ref(velocity_ecef[1]),std::ref(velocity_ecef[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const EcefVel& self); -void extract(Serializer& serializer, EcefVel& self); +void insert(::microstrain::Buffer& serializer, const EcefVel& self); +void extract(::microstrain::Buffer& serializer, EcefVel& self); ///@} @@ -2144,8 +2144,8 @@ struct EcefPosUncertainty return std::make_tuple(std::ref(pos_uncertainty[0]),std::ref(pos_uncertainty[1]),std::ref(pos_uncertainty[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const EcefPosUncertainty& self); -void extract(Serializer& serializer, EcefPosUncertainty& self); +void insert(::microstrain::Buffer& serializer, const EcefPosUncertainty& self); +void extract(::microstrain::Buffer& serializer, EcefPosUncertainty& self); ///@} @@ -2178,8 +2178,8 @@ struct EcefVelUncertainty return std::make_tuple(std::ref(vel_uncertainty[0]),std::ref(vel_uncertainty[1]),std::ref(vel_uncertainty[2]),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const EcefVelUncertainty& self); -void extract(Serializer& serializer, EcefVelUncertainty& self); +void insert(::microstrain::Buffer& serializer, const EcefVelUncertainty& self); +void extract(::microstrain::Buffer& serializer, EcefVelUncertainty& self); ///@} @@ -2214,8 +2214,8 @@ struct AidingMeasurementSummary return std::make_tuple(std::ref(time_of_week),std::ref(source),std::ref(type),std::ref(indicator)); } }; -void insert(Serializer& serializer, const AidingMeasurementSummary& self); -void extract(Serializer& serializer, AidingMeasurementSummary& self); +void insert(::microstrain::Buffer& serializer, const AidingMeasurementSummary& self); +void extract(::microstrain::Buffer& serializer, AidingMeasurementSummary& self); ///@} @@ -2248,8 +2248,8 @@ struct OdometerScaleFactorError return std::make_tuple(std::ref(scale_factor_error),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const OdometerScaleFactorError& self); -void extract(Serializer& serializer, OdometerScaleFactorError& self); +void insert(::microstrain::Buffer& serializer, const OdometerScaleFactorError& self); +void extract(::microstrain::Buffer& serializer, OdometerScaleFactorError& self); ///@} @@ -2282,8 +2282,8 @@ struct OdometerScaleFactorErrorUncertainty return std::make_tuple(std::ref(scale_factor_error_uncertainty),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const OdometerScaleFactorErrorUncertainty& self); -void extract(Serializer& serializer, OdometerScaleFactorErrorUncertainty& self); +void insert(::microstrain::Buffer& serializer, const OdometerScaleFactorErrorUncertainty& self); +void extract(::microstrain::Buffer& serializer, OdometerScaleFactorErrorUncertainty& self); ///@} @@ -2358,8 +2358,8 @@ struct GnssDualAntennaStatus return std::make_tuple(std::ref(time_of_week),std::ref(heading),std::ref(heading_unc),std::ref(fix_type),std::ref(status_flags),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GnssDualAntennaStatus& self); -void extract(Serializer& serializer, GnssDualAntennaStatus& self); +void insert(::microstrain::Buffer& serializer, const GnssDualAntennaStatus& self); +void extract(::microstrain::Buffer& serializer, GnssDualAntennaStatus& self); ///@} @@ -2395,8 +2395,8 @@ struct AidingFrameConfigError return std::make_tuple(std::ref(frame_id),std::ref(translation[0]),std::ref(translation[1]),std::ref(translation[2]),std::ref(attitude[0]),std::ref(attitude[1]),std::ref(attitude[2]),std::ref(attitude[3])); } }; -void insert(Serializer& serializer, const AidingFrameConfigError& self); -void extract(Serializer& serializer, AidingFrameConfigError& self); +void insert(::microstrain::Buffer& serializer, const AidingFrameConfigError& self); +void extract(::microstrain::Buffer& serializer, AidingFrameConfigError& self); ///@} @@ -2432,8 +2432,8 @@ struct AidingFrameConfigErrorUncertainty return std::make_tuple(std::ref(frame_id),std::ref(translation_unc[0]),std::ref(translation_unc[1]),std::ref(translation_unc[2]),std::ref(attitude_unc[0]),std::ref(attitude_unc[1]),std::ref(attitude_unc[2])); } }; -void insert(Serializer& serializer, const AidingFrameConfigErrorUncertainty& self); -void extract(Serializer& serializer, AidingFrameConfigErrorUncertainty& self); +void insert(::microstrain::Buffer& serializer, const AidingFrameConfigErrorUncertainty& self); +void extract(::microstrain::Buffer& serializer, AidingFrameConfigErrorUncertainty& self); ///@} diff --git a/src/mip/definitions/data_gnss.cpp b/src/mip/definitions/data_gnss.cpp index 6a82cbc77..741a73479 100644 --- a/src/mip/definitions/data_gnss.cpp +++ b/src/mip/definitions/data_gnss.cpp @@ -1,14 +1,14 @@ #include "data_gnss.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -29,7 +29,7 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const PosLlh& self) +void insert(::microstrain::Buffer& serializer, const PosLlh& self) { insert(serializer, self.latitude); @@ -46,7 +46,7 @@ void insert(Serializer& serializer, const PosLlh& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, PosLlh& self) +void extract(::microstrain::Buffer& serializer, PosLlh& self) { extract(serializer, self.latitude); @@ -64,7 +64,7 @@ void extract(Serializer& serializer, PosLlh& self) } -void insert(Serializer& serializer, const PosEcef& self) +void insert(::microstrain::Buffer& serializer, const PosEcef& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.x[i]); @@ -74,7 +74,7 @@ void insert(Serializer& serializer, const PosEcef& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, PosEcef& self) +void extract(::microstrain::Buffer& serializer, PosEcef& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.x[i]); @@ -85,7 +85,7 @@ void extract(Serializer& serializer, PosEcef& self) } -void insert(Serializer& serializer, const VelNed& self) +void insert(::microstrain::Buffer& serializer, const VelNed& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.v[i]); @@ -103,7 +103,7 @@ void insert(Serializer& serializer, const VelNed& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, VelNed& self) +void extract(::microstrain::Buffer& serializer, VelNed& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.v[i]); @@ -122,7 +122,7 @@ void extract(Serializer& serializer, VelNed& self) } -void insert(Serializer& serializer, const VelEcef& self) +void insert(::microstrain::Buffer& serializer, const VelEcef& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.v[i]); @@ -132,7 +132,7 @@ void insert(Serializer& serializer, const VelEcef& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, VelEcef& self) +void extract(::microstrain::Buffer& serializer, VelEcef& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.v[i]); @@ -143,7 +143,7 @@ void extract(Serializer& serializer, VelEcef& self) } -void insert(Serializer& serializer, const Dop& self) +void insert(::microstrain::Buffer& serializer, const Dop& self) { insert(serializer, self.gdop); @@ -162,7 +162,7 @@ void insert(Serializer& serializer, const Dop& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, Dop& self) +void extract(::microstrain::Buffer& serializer, Dop& self) { extract(serializer, self.gdop); @@ -182,7 +182,7 @@ void extract(Serializer& serializer, Dop& self) } -void insert(Serializer& serializer, const UtcTime& self) +void insert(::microstrain::Buffer& serializer, const UtcTime& self) { insert(serializer, self.year); @@ -201,7 +201,7 @@ void insert(Serializer& serializer, const UtcTime& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, UtcTime& self) +void extract(::microstrain::Buffer& serializer, UtcTime& self) { extract(serializer, self.year); @@ -221,7 +221,7 @@ void extract(Serializer& serializer, UtcTime& self) } -void insert(Serializer& serializer, const GpsTime& self) +void insert(::microstrain::Buffer& serializer, const GpsTime& self) { insert(serializer, self.tow); @@ -230,7 +230,7 @@ void insert(Serializer& serializer, const GpsTime& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GpsTime& self) +void extract(::microstrain::Buffer& serializer, GpsTime& self) { extract(serializer, self.tow); @@ -240,7 +240,7 @@ void extract(Serializer& serializer, GpsTime& self) } -void insert(Serializer& serializer, const ClockInfo& self) +void insert(::microstrain::Buffer& serializer, const ClockInfo& self) { insert(serializer, self.bias); @@ -251,7 +251,7 @@ void insert(Serializer& serializer, const ClockInfo& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, ClockInfo& self) +void extract(::microstrain::Buffer& serializer, ClockInfo& self) { extract(serializer, self.bias); @@ -263,7 +263,7 @@ void extract(Serializer& serializer, ClockInfo& self) } -void insert(Serializer& serializer, const FixInfo& self) +void insert(::microstrain::Buffer& serializer, const FixInfo& self) { insert(serializer, self.fix_type); @@ -274,7 +274,7 @@ void insert(Serializer& serializer, const FixInfo& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, FixInfo& self) +void extract(::microstrain::Buffer& serializer, FixInfo& self) { extract(serializer, self.fix_type); @@ -286,7 +286,7 @@ void extract(Serializer& serializer, FixInfo& self) } -void insert(Serializer& serializer, const SvInfo& self) +void insert(::microstrain::Buffer& serializer, const SvInfo& self) { insert(serializer, self.channel); @@ -303,7 +303,7 @@ void insert(Serializer& serializer, const SvInfo& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, SvInfo& self) +void extract(::microstrain::Buffer& serializer, SvInfo& self) { extract(serializer, self.channel); @@ -321,7 +321,7 @@ void extract(Serializer& serializer, SvInfo& self) } -void insert(Serializer& serializer, const HwStatus& self) +void insert(::microstrain::Buffer& serializer, const HwStatus& self) { insert(serializer, self.receiver_state); @@ -332,7 +332,7 @@ void insert(Serializer& serializer, const HwStatus& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, HwStatus& self) +void extract(::microstrain::Buffer& serializer, HwStatus& self) { extract(serializer, self.receiver_state); @@ -344,7 +344,7 @@ void extract(Serializer& serializer, HwStatus& self) } -void insert(Serializer& serializer, const DgpsInfo& self) +void insert(::microstrain::Buffer& serializer, const DgpsInfo& self) { insert(serializer, self.sv_id); @@ -357,7 +357,7 @@ void insert(Serializer& serializer, const DgpsInfo& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, DgpsInfo& self) +void extract(::microstrain::Buffer& serializer, DgpsInfo& self) { extract(serializer, self.sv_id); @@ -371,7 +371,7 @@ void extract(Serializer& serializer, DgpsInfo& self) } -void insert(Serializer& serializer, const DgpsChannel& self) +void insert(::microstrain::Buffer& serializer, const DgpsChannel& self) { insert(serializer, self.sv_id); @@ -384,7 +384,7 @@ void insert(Serializer& serializer, const DgpsChannel& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, DgpsChannel& self) +void extract(::microstrain::Buffer& serializer, DgpsChannel& self) { extract(serializer, self.sv_id); @@ -398,7 +398,7 @@ void extract(Serializer& serializer, DgpsChannel& self) } -void insert(Serializer& serializer, const ClockInfo2& self) +void insert(::microstrain::Buffer& serializer, const ClockInfo2& self) { insert(serializer, self.bias); @@ -411,7 +411,7 @@ void insert(Serializer& serializer, const ClockInfo2& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, ClockInfo2& self) +void extract(::microstrain::Buffer& serializer, ClockInfo2& self) { extract(serializer, self.bias); @@ -425,14 +425,14 @@ void extract(Serializer& serializer, ClockInfo2& self) } -void insert(Serializer& serializer, const GpsLeapSeconds& self) +void insert(::microstrain::Buffer& serializer, const GpsLeapSeconds& self) { insert(serializer, self.leap_seconds); insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GpsLeapSeconds& self) +void extract(::microstrain::Buffer& serializer, GpsLeapSeconds& self) { extract(serializer, self.leap_seconds); @@ -440,7 +440,7 @@ void extract(Serializer& serializer, GpsLeapSeconds& self) } -void insert(Serializer& serializer, const SbasInfo& self) +void insert(::microstrain::Buffer& serializer, const SbasInfo& self) { insert(serializer, self.time_of_week); @@ -457,7 +457,7 @@ void insert(Serializer& serializer, const SbasInfo& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, SbasInfo& self) +void extract(::microstrain::Buffer& serializer, SbasInfo& self) { extract(serializer, self.time_of_week); @@ -475,7 +475,7 @@ void extract(Serializer& serializer, SbasInfo& self) } -void insert(Serializer& serializer, const SbasCorrection& self) +void insert(::microstrain::Buffer& serializer, const SbasCorrection& self) { insert(serializer, self.index); @@ -498,7 +498,7 @@ void insert(Serializer& serializer, const SbasCorrection& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, SbasCorrection& self) +void extract(::microstrain::Buffer& serializer, SbasCorrection& self) { extract(serializer, self.index); @@ -522,7 +522,7 @@ void extract(Serializer& serializer, SbasCorrection& self) } -void insert(Serializer& serializer, const RfErrorDetection& self) +void insert(::microstrain::Buffer& serializer, const RfErrorDetection& self) { insert(serializer, self.rf_band); @@ -536,7 +536,7 @@ void insert(Serializer& serializer, const RfErrorDetection& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, RfErrorDetection& self) +void extract(::microstrain::Buffer& serializer, RfErrorDetection& self) { extract(serializer, self.rf_band); @@ -551,7 +551,7 @@ void extract(Serializer& serializer, RfErrorDetection& self) } -void insert(Serializer& serializer, const BaseStationInfo& self) +void insert(::microstrain::Buffer& serializer, const BaseStationInfo& self) { insert(serializer, self.time_of_week); @@ -569,7 +569,7 @@ void insert(Serializer& serializer, const BaseStationInfo& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, BaseStationInfo& self) +void extract(::microstrain::Buffer& serializer, BaseStationInfo& self) { extract(serializer, self.time_of_week); @@ -588,7 +588,7 @@ void extract(Serializer& serializer, BaseStationInfo& self) } -void insert(Serializer& serializer, const RtkCorrectionsStatus& self) +void insert(::microstrain::Buffer& serializer, const RtkCorrectionsStatus& self) { insert(serializer, self.time_of_week); @@ -612,7 +612,7 @@ void insert(Serializer& serializer, const RtkCorrectionsStatus& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, RtkCorrectionsStatus& self) +void extract(::microstrain::Buffer& serializer, RtkCorrectionsStatus& self) { extract(serializer, self.time_of_week); @@ -637,7 +637,7 @@ void extract(Serializer& serializer, RtkCorrectionsStatus& self) } -void insert(Serializer& serializer, const SatelliteStatus& self) +void insert(::microstrain::Buffer& serializer, const SatelliteStatus& self) { insert(serializer, self.index); @@ -660,7 +660,7 @@ void insert(Serializer& serializer, const SatelliteStatus& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, SatelliteStatus& self) +void extract(::microstrain::Buffer& serializer, SatelliteStatus& self) { extract(serializer, self.index); @@ -684,7 +684,7 @@ void extract(Serializer& serializer, SatelliteStatus& self) } -void insert(Serializer& serializer, const Raw& self) +void insert(::microstrain::Buffer& serializer, const Raw& self) { insert(serializer, self.index); @@ -725,7 +725,7 @@ void insert(Serializer& serializer, const Raw& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, Raw& self) +void extract(::microstrain::Buffer& serializer, Raw& self) { extract(serializer, self.index); @@ -767,7 +767,7 @@ void extract(Serializer& serializer, Raw& self) } -void insert(Serializer& serializer, const GpsEphemeris& self) +void insert(::microstrain::Buffer& serializer, const GpsEphemeris& self) { insert(serializer, self.index); @@ -838,7 +838,7 @@ void insert(Serializer& serializer, const GpsEphemeris& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GpsEphemeris& self) +void extract(::microstrain::Buffer& serializer, GpsEphemeris& self) { extract(serializer, self.index); @@ -910,7 +910,7 @@ void extract(Serializer& serializer, GpsEphemeris& self) } -void insert(Serializer& serializer, const GalileoEphemeris& self) +void insert(::microstrain::Buffer& serializer, const GalileoEphemeris& self) { insert(serializer, self.index); @@ -981,7 +981,7 @@ void insert(Serializer& serializer, const GalileoEphemeris& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GalileoEphemeris& self) +void extract(::microstrain::Buffer& serializer, GalileoEphemeris& self) { extract(serializer, self.index); @@ -1053,7 +1053,7 @@ void extract(Serializer& serializer, GalileoEphemeris& self) } -void insert(Serializer& serializer, const GloEphemeris& self) +void insert(::microstrain::Buffer& serializer, const GloEphemeris& self) { insert(serializer, self.index); @@ -1109,7 +1109,7 @@ void insert(Serializer& serializer, const GloEphemeris& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GloEphemeris& self) +void extract(::microstrain::Buffer& serializer, GloEphemeris& self) { extract(serializer, self.index); @@ -1166,7 +1166,7 @@ void extract(Serializer& serializer, GloEphemeris& self) } -void insert(Serializer& serializer, const GpsIonoCorr& self) +void insert(::microstrain::Buffer& serializer, const GpsIonoCorr& self) { insert(serializer, self.time_of_week); @@ -1181,7 +1181,7 @@ void insert(Serializer& serializer, const GpsIonoCorr& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GpsIonoCorr& self) +void extract(::microstrain::Buffer& serializer, GpsIonoCorr& self) { extract(serializer, self.time_of_week); @@ -1197,7 +1197,7 @@ void extract(Serializer& serializer, GpsIonoCorr& self) } -void insert(Serializer& serializer, const GalileoIonoCorr& self) +void insert(::microstrain::Buffer& serializer, const GalileoIonoCorr& self) { insert(serializer, self.time_of_week); @@ -1211,7 +1211,7 @@ void insert(Serializer& serializer, const GalileoIonoCorr& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GalileoIonoCorr& self) +void extract(::microstrain::Buffer& serializer, GalileoIonoCorr& self) { extract(serializer, self.time_of_week); diff --git a/src/mip/definitions/data_gnss.hpp b/src/mip/definitions/data_gnss.hpp index 70b783529..2d8de607e 100644 --- a/src/mip/definitions/data_gnss.hpp +++ b/src/mip/definitions/data_gnss.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -241,8 +241,8 @@ struct PosLlh return std::make_tuple(std::ref(latitude),std::ref(longitude),std::ref(ellipsoid_height),std::ref(msl_height),std::ref(horizontal_accuracy),std::ref(vertical_accuracy),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const PosLlh& self); -void extract(Serializer& serializer, PosLlh& self); +void insert(::microstrain::Buffer& serializer, const PosLlh& self); +void extract(::microstrain::Buffer& serializer, PosLlh& self); ///@} @@ -307,8 +307,8 @@ struct PosEcef return std::make_tuple(std::ref(x[0]),std::ref(x[1]),std::ref(x[2]),std::ref(x_accuracy),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const PosEcef& self); -void extract(Serializer& serializer, PosEcef& self); +void insert(::microstrain::Buffer& serializer, const PosEcef& self); +void extract(::microstrain::Buffer& serializer, PosEcef& self); ///@} @@ -389,8 +389,8 @@ struct VelNed return std::make_tuple(std::ref(v[0]),std::ref(v[1]),std::ref(v[2]),std::ref(speed),std::ref(ground_speed),std::ref(heading),std::ref(speed_accuracy),std::ref(heading_accuracy),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const VelNed& self); -void extract(Serializer& serializer, VelNed& self); +void insert(::microstrain::Buffer& serializer, const VelNed& self); +void extract(::microstrain::Buffer& serializer, VelNed& self); ///@} @@ -455,8 +455,8 @@ struct VelEcef return std::make_tuple(std::ref(v[0]),std::ref(v[1]),std::ref(v[2]),std::ref(v_accuracy),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const VelEcef& self); -void extract(Serializer& serializer, VelEcef& self); +void insert(::microstrain::Buffer& serializer, const VelEcef& self); +void extract(::microstrain::Buffer& serializer, VelEcef& self); ///@} @@ -541,8 +541,8 @@ struct Dop return std::make_tuple(std::ref(gdop),std::ref(pdop),std::ref(hdop),std::ref(vdop),std::ref(tdop),std::ref(ndop),std::ref(edop),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const Dop& self); -void extract(Serializer& serializer, Dop& self); +void insert(::microstrain::Buffer& serializer, const Dop& self); +void extract(::microstrain::Buffer& serializer, Dop& self); ///@} @@ -612,8 +612,8 @@ struct UtcTime return std::make_tuple(std::ref(year),std::ref(month),std::ref(day),std::ref(hour),std::ref(min),std::ref(sec),std::ref(msec),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const UtcTime& self); -void extract(Serializer& serializer, UtcTime& self); +void insert(::microstrain::Buffer& serializer, const UtcTime& self); +void extract(::microstrain::Buffer& serializer, UtcTime& self); ///@} @@ -678,8 +678,8 @@ struct GpsTime return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GpsTime& self); -void extract(Serializer& serializer, GpsTime& self); +void insert(::microstrain::Buffer& serializer, const GpsTime& self); +void extract(::microstrain::Buffer& serializer, GpsTime& self); ///@} @@ -748,8 +748,8 @@ struct ClockInfo return std::make_tuple(std::ref(bias),std::ref(drift),std::ref(accuracy_estimate),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const ClockInfo& self); -void extract(Serializer& serializer, ClockInfo& self); +void insert(::microstrain::Buffer& serializer, const ClockInfo& self); +void extract(::microstrain::Buffer& serializer, ClockInfo& self); ///@} @@ -858,8 +858,8 @@ struct FixInfo return std::make_tuple(std::ref(fix_type),std::ref(num_sv),std::ref(fix_flags),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const FixInfo& self); -void extract(Serializer& serializer, FixInfo& self); +void insert(::microstrain::Buffer& serializer, const FixInfo& self); +void extract(::microstrain::Buffer& serializer, FixInfo& self); ///@} @@ -970,8 +970,8 @@ struct SvInfo return std::make_tuple(std::ref(channel),std::ref(sv_id),std::ref(carrier_noise_ratio),std::ref(azimuth),std::ref(elevation),std::ref(sv_flags),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const SvInfo& self); -void extract(Serializer& serializer, SvInfo& self); +void insert(::microstrain::Buffer& serializer, const SvInfo& self); +void extract(::microstrain::Buffer& serializer, SvInfo& self); ///@} @@ -1063,8 +1063,8 @@ struct HwStatus return std::make_tuple(std::ref(receiver_state),std::ref(antenna_state),std::ref(antenna_power),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const HwStatus& self); -void extract(Serializer& serializer, HwStatus& self); +void insert(::microstrain::Buffer& serializer, const HwStatus& self); +void extract(::microstrain::Buffer& serializer, HwStatus& self); ///@} @@ -1149,8 +1149,8 @@ struct DgpsInfo return std::make_tuple(std::ref(sv_id),std::ref(age),std::ref(range_correction),std::ref(range_rate_correction),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const DgpsInfo& self); -void extract(Serializer& serializer, DgpsInfo& self); +void insert(::microstrain::Buffer& serializer, const DgpsInfo& self); +void extract(::microstrain::Buffer& serializer, DgpsInfo& self); ///@} @@ -1225,8 +1225,8 @@ struct DgpsChannel return std::make_tuple(std::ref(sv_id),std::ref(age),std::ref(range_correction),std::ref(range_rate_correction),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const DgpsChannel& self); -void extract(Serializer& serializer, DgpsChannel& self); +void insert(::microstrain::Buffer& serializer, const DgpsChannel& self); +void extract(::microstrain::Buffer& serializer, DgpsChannel& self); ///@} @@ -1301,8 +1301,8 @@ struct ClockInfo2 return std::make_tuple(std::ref(bias),std::ref(drift),std::ref(bias_accuracy_estimate),std::ref(drift_accuracy_estimate),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const ClockInfo2& self); -void extract(Serializer& serializer, ClockInfo2& self); +void insert(::microstrain::Buffer& serializer, const ClockInfo2& self); +void extract(::microstrain::Buffer& serializer, ClockInfo2& self); ///@} @@ -1360,8 +1360,8 @@ struct GpsLeapSeconds return std::make_tuple(std::ref(leap_seconds),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GpsLeapSeconds& self); -void extract(Serializer& serializer, GpsLeapSeconds& self); +void insert(::microstrain::Buffer& serializer, const GpsLeapSeconds& self); +void extract(::microstrain::Buffer& serializer, GpsLeapSeconds& self); ///@} @@ -1476,8 +1476,8 @@ struct SbasInfo return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(sbas_system),std::ref(sbas_id),std::ref(count),std::ref(sbas_status),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const SbasInfo& self); -void extract(Serializer& serializer, SbasInfo& self); +void insert(::microstrain::Buffer& serializer, const SbasInfo& self); +void extract(::microstrain::Buffer& serializer, SbasInfo& self); ///@} @@ -1574,8 +1574,8 @@ struct SbasCorrection return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(gnss_id),std::ref(sv_id),std::ref(udrei),std::ref(pseudorange_correction),std::ref(iono_correction),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const SbasCorrection& self); -void extract(Serializer& serializer, SbasCorrection& self); +void insert(::microstrain::Buffer& serializer, const SbasCorrection& self); +void extract(::microstrain::Buffer& serializer, SbasCorrection& self); ///@} @@ -1669,8 +1669,8 @@ struct RfErrorDetection return std::make_tuple(std::ref(rf_band),std::ref(jamming_state),std::ref(spoofing_state),std::ref(reserved),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const RfErrorDetection& self); -void extract(Serializer& serializer, RfErrorDetection& self); +void insert(::microstrain::Buffer& serializer, const RfErrorDetection& self); +void extract(::microstrain::Buffer& serializer, RfErrorDetection& self); ///@} @@ -1802,8 +1802,8 @@ struct BaseStationInfo return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(ecef_pos[0]),std::ref(ecef_pos[1]),std::ref(ecef_pos[2]),std::ref(height),std::ref(station_id),std::ref(indicators),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const BaseStationInfo& self); -void extract(Serializer& serializer, BaseStationInfo& self); +void insert(::microstrain::Buffer& serializer, const BaseStationInfo& self); +void extract(::microstrain::Buffer& serializer, BaseStationInfo& self); ///@} @@ -1941,8 +1941,8 @@ struct RtkCorrectionsStatus return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(epoch_status),std::ref(dongle_status),std::ref(gps_correction_latency),std::ref(glonass_correction_latency),std::ref(galileo_correction_latency),std::ref(beidou_correction_latency),std::ref(reserved),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const RtkCorrectionsStatus& self); -void extract(Serializer& serializer, RtkCorrectionsStatus& self); +void insert(::microstrain::Buffer& serializer, const RtkCorrectionsStatus& self); +void extract(::microstrain::Buffer& serializer, RtkCorrectionsStatus& self); ///@} @@ -2029,8 +2029,8 @@ struct SatelliteStatus return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(gnss_id),std::ref(satellite_id),std::ref(elevation),std::ref(azimuth),std::ref(health),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const SatelliteStatus& self); -void extract(Serializer& serializer, SatelliteStatus& self); +void insert(::microstrain::Buffer& serializer, const SatelliteStatus& self); +void extract(::microstrain::Buffer& serializer, SatelliteStatus& self); ///@} @@ -2163,8 +2163,8 @@ struct Raw return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(receiver_id),std::ref(tracking_channel),std::ref(gnss_id),std::ref(satellite_id),std::ref(signal_id),std::ref(signal_strength),std::ref(quality),std::ref(pseudorange),std::ref(carrier_phase),std::ref(doppler),std::ref(range_uncert),std::ref(phase_uncert),std::ref(doppler_uncert),std::ref(lock_time),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const Raw& self); -void extract(Serializer& serializer, Raw& self); +void insert(::microstrain::Buffer& serializer, const Raw& self); +void extract(::microstrain::Buffer& serializer, Raw& self); ///@} @@ -2260,8 +2260,8 @@ struct GpsEphemeris return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(satellite_id),std::ref(health),std::ref(iodc),std::ref(iode),std::ref(t_oc),std::ref(af0),std::ref(af1),std::ref(af2),std::ref(t_gd),std::ref(ISC_L1CA),std::ref(ISC_L2C),std::ref(t_oe),std::ref(a),std::ref(a_dot),std::ref(mean_anomaly),std::ref(delta_mean_motion),std::ref(delta_mean_motion_dot),std::ref(eccentricity),std::ref(argument_of_perigee),std::ref(omega),std::ref(omega_dot),std::ref(inclination),std::ref(inclination_dot),std::ref(c_ic),std::ref(c_is),std::ref(c_uc),std::ref(c_us),std::ref(c_rc),std::ref(c_rs),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GpsEphemeris& self); -void extract(Serializer& serializer, GpsEphemeris& self); +void insert(::microstrain::Buffer& serializer, const GpsEphemeris& self); +void extract(::microstrain::Buffer& serializer, GpsEphemeris& self); ///@} @@ -2357,8 +2357,8 @@ struct GalileoEphemeris return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(satellite_id),std::ref(health),std::ref(iodc),std::ref(iode),std::ref(t_oc),std::ref(af0),std::ref(af1),std::ref(af2),std::ref(t_gd),std::ref(ISC_L1CA),std::ref(ISC_L2C),std::ref(t_oe),std::ref(a),std::ref(a_dot),std::ref(mean_anomaly),std::ref(delta_mean_motion),std::ref(delta_mean_motion_dot),std::ref(eccentricity),std::ref(argument_of_perigee),std::ref(omega),std::ref(omega_dot),std::ref(inclination),std::ref(inclination_dot),std::ref(c_ic),std::ref(c_is),std::ref(c_uc),std::ref(c_us),std::ref(c_rc),std::ref(c_rs),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GalileoEphemeris& self); -void extract(Serializer& serializer, GalileoEphemeris& self); +void insert(::microstrain::Buffer& serializer, const GalileoEphemeris& self); +void extract(::microstrain::Buffer& serializer, GalileoEphemeris& self); ///@} @@ -2442,8 +2442,8 @@ struct GloEphemeris return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(satellite_id),std::ref(freq_number),std::ref(tk),std::ref(tb),std::ref(sat_type),std::ref(gamma),std::ref(tau_n),std::ref(x[0]),std::ref(x[1]),std::ref(x[2]),std::ref(v[0]),std::ref(v[1]),std::ref(v[2]),std::ref(a[0]),std::ref(a[1]),std::ref(a[2]),std::ref(health),std::ref(P),std::ref(NT),std::ref(delta_tau_n),std::ref(Ft),std::ref(En),std::ref(P1),std::ref(P2),std::ref(P3),std::ref(P4),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GloEphemeris& self); -void extract(Serializer& serializer, GloEphemeris& self); +void insert(::microstrain::Buffer& serializer, const GloEphemeris& self); +void extract(::microstrain::Buffer& serializer, GloEphemeris& self); ///@} @@ -2516,8 +2516,8 @@ struct GpsIonoCorr return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(alpha),std::ref(beta),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GpsIonoCorr& self); -void extract(Serializer& serializer, GpsIonoCorr& self); +void insert(::microstrain::Buffer& serializer, const GpsIonoCorr& self); +void extract(::microstrain::Buffer& serializer, GpsIonoCorr& self); ///@} @@ -2590,8 +2590,8 @@ struct GalileoIonoCorr return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(alpha[0]),std::ref(alpha[1]),std::ref(alpha[2]),std::ref(disturbance_flags),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GalileoIonoCorr& self); -void extract(Serializer& serializer, GalileoIonoCorr& self); +void insert(::microstrain::Buffer& serializer, const GalileoIonoCorr& self); +void extract(::microstrain::Buffer& serializer, GalileoIonoCorr& self); ///@} diff --git a/src/mip/definitions/data_sensor.cpp b/src/mip/definitions/data_sensor.cpp index 19338d673..40c906b86 100644 --- a/src/mip/definitions/data_sensor.cpp +++ b/src/mip/definitions/data_sensor.cpp @@ -1,14 +1,14 @@ #include "data_sensor.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -29,159 +29,159 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const RawAccel& self) +void insert(::microstrain::Buffer& serializer, const RawAccel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.raw_accel[i]); } -void extract(Serializer& serializer, RawAccel& self) +void extract(::microstrain::Buffer& serializer, RawAccel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.raw_accel[i]); } -void insert(Serializer& serializer, const RawGyro& self) +void insert(::microstrain::Buffer& serializer, const RawGyro& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.raw_gyro[i]); } -void extract(Serializer& serializer, RawGyro& self) +void extract(::microstrain::Buffer& serializer, RawGyro& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.raw_gyro[i]); } -void insert(Serializer& serializer, const RawMag& self) +void insert(::microstrain::Buffer& serializer, const RawMag& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.raw_mag[i]); } -void extract(Serializer& serializer, RawMag& self) +void extract(::microstrain::Buffer& serializer, RawMag& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.raw_mag[i]); } -void insert(Serializer& serializer, const RawPressure& self) +void insert(::microstrain::Buffer& serializer, const RawPressure& self) { insert(serializer, self.raw_pressure); } -void extract(Serializer& serializer, RawPressure& self) +void extract(::microstrain::Buffer& serializer, RawPressure& self) { extract(serializer, self.raw_pressure); } -void insert(Serializer& serializer, const ScaledAccel& self) +void insert(::microstrain::Buffer& serializer, const ScaledAccel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scaled_accel[i]); } -void extract(Serializer& serializer, ScaledAccel& self) +void extract(::microstrain::Buffer& serializer, ScaledAccel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scaled_accel[i]); } -void insert(Serializer& serializer, const ScaledGyro& self) +void insert(::microstrain::Buffer& serializer, const ScaledGyro& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scaled_gyro[i]); } -void extract(Serializer& serializer, ScaledGyro& self) +void extract(::microstrain::Buffer& serializer, ScaledGyro& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scaled_gyro[i]); } -void insert(Serializer& serializer, const ScaledMag& self) +void insert(::microstrain::Buffer& serializer, const ScaledMag& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scaled_mag[i]); } -void extract(Serializer& serializer, ScaledMag& self) +void extract(::microstrain::Buffer& serializer, ScaledMag& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scaled_mag[i]); } -void insert(Serializer& serializer, const ScaledPressure& self) +void insert(::microstrain::Buffer& serializer, const ScaledPressure& self) { insert(serializer, self.scaled_pressure); } -void extract(Serializer& serializer, ScaledPressure& self) +void extract(::microstrain::Buffer& serializer, ScaledPressure& self) { extract(serializer, self.scaled_pressure); } -void insert(Serializer& serializer, const DeltaTheta& self) +void insert(::microstrain::Buffer& serializer, const DeltaTheta& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.delta_theta[i]); } -void extract(Serializer& serializer, DeltaTheta& self) +void extract(::microstrain::Buffer& serializer, DeltaTheta& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.delta_theta[i]); } -void insert(Serializer& serializer, const DeltaVelocity& self) +void insert(::microstrain::Buffer& serializer, const DeltaVelocity& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.delta_velocity[i]); } -void extract(Serializer& serializer, DeltaVelocity& self) +void extract(::microstrain::Buffer& serializer, DeltaVelocity& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.delta_velocity[i]); } -void insert(Serializer& serializer, const CompOrientationMatrix& self) +void insert(::microstrain::Buffer& serializer, const CompOrientationMatrix& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.m[i]); } -void extract(Serializer& serializer, CompOrientationMatrix& self) +void extract(::microstrain::Buffer& serializer, CompOrientationMatrix& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.m[i]); } -void insert(Serializer& serializer, const CompQuaternion& self) +void insert(::microstrain::Buffer& serializer, const CompQuaternion& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.q[i]); } -void extract(Serializer& serializer, CompQuaternion& self) +void extract(::microstrain::Buffer& serializer, CompQuaternion& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.q[i]); } -void insert(Serializer& serializer, const CompEulerAngles& self) +void insert(::microstrain::Buffer& serializer, const CompEulerAngles& self) { insert(serializer, self.roll); @@ -190,7 +190,7 @@ void insert(Serializer& serializer, const CompEulerAngles& self) insert(serializer, self.yaw); } -void extract(Serializer& serializer, CompEulerAngles& self) +void extract(::microstrain::Buffer& serializer, CompEulerAngles& self) { extract(serializer, self.roll); @@ -200,51 +200,51 @@ void extract(Serializer& serializer, CompEulerAngles& self) } -void insert(Serializer& serializer, const CompOrientationUpdateMatrix& self) +void insert(::microstrain::Buffer& serializer, const CompOrientationUpdateMatrix& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.m[i]); } -void extract(Serializer& serializer, CompOrientationUpdateMatrix& self) +void extract(::microstrain::Buffer& serializer, CompOrientationUpdateMatrix& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.m[i]); } -void insert(Serializer& serializer, const OrientationRawTemp& self) +void insert(::microstrain::Buffer& serializer, const OrientationRawTemp& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.raw_temp[i]); } -void extract(Serializer& serializer, OrientationRawTemp& self) +void extract(::microstrain::Buffer& serializer, OrientationRawTemp& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.raw_temp[i]); } -void insert(Serializer& serializer, const InternalTimestamp& self) +void insert(::microstrain::Buffer& serializer, const InternalTimestamp& self) { insert(serializer, self.counts); } -void extract(Serializer& serializer, InternalTimestamp& self) +void extract(::microstrain::Buffer& serializer, InternalTimestamp& self) { extract(serializer, self.counts); } -void insert(Serializer& serializer, const PpsTimestamp& self) +void insert(::microstrain::Buffer& serializer, const PpsTimestamp& self) { insert(serializer, self.seconds); insert(serializer, self.useconds); } -void extract(Serializer& serializer, PpsTimestamp& self) +void extract(::microstrain::Buffer& serializer, PpsTimestamp& self) { extract(serializer, self.seconds); @@ -252,7 +252,7 @@ void extract(Serializer& serializer, PpsTimestamp& self) } -void insert(Serializer& serializer, const GpsTimestamp& self) +void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self) { insert(serializer, self.tow); @@ -261,7 +261,7 @@ void insert(Serializer& serializer, const GpsTimestamp& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GpsTimestamp& self) +void extract(::microstrain::Buffer& serializer, GpsTimestamp& self) { extract(serializer, self.tow); @@ -271,7 +271,7 @@ void extract(Serializer& serializer, GpsTimestamp& self) } -void insert(Serializer& serializer, const TemperatureAbs& self) +void insert(::microstrain::Buffer& serializer, const TemperatureAbs& self) { insert(serializer, self.min_temp); @@ -280,7 +280,7 @@ void insert(Serializer& serializer, const TemperatureAbs& self) insert(serializer, self.mean_temp); } -void extract(Serializer& serializer, TemperatureAbs& self) +void extract(::microstrain::Buffer& serializer, TemperatureAbs& self) { extract(serializer, self.min_temp); @@ -290,44 +290,44 @@ void extract(Serializer& serializer, TemperatureAbs& self) } -void insert(Serializer& serializer, const UpVector& self) +void insert(::microstrain::Buffer& serializer, const UpVector& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.up[i]); } -void extract(Serializer& serializer, UpVector& self) +void extract(::microstrain::Buffer& serializer, UpVector& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.up[i]); } -void insert(Serializer& serializer, const NorthVector& self) +void insert(::microstrain::Buffer& serializer, const NorthVector& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.north[i]); } -void extract(Serializer& serializer, NorthVector& self) +void extract(::microstrain::Buffer& serializer, NorthVector& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.north[i]); } -void insert(Serializer& serializer, const OverrangeStatus& self) +void insert(::microstrain::Buffer& serializer, const OverrangeStatus& self) { insert(serializer, self.status); } -void extract(Serializer& serializer, OverrangeStatus& self) +void extract(::microstrain::Buffer& serializer, OverrangeStatus& self) { extract(serializer, self.status); } -void insert(Serializer& serializer, const OdometerData& self) +void insert(::microstrain::Buffer& serializer, const OdometerData& self) { insert(serializer, self.speed); @@ -336,7 +336,7 @@ void insert(Serializer& serializer, const OdometerData& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, OdometerData& self) +void extract(::microstrain::Buffer& serializer, OdometerData& self) { extract(serializer, self.speed); diff --git a/src/mip/definitions/data_sensor.hpp b/src/mip/definitions/data_sensor.hpp index dde268718..d7fd48366 100644 --- a/src/mip/definitions/data_sensor.hpp +++ b/src/mip/definitions/data_sensor.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -98,8 +98,8 @@ struct RawAccel return std::make_tuple(std::ref(raw_accel[0]),std::ref(raw_accel[1]),std::ref(raw_accel[2])); } }; -void insert(Serializer& serializer, const RawAccel& self); -void extract(Serializer& serializer, RawAccel& self); +void insert(::microstrain::Buffer& serializer, const RawAccel& self); +void extract(::microstrain::Buffer& serializer, RawAccel& self); ///@} @@ -132,8 +132,8 @@ struct RawGyro return std::make_tuple(std::ref(raw_gyro[0]),std::ref(raw_gyro[1]),std::ref(raw_gyro[2])); } }; -void insert(Serializer& serializer, const RawGyro& self); -void extract(Serializer& serializer, RawGyro& self); +void insert(::microstrain::Buffer& serializer, const RawGyro& self); +void extract(::microstrain::Buffer& serializer, RawGyro& self); ///@} @@ -166,8 +166,8 @@ struct RawMag return std::make_tuple(std::ref(raw_mag[0]),std::ref(raw_mag[1]),std::ref(raw_mag[2])); } }; -void insert(Serializer& serializer, const RawMag& self); -void extract(Serializer& serializer, RawMag& self); +void insert(::microstrain::Buffer& serializer, const RawMag& self); +void extract(::microstrain::Buffer& serializer, RawMag& self); ///@} @@ -200,8 +200,8 @@ struct RawPressure return std::make_tuple(std::ref(raw_pressure)); } }; -void insert(Serializer& serializer, const RawPressure& self); -void extract(Serializer& serializer, RawPressure& self); +void insert(::microstrain::Buffer& serializer, const RawPressure& self); +void extract(::microstrain::Buffer& serializer, RawPressure& self); ///@} @@ -234,8 +234,8 @@ struct ScaledAccel return std::make_tuple(std::ref(scaled_accel[0]),std::ref(scaled_accel[1]),std::ref(scaled_accel[2])); } }; -void insert(Serializer& serializer, const ScaledAccel& self); -void extract(Serializer& serializer, ScaledAccel& self); +void insert(::microstrain::Buffer& serializer, const ScaledAccel& self); +void extract(::microstrain::Buffer& serializer, ScaledAccel& self); ///@} @@ -268,8 +268,8 @@ struct ScaledGyro return std::make_tuple(std::ref(scaled_gyro[0]),std::ref(scaled_gyro[1]),std::ref(scaled_gyro[2])); } }; -void insert(Serializer& serializer, const ScaledGyro& self); -void extract(Serializer& serializer, ScaledGyro& self); +void insert(::microstrain::Buffer& serializer, const ScaledGyro& self); +void extract(::microstrain::Buffer& serializer, ScaledGyro& self); ///@} @@ -302,8 +302,8 @@ struct ScaledMag return std::make_tuple(std::ref(scaled_mag[0]),std::ref(scaled_mag[1]),std::ref(scaled_mag[2])); } }; -void insert(Serializer& serializer, const ScaledMag& self); -void extract(Serializer& serializer, ScaledMag& self); +void insert(::microstrain::Buffer& serializer, const ScaledMag& self); +void extract(::microstrain::Buffer& serializer, ScaledMag& self); ///@} @@ -335,8 +335,8 @@ struct ScaledPressure return std::make_tuple(std::ref(scaled_pressure)); } }; -void insert(Serializer& serializer, const ScaledPressure& self); -void extract(Serializer& serializer, ScaledPressure& self); +void insert(::microstrain::Buffer& serializer, const ScaledPressure& self); +void extract(::microstrain::Buffer& serializer, ScaledPressure& self); ///@} @@ -369,8 +369,8 @@ struct DeltaTheta return std::make_tuple(std::ref(delta_theta[0]),std::ref(delta_theta[1]),std::ref(delta_theta[2])); } }; -void insert(Serializer& serializer, const DeltaTheta& self); -void extract(Serializer& serializer, DeltaTheta& self); +void insert(::microstrain::Buffer& serializer, const DeltaTheta& self); +void extract(::microstrain::Buffer& serializer, DeltaTheta& self); ///@} @@ -403,8 +403,8 @@ struct DeltaVelocity return std::make_tuple(std::ref(delta_velocity[0]),std::ref(delta_velocity[1]),std::ref(delta_velocity[2])); } }; -void insert(Serializer& serializer, const DeltaVelocity& self); -void extract(Serializer& serializer, DeltaVelocity& self); +void insert(::microstrain::Buffer& serializer, const DeltaVelocity& self); +void extract(::microstrain::Buffer& serializer, DeltaVelocity& self); ///@} @@ -446,8 +446,8 @@ struct CompOrientationMatrix return std::make_tuple(std::ref(m[0]),std::ref(m[1]),std::ref(m[2]),std::ref(m[3]),std::ref(m[4]),std::ref(m[5]),std::ref(m[6]),std::ref(m[7]),std::ref(m[8])); } }; -void insert(Serializer& serializer, const CompOrientationMatrix& self); -void extract(Serializer& serializer, CompOrientationMatrix& self); +void insert(::microstrain::Buffer& serializer, const CompOrientationMatrix& self); +void extract(::microstrain::Buffer& serializer, CompOrientationMatrix& self); ///@} @@ -487,8 +487,8 @@ struct CompQuaternion return std::make_tuple(std::ref(q[0]),std::ref(q[1]),std::ref(q[2]),std::ref(q[3])); } }; -void insert(Serializer& serializer, const CompQuaternion& self); -void extract(Serializer& serializer, CompQuaternion& self); +void insert(::microstrain::Buffer& serializer, const CompQuaternion& self); +void extract(::microstrain::Buffer& serializer, CompQuaternion& self); ///@} @@ -523,8 +523,8 @@ struct CompEulerAngles return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); } }; -void insert(Serializer& serializer, const CompEulerAngles& self); -void extract(Serializer& serializer, CompEulerAngles& self); +void insert(::microstrain::Buffer& serializer, const CompEulerAngles& self); +void extract(::microstrain::Buffer& serializer, CompEulerAngles& self); ///@} @@ -556,8 +556,8 @@ struct CompOrientationUpdateMatrix return std::make_tuple(std::ref(m[0]),std::ref(m[1]),std::ref(m[2]),std::ref(m[3]),std::ref(m[4]),std::ref(m[5]),std::ref(m[6]),std::ref(m[7]),std::ref(m[8])); } }; -void insert(Serializer& serializer, const CompOrientationUpdateMatrix& self); -void extract(Serializer& serializer, CompOrientationUpdateMatrix& self); +void insert(::microstrain::Buffer& serializer, const CompOrientationUpdateMatrix& self); +void extract(::microstrain::Buffer& serializer, CompOrientationUpdateMatrix& self); ///@} @@ -589,8 +589,8 @@ struct OrientationRawTemp return std::make_tuple(std::ref(raw_temp)); } }; -void insert(Serializer& serializer, const OrientationRawTemp& self); -void extract(Serializer& serializer, OrientationRawTemp& self); +void insert(::microstrain::Buffer& serializer, const OrientationRawTemp& self); +void extract(::microstrain::Buffer& serializer, OrientationRawTemp& self); ///@} @@ -622,8 +622,8 @@ struct InternalTimestamp return std::make_tuple(std::ref(counts)); } }; -void insert(Serializer& serializer, const InternalTimestamp& self); -void extract(Serializer& serializer, InternalTimestamp& self); +void insert(::microstrain::Buffer& serializer, const InternalTimestamp& self); +void extract(::microstrain::Buffer& serializer, InternalTimestamp& self); ///@} @@ -656,8 +656,8 @@ struct PpsTimestamp return std::make_tuple(std::ref(seconds),std::ref(useconds)); } }; -void insert(Serializer& serializer, const PpsTimestamp& self); -void extract(Serializer& serializer, PpsTimestamp& self); +void insert(::microstrain::Buffer& serializer, const PpsTimestamp& self); +void extract(::microstrain::Buffer& serializer, PpsTimestamp& self); ///@} @@ -734,8 +734,8 @@ struct GpsTimestamp return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GpsTimestamp& self); -void extract(Serializer& serializer, GpsTimestamp& self); +void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self); +void extract(::microstrain::Buffer& serializer, GpsTimestamp& self); ///@} @@ -773,8 +773,8 @@ struct TemperatureAbs return std::make_tuple(std::ref(min_temp),std::ref(max_temp),std::ref(mean_temp)); } }; -void insert(Serializer& serializer, const TemperatureAbs& self); -void extract(Serializer& serializer, TemperatureAbs& self); +void insert(::microstrain::Buffer& serializer, const TemperatureAbs& self); +void extract(::microstrain::Buffer& serializer, TemperatureAbs& self); ///@} @@ -812,8 +812,8 @@ struct UpVector return std::make_tuple(std::ref(up[0]),std::ref(up[1]),std::ref(up[2])); } }; -void insert(Serializer& serializer, const UpVector& self); -void extract(Serializer& serializer, UpVector& self); +void insert(::microstrain::Buffer& serializer, const UpVector& self); +void extract(::microstrain::Buffer& serializer, UpVector& self); ///@} @@ -848,8 +848,8 @@ struct NorthVector return std::make_tuple(std::ref(north[0]),std::ref(north[1]),std::ref(north[2])); } }; -void insert(Serializer& serializer, const NorthVector& self); -void extract(Serializer& serializer, NorthVector& self); +void insert(::microstrain::Buffer& serializer, const NorthVector& self); +void extract(::microstrain::Buffer& serializer, NorthVector& self); ///@} @@ -932,8 +932,8 @@ struct OverrangeStatus return std::make_tuple(std::ref(status)); } }; -void insert(Serializer& serializer, const OverrangeStatus& self); -void extract(Serializer& serializer, OverrangeStatus& self); +void insert(::microstrain::Buffer& serializer, const OverrangeStatus& self); +void extract(::microstrain::Buffer& serializer, OverrangeStatus& self); ///@} @@ -966,8 +966,8 @@ struct OdometerData return std::make_tuple(std::ref(speed),std::ref(uncertainty),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const OdometerData& self); -void extract(Serializer& serializer, OdometerData& self); +void insert(::microstrain::Buffer& serializer, const OdometerData& self); +void extract(::microstrain::Buffer& serializer, OdometerData& self); ///@} diff --git a/src/mip/definitions/data_shared.cpp b/src/mip/definitions/data_shared.cpp index 2f8768339..c9963b440 100644 --- a/src/mip/definitions/data_shared.cpp +++ b/src/mip/definitions/data_shared.cpp @@ -1,14 +1,14 @@ #include "data_shared.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -29,40 +29,40 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const EventSource& self) +void insert(::microstrain::Buffer& serializer, const EventSource& self) { insert(serializer, self.trigger_id); } -void extract(Serializer& serializer, EventSource& self) +void extract(::microstrain::Buffer& serializer, EventSource& self) { extract(serializer, self.trigger_id); } -void insert(Serializer& serializer, const Ticks& self) +void insert(::microstrain::Buffer& serializer, const Ticks& self) { insert(serializer, self.ticks); } -void extract(Serializer& serializer, Ticks& self) +void extract(::microstrain::Buffer& serializer, Ticks& self) { extract(serializer, self.ticks); } -void insert(Serializer& serializer, const DeltaTicks& self) +void insert(::microstrain::Buffer& serializer, const DeltaTicks& self) { insert(serializer, self.ticks); } -void extract(Serializer& serializer, DeltaTicks& self) +void extract(::microstrain::Buffer& serializer, DeltaTicks& self) { extract(serializer, self.ticks); } -void insert(Serializer& serializer, const GpsTimestamp& self) +void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self) { insert(serializer, self.tow); @@ -71,7 +71,7 @@ void insert(Serializer& serializer, const GpsTimestamp& self) insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, GpsTimestamp& self) +void extract(::microstrain::Buffer& serializer, GpsTimestamp& self) { extract(serializer, self.tow); @@ -81,47 +81,47 @@ void extract(Serializer& serializer, GpsTimestamp& self) } -void insert(Serializer& serializer, const DeltaTime& self) +void insert(::microstrain::Buffer& serializer, const DeltaTime& self) { insert(serializer, self.seconds); } -void extract(Serializer& serializer, DeltaTime& self) +void extract(::microstrain::Buffer& serializer, DeltaTime& self) { extract(serializer, self.seconds); } -void insert(Serializer& serializer, const ReferenceTimestamp& self) +void insert(::microstrain::Buffer& serializer, const ReferenceTimestamp& self) { insert(serializer, self.nanoseconds); } -void extract(Serializer& serializer, ReferenceTimestamp& self) +void extract(::microstrain::Buffer& serializer, ReferenceTimestamp& self) { extract(serializer, self.nanoseconds); } -void insert(Serializer& serializer, const ReferenceTimeDelta& self) +void insert(::microstrain::Buffer& serializer, const ReferenceTimeDelta& self) { insert(serializer, self.dt_nanos); } -void extract(Serializer& serializer, ReferenceTimeDelta& self) +void extract(::microstrain::Buffer& serializer, ReferenceTimeDelta& self) { extract(serializer, self.dt_nanos); } -void insert(Serializer& serializer, const ExternalTimestamp& self) +void insert(::microstrain::Buffer& serializer, const ExternalTimestamp& self) { insert(serializer, self.nanoseconds); insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, ExternalTimestamp& self) +void extract(::microstrain::Buffer& serializer, ExternalTimestamp& self) { extract(serializer, self.nanoseconds); @@ -129,14 +129,14 @@ void extract(Serializer& serializer, ExternalTimestamp& self) } -void insert(Serializer& serializer, const ExternalTimeDelta& self) +void insert(::microstrain::Buffer& serializer, const ExternalTimeDelta& self) { insert(serializer, self.dt_nanos); insert(serializer, self.valid_flags); } -void extract(Serializer& serializer, ExternalTimeDelta& self) +void extract(::microstrain::Buffer& serializer, ExternalTimeDelta& self) { extract(serializer, self.dt_nanos); diff --git a/src/mip/definitions/data_shared.hpp b/src/mip/definitions/data_shared.hpp index 05df1eddf..1c37600e1 100644 --- a/src/mip/definitions/data_shared.hpp +++ b/src/mip/definitions/data_shared.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -85,8 +85,8 @@ struct EventSource return std::make_tuple(std::ref(trigger_id)); } }; -void insert(Serializer& serializer, const EventSource& self); -void extract(Serializer& serializer, EventSource& self); +void insert(::microstrain::Buffer& serializer, const EventSource& self); +void extract(::microstrain::Buffer& serializer, EventSource& self); ///@} @@ -121,8 +121,8 @@ struct Ticks return std::make_tuple(std::ref(ticks)); } }; -void insert(Serializer& serializer, const Ticks& self); -void extract(Serializer& serializer, Ticks& self); +void insert(::microstrain::Buffer& serializer, const Ticks& self); +void extract(::microstrain::Buffer& serializer, Ticks& self); ///@} @@ -158,8 +158,8 @@ struct DeltaTicks return std::make_tuple(std::ref(ticks)); } }; -void insert(Serializer& serializer, const DeltaTicks& self); -void extract(Serializer& serializer, DeltaTicks& self); +void insert(::microstrain::Buffer& serializer, const DeltaTicks& self); +void extract(::microstrain::Buffer& serializer, DeltaTicks& self); ///@} @@ -227,8 +227,8 @@ struct GpsTimestamp return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const GpsTimestamp& self); -void extract(Serializer& serializer, GpsTimestamp& self); +void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self); +void extract(::microstrain::Buffer& serializer, GpsTimestamp& self); ///@} @@ -269,8 +269,8 @@ struct DeltaTime return std::make_tuple(std::ref(seconds)); } }; -void insert(Serializer& serializer, const DeltaTime& self); -void extract(Serializer& serializer, DeltaTime& self); +void insert(::microstrain::Buffer& serializer, const DeltaTime& self); +void extract(::microstrain::Buffer& serializer, DeltaTime& self); ///@} @@ -309,8 +309,8 @@ struct ReferenceTimestamp return std::make_tuple(std::ref(nanoseconds)); } }; -void insert(Serializer& serializer, const ReferenceTimestamp& self); -void extract(Serializer& serializer, ReferenceTimestamp& self); +void insert(::microstrain::Buffer& serializer, const ReferenceTimestamp& self); +void extract(::microstrain::Buffer& serializer, ReferenceTimestamp& self); ///@} @@ -351,8 +351,8 @@ struct ReferenceTimeDelta return std::make_tuple(std::ref(dt_nanos)); } }; -void insert(Serializer& serializer, const ReferenceTimeDelta& self); -void extract(Serializer& serializer, ReferenceTimeDelta& self); +void insert(::microstrain::Buffer& serializer, const ReferenceTimeDelta& self); +void extract(::microstrain::Buffer& serializer, ReferenceTimeDelta& self); ///@} @@ -418,8 +418,8 @@ struct ExternalTimestamp return std::make_tuple(std::ref(nanoseconds),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const ExternalTimestamp& self); -void extract(Serializer& serializer, ExternalTimestamp& self); +void insert(::microstrain::Buffer& serializer, const ExternalTimestamp& self); +void extract(::microstrain::Buffer& serializer, ExternalTimestamp& self); ///@} @@ -489,8 +489,8 @@ struct ExternalTimeDelta return std::make_tuple(std::ref(dt_nanos),std::ref(valid_flags)); } }; -void insert(Serializer& serializer, const ExternalTimeDelta& self); -void extract(Serializer& serializer, ExternalTimeDelta& self); +void insert(::microstrain::Buffer& serializer, const ExternalTimeDelta& self); +void extract(::microstrain::Buffer& serializer, ExternalTimeDelta& self); ///@} diff --git a/src/mip/definitions/data_system.cpp b/src/mip/definitions/data_system.cpp index 7a6446044..2de74ac20 100644 --- a/src/mip/definitions/data_system.cpp +++ b/src/mip/definitions/data_system.cpp @@ -1,14 +1,14 @@ #include "data_system.hpp" -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" #include "../mip_interface.h" #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -29,27 +29,27 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(Serializer& serializer, const BuiltInTest& self) +void insert(::microstrain::Buffer& serializer, const BuiltInTest& self) { for(unsigned int i=0; i < 16; i++) insert(serializer, self.result[i]); } -void extract(Serializer& serializer, BuiltInTest& self) +void extract(::microstrain::Buffer& serializer, BuiltInTest& self) { for(unsigned int i=0; i < 16; i++) extract(serializer, self.result[i]); } -void insert(Serializer& serializer, const TimeSyncStatus& self) +void insert(::microstrain::Buffer& serializer, const TimeSyncStatus& self) { insert(serializer, self.time_sync); insert(serializer, self.last_pps_rcvd); } -void extract(Serializer& serializer, TimeSyncStatus& self) +void extract(::microstrain::Buffer& serializer, TimeSyncStatus& self) { extract(serializer, self.time_sync); @@ -57,25 +57,25 @@ void extract(Serializer& serializer, TimeSyncStatus& self) } -void insert(Serializer& serializer, const GpioState& self) +void insert(::microstrain::Buffer& serializer, const GpioState& self) { insert(serializer, self.states); } -void extract(Serializer& serializer, GpioState& self) +void extract(::microstrain::Buffer& serializer, GpioState& self) { extract(serializer, self.states); } -void insert(Serializer& serializer, const GpioAnalogValue& self) +void insert(::microstrain::Buffer& serializer, const GpioAnalogValue& self) { insert(serializer, self.gpio_id); insert(serializer, self.value); } -void extract(Serializer& serializer, GpioAnalogValue& self) +void extract(::microstrain::Buffer& serializer, GpioAnalogValue& self) { extract(serializer, self.gpio_id); diff --git a/src/mip/definitions/data_system.hpp b/src/mip/definitions/data_system.hpp index 17170999f..5bec37524 100644 --- a/src/mip/definitions/data_system.hpp +++ b/src/mip/definitions/data_system.hpp @@ -9,7 +9,7 @@ #include namespace mip { -class Serializer; +; namespace C { struct mip_interface; @@ -93,8 +93,8 @@ struct BuiltInTest return std::make_tuple(std::ref(result)); } }; -void insert(Serializer& serializer, const BuiltInTest& self); -void extract(Serializer& serializer, BuiltInTest& self); +void insert(::microstrain::Buffer& serializer, const BuiltInTest& self); +void extract(::microstrain::Buffer& serializer, BuiltInTest& self); ///@} @@ -127,8 +127,8 @@ struct TimeSyncStatus return std::make_tuple(std::ref(time_sync),std::ref(last_pps_rcvd)); } }; -void insert(Serializer& serializer, const TimeSyncStatus& self); -void extract(Serializer& serializer, TimeSyncStatus& self); +void insert(::microstrain::Buffer& serializer, const TimeSyncStatus& self); +void extract(::microstrain::Buffer& serializer, TimeSyncStatus& self); ///@} @@ -178,8 +178,8 @@ struct GpioState return std::make_tuple(std::ref(states)); } }; -void insert(Serializer& serializer, const GpioState& self); -void extract(Serializer& serializer, GpioState& self); +void insert(::microstrain::Buffer& serializer, const GpioState& self); +void extract(::microstrain::Buffer& serializer, GpioState& self); ///@} @@ -213,8 +213,8 @@ struct GpioAnalogValue return std::make_tuple(std::ref(gpio_id),std::ref(value)); } }; -void insert(Serializer& serializer, const GpioAnalogValue& self); -void extract(Serializer& serializer, GpioAnalogValue& self); +void insert(::microstrain::Buffer& serializer, const GpioAnalogValue& self); +void extract(::microstrain::Buffer& serializer, GpioAnalogValue& self); ///@} diff --git a/src/mip/definitions/descriptors.h b/src/mip/definitions/descriptors.h index 1bb90cf39..abf4cff34 100644 --- a/src/mip/definitions/descriptors.h +++ b/src/mip/definitions/descriptors.h @@ -7,6 +7,7 @@ #include "../mip_result.h" #ifdef __cplusplus +#include "microstrain/common/buffer.hpp" #include #include @@ -14,6 +15,7 @@ namespace mip { namespace C { +using ::microstrain::C::microstrain_serializer; extern "C" { #endif // __cplusplus @@ -89,8 +91,8 @@ struct CompositeDescriptor /// template struct Bitfield {}; -template void insert (microstrain::Serializer& serializer, const Bitfield& bitfield) { insert(serializer, static_cast(bitfield).value); } -template void extract(microstrain::Serializer& serializer, Bitfield& bitfield) { extract(serializer, static_cast(bitfield).value); } +template void insert (::microstrain::Buffer& serializer, const Bitfield& bitfield) { insert(serializer, static_cast(bitfield).value); } +template void extract(::microstrain::Buffer& serializer, Bitfield& bitfield) { extract(serializer, static_cast(bitfield).value); } enum class FunctionSelector : uint8_t diff --git a/src/mip/mip.hpp b/src/mip/mip.hpp index 336bc31b3..55c326ba9 100644 --- a/src/mip/mip.hpp +++ b/src/mip/mip.hpp @@ -174,9 +174,35 @@ class PacketRef : public C::mip_packet int remainingSpace() const { return C::mip_packet_remaining_space(this); } ///<@copydoc mip::C::mip_packet_remaining_space bool addField(uint8_t fieldDescriptor, const uint8_t* payload, uint8_t payloadLength) { return C::mip_packet_add_field(this, fieldDescriptor, payload, payloadLength); } ///<@copydoc mip::C::mip_packet_add_field - int allocField(uint8_t fieldDescriptor, uint8_t payloadLength, uint8_t** payloadPtr_out) { return C::mip_packet_alloc_field(this, fieldDescriptor, payloadLength, payloadPtr_out); } ///<@copydoc mip::C::mip_packet_alloc_field - int reallocLastField(uint8_t* payloadPtr, uint8_t newPayloadLength) { return C::mip_packet_realloc_last_field(this, payloadPtr, newPayloadLength); } ///<@copydoc mip::C::mip_packet_realloc_last_field - int cancelLastField(uint8_t* payloadPtr) { return C::mip_packet_cancel_last_field(this, payloadPtr); } ///<@copydoc mip::C::mip_packet_cancel_last_field + microstrain::Buffer createField(uint8_t fieldDescriptor, uint8_t length) { uint8_t* ptr; if(C::mip_packet_alloc_field(this, fieldDescriptor, length, &ptr) < 0) length=0; return microstrain::Buffer{ptr, length}; } + //std::tuple createField(uint8_t fieldDescriptor) { uint8_t* ptr; int max_size = C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr); return max_size >= 0 ? std::make_tuple(ptr, max_size) : std::make_tuple(nullptr, 0); } ///<@copydoc mip::C::mip_packet_alloc_field + //int finishLastField(uint8_t* payloadPtr, uint8_t newPayloadLength) { return C::mip_packet_realloc_last_field(this, payloadPtr, newPayloadLength); } ///<@copydoc mip::C::mip_packet_realloc_last_field + //int cancelLastField(uint8_t* payloadPtr) { return C::mip_packet_cancel_last_field(this, payloadPtr); } ///<@copydoc mip::C::mip_packet_cancel_last_field + + class AllocatedField : public microstrain::Buffer + { + public: + AllocatedField(mip::PacketRef& packet, uint8_t* buffer, size_t space) : Buffer(buffer, space), m_packet(packet) {} + AllocatedField(const AllocatedField&) = delete; + AllocatedField& operator=(const AllocatedField&) = delete; + + bool commit() + { + bool ok = isOk(); + + if(ok) + C::mip_packet_realloc_last_field(&m_packet, pointer(), length()); + else + C::mip_packet_cancel_last_field(&m_packet, pointer()); + + return ok; + } + + private: + PacketRef& m_packet; + }; + + AllocatedField createField(uint8_t fieldDescriptor) { uint8_t* ptr; size_t max_size = std::max(0, C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr)); return {*this, ptr, max_size}; } void finalize() { C::mip_packet_finalize(this); } ///<@copydoc mip::C::mip_packet_finalize @@ -229,10 +255,10 @@ class PacketRef : public C::mip_packet { if( fieldDescriptor == INVALID_FIELD_DESCRIPTOR ) fieldDescriptor = FieldType::FIELD_DESCRIPTOR; - microstrain::Serializer serializer(*this, fieldDescriptor); - insert(serializer, field); - C::microstrain_serializer_finish_new_field(&serializer, this); - return serializer.isOk(); + + AllocatedField buffer = createField(fieldDescriptor); + buffer.insert(field); + return buffer.commit(); } ///@brief Creates a new PacketRef containing a single MIP field from an instance of the field type. diff --git a/src/mip/mip_all.hpp b/src/mip/mip_all.hpp index 7284dde9f..7df181d63 100644 --- a/src/mip/mip_all.hpp +++ b/src/mip/mip_all.hpp @@ -11,7 +11,7 @@ #include "definitions/descriptors.h" //MIP Utils -#include "microstrain/common/serialization.h" +#include "microstrain/common/buffer.hpp" //MIP Commands #include "definitions/commands_base.hpp" diff --git a/src/mip/mip_field.h b/src/mip/mip_field.h index ee0b5677c..d7cf2d618 100644 --- a/src/mip/mip_field.h +++ b/src/mip/mip_field.h @@ -118,7 +118,7 @@ bool mip_field_next_in_packet(mip_field* field, const mip_packet* packet); //////////////////////////////////////////////////////////////////////////////// /// -void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field* field); +//void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field* field); #ifdef __cplusplus } // namespace mip diff --git a/src/mip/mip_packet.h b/src/mip/mip_packet.h index 6ab413388..7ab5ce8e0 100644 --- a/src/mip/mip_packet.h +++ b/src/mip/mip_packet.h @@ -116,8 +116,8 @@ bool mip_packet_is_data(const mip_packet* packet); /// ///@{ -void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor); -void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet* packet); +//void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor); +//void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet* packet); ///@} ///@} From e2f9c59f2fd710e7d9f27b29e8b304f152f96c70 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 28 May 2024 12:15:05 -0400 Subject: [PATCH 011/147] Update C++ serialization stuff. --- src/microstrain/common/CMakeLists.txt | 1 + src/microstrain/common/buffer.hpp | 106 +++-- src/microstrain/common/serialization.c | 14 +- src/microstrain/common/serialization.h | 4 +- src/mip/definitions/commands_3dm.cpp | 470 ++++++++++----------- src/mip/definitions/commands_aiding.cpp | 42 +- src/mip/definitions/commands_base.cpp | 24 +- src/mip/definitions/commands_filter.cpp | 520 ++++++++++++------------ src/mip/definitions/commands_gnss.cpp | 30 +- src/mip/definitions/commands_system.cpp | 8 +- src/mip/mip.hpp | 4 +- 11 files changed, 617 insertions(+), 606 deletions(-) diff --git a/src/microstrain/common/CMakeLists.txt b/src/microstrain/common/CMakeLists.txt index 5a9377525..b0abf0bfb 100644 --- a/src/microstrain/common/CMakeLists.txt +++ b/src/microstrain/common/CMakeLists.txt @@ -4,6 +4,7 @@ set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max set(SOURCES + buffer.hpp descriptor_id.hpp index.hpp logging.h diff --git a/src/microstrain/common/buffer.hpp b/src/microstrain/common/buffer.hpp index d8c7ed623..b9838361a 100644 --- a/src/microstrain/common/buffer.hpp +++ b/src/microstrain/common/buffer.hpp @@ -16,7 +16,7 @@ namespace microstrain template typename std::enable_if::value && sizeof(T)==1, size_t>::type -/*size_t*/ insert_basic(uint8_t* buffer, T value) +/*size_t*/ write(uint8_t* buffer, T value) { buffer[0] = reinterpret_cast(&value)[0]; return sizeof(T); @@ -24,7 +24,7 @@ typename std::enable_if::value && sizeof(T)==1, size_t>::t template typename std::enable_if::value && sizeof(T)==2, size_t>::type -/*size_t*/ insert_basic(uint8_t* buffer, T value) +/*size_t*/ write(uint8_t* buffer, T value) { buffer[0] = reinterpret_cast(&value)[1]; buffer[1] = reinterpret_cast(&value)[0]; @@ -33,7 +33,7 @@ typename std::enable_if::value && sizeof(T)==2, size_t>::t template typename std::enable_if::value && sizeof(T)==4, size_t>::type -/*size_t*/ insert_basic(uint8_t* buffer, T value) +/*size_t*/ write(uint8_t* buffer, T value) { buffer[0] = reinterpret_cast(&value)[3]; buffer[1] = reinterpret_cast(&value)[2]; @@ -44,7 +44,7 @@ typename std::enable_if::value && sizeof(T)==4, size_t>::t template typename std::enable_if::value && sizeof(T)==8, size_t>::type -/*size_t*/ insert_basic(uint8_t* buffer, T value) +/*size_t*/ write(uint8_t* buffer, T value) { buffer[0] = reinterpret_cast(&value)[7]; buffer[1] = reinterpret_cast(&value)[6]; @@ -63,7 +63,7 @@ typename std::enable_if::value && sizeof(T)==8, size_t>::t template typename std::enable_if::value && sizeof(T)==1, size_t>::type -/*size_t*/ extract_basic(const uint8_t* buffer, T& value) +/*size_t*/ read(const uint8_t* buffer, T& value) { reinterpret_cast(&value)[0] = buffer[0]; return sizeof(T); @@ -71,7 +71,7 @@ typename std::enable_if::value && sizeof(T)==1, size_t>::t template typename std::enable_if::value && sizeof(T)==2, size_t>::type -/*size_t*/ extract_basic(const uint8_t* buffer, T& value) +/*size_t*/ read(const uint8_t* buffer, T& value) { reinterpret_cast(&value)[0] = buffer[1]; reinterpret_cast(&value)[1] = buffer[0]; @@ -80,7 +80,7 @@ typename std::enable_if::value && sizeof(T)==2, size_t>::t template typename std::enable_if::value && sizeof(T)==4, size_t>::type -/*size_t*/ extract_basic(const uint8_t* buffer, T& value) +/*size_t*/ read(const uint8_t* buffer, T& value) { reinterpret_cast(&value)[0] = buffer[3]; reinterpret_cast(&value)[1] = buffer[2]; @@ -91,7 +91,7 @@ typename std::enable_if::value && sizeof(T)==4, size_t>::t template typename std::enable_if::value && sizeof(T)==8, size_t>::type -/*size_t*/ extract_basic(const uint8_t* buffer, T& value) +/*size_t*/ read(const uint8_t* buffer, T& value) { reinterpret_cast(&value)[0] = buffer[7]; reinterpret_cast(&value)[1] = buffer[6]; @@ -122,13 +122,13 @@ class Buffer bool isOk() const { return !isOverrun(); } bool hasRemaining(size_t count) const { return m_offset+count <= m_size; } - const uint8_t* pointer() const { return m_ptr; } - uint8_t* pointer() { return m_ptr; } + const uint8_t* basePointer() const { return m_ptr; } + uint8_t* basePointer() { return m_ptr; } - const uint8_t* pointer(size_t required_size) const { return hasRemaining(required_size) ? m_ptr : nullptr; } - uint8_t* pointer(size_t required_size) { return hasRemaining(required_size) ? m_ptr : nullptr; } + const uint8_t* pointer(size_t required_size) const { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } + uint8_t* pointer(size_t required_size) { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } - uint8_t* getPtrAndAdvance(size_t size) { uint8_t* ptr = (hasRemaining(size) ? m_ptr : nullptr); m_offset += size; return ptr; } + uint8_t* getPtrAndAdvance(size_t size) { uint8_t* ptr = hasRemaining(size) ? (m_ptr+m_offset) : nullptr; m_offset += size; return ptr; } void invalidate() { m_offset = -1U; } @@ -139,7 +139,7 @@ class Buffer bool extract(Ts&... values); template - struct Count + struct Counter { T& count; size_t max_count = 0; @@ -170,7 +170,7 @@ typename std::enable_if::value, size_t>::type /*size_t*/ insert(Buffer& buffer, T value) { if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) - insert_basic(ptr, value); + write(ptr, value); return sizeof(T); } @@ -183,31 +183,32 @@ typename std::enable_if::value, size_t>::type using BaseType = typename std::underlying_type::type; if(auto ptr = buffer.getPtrAndAdvance(sizeof(BaseType))) - insert_basic(ptr, static_cast(value)); + write(ptr, static_cast(value)); return sizeof(BaseType); } -// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. -template -typename std::enable_if::value, size_t>::type -/*size_t*/ insert(Buffer& buffer, const T& value) -{ - return value.serialize(buffer); -} +//// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. +//template +//typename std::enable_if::value, size_t>::type +///*size_t*/ insert(Buffer& buffer, const T& value) +//{ +// return value.serialize(buffer); +//} -#if __cpp_fold_expressions >= 201603L +#if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template size_t insert(Buffer& buffer, Ts... values) { - if( (std::is_arithmetic::value && ...) ) + if constexpr( (std::is_arithmetic::value && ...) ) { const size_t size = ( ... + sizeof(Ts) ); if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) { size_t offset = 0; - return ( ... + (offset += insert_basic(ptr+offset, values)) ); + ( ..., (offset += write(ptr+offset, values)) ); + return offset; } return size; @@ -246,7 +247,7 @@ typename std::enable_if::value, size_t>::type /*size_t*/ extract(Buffer& buffer, T& value) { if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) - extract_basic(ptr, value); + read(ptr, value); return sizeof(T); } @@ -261,33 +262,34 @@ typename std::enable_if::value, size_t>::type if(auto ptr = buffer.getPtrAndAdvance(sizeof(BaseType))) { BaseType base; - extract_basic(ptr, base); + read(ptr, base); value = static_cast(base); } return sizeof(BaseType); } -// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. -template -typename std::enable_if::value, size_t>::type -/*size_t*/ extract(Buffer& buffer, T& value) -{ - return value.deserialize(buffer); -} +//// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. +//template +//typename std::enable_if::value, size_t>::type +///*size_t*/ extract(Buffer& buffer, T& value) +//{ +// return value.deserialize(buffer); +//} -#if __cpp_fold_expressions >= 201603L +#if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template -size_t insert(Buffer& buffer, Ts&... values) +size_t extract(Buffer& buffer, Ts&... values) { - if( (std::is_arithmetic::value && ...) ) + if constexpr( (std::is_arithmetic::value && ...) ) { const size_t size = ( ... + sizeof(Ts) ); if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) { size_t offset = 0; - return ( ... + (offset += extract_basic(ptr+offset, values)) ); + ( ..., (offset += read(ptr+offset, values)) ); + return offset; } return size; @@ -305,24 +307,40 @@ size_t extract(Buffer& buffer, T0 value0, Ts... values) +//template +//size_t extract(Buffer& buffer, Buffer::Counter counter) +//{ +// size_t size = extract(counter.count); +// +// if(counter.count > counter.max_count) +// buffer.invalidate(); +// +// return size; +//} + template -size_t extract(Buffer& buffer, Buffer::Count counter) +size_t extract_count(Buffer& buffer, T& count, size_t max_count) { - size_t size = extract(counter.count); + T tmp; + size_t size = extract(buffer, tmp); - if(counter.count > counter.max_count) + if(tmp <= max_count) + count = tmp; + else buffer.invalidate(); return size; } +template +size_t extract_count(Buffer& buffer, T* count, size_t max_count) { return extract_count(buffer, *count, max_count); } template -bool Buffer::insert(const Ts&... values) { return insert(*this, values...); } +bool Buffer::insert(const Ts&... values) { return microstrain::insert(*this, values...); } template -bool Buffer::extract(Ts&... values) { return extract(*this, values...); } +bool Buffer::extract(Ts&... values) { return microstrain::extract(*this, values...); } } // namespace microstrain diff --git a/src/microstrain/common/serialization.c b/src/microstrain/common/serialization.c index 9ab831812..dde2ed5a2 100644 --- a/src/microstrain/common/serialization.c +++ b/src/microstrain/common/serialization.c @@ -1,10 +1,6 @@ #include "serialization.h" -#ifdef __cplusplus -namespace microstrain { -#endif - //////////////////////////////////////////////////////////////////////////////// ///@brief Initialize a serialization struct for insertion into a buffer. @@ -123,7 +119,7 @@ static void pack(uint8_t* buffer, const void* value, size_t size) } #define INSERT_MACRO(name, type) \ -void insert_##name(microstrain_serializer* serializer, type value) \ +void microstrain_insert_##name(microstrain_serializer* serializer, type value) \ { \ const size_t offset = serializer->_offset + sizeof(type); \ if( offset <= serializer->_buffer_size ) \ @@ -154,7 +150,7 @@ static void unpack(const uint8_t* buffer, void* value, size_t size) #define EXTRACT_MACRO(name, type) \ -void extract_##name(microstrain_serializer* serializer, type* value) \ +void microstrain_extract_##name(microstrain_serializer* serializer, type* value) \ { \ const size_t offset = serializer->_offset + sizeof(type); \ if( offset <= serializer->_buffer_size ) \ @@ -189,7 +185,7 @@ EXTRACT_MACRO(double, double ) /// The maximum value of the counter. If the count exceeds this, it is /// set to 0 and the serializer is put into an error state. /// -void extract_count(microstrain_serializer* serializer, uint8_t* count_out, uint8_t max_count) +void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* count_out, uint8_t max_count) { *count_out = 0; // Default to zero if extraction fails. microstrain_extract_u8(serializer, count_out); @@ -205,7 +201,3 @@ void extract_count(microstrain_serializer* serializer, uint8_t* count_out, uint8 serializer->_offset = SIZE_MAX; } } - -#ifdef __cplusplus -} // namespace microstrain -#endif diff --git a/src/microstrain/common/serialization.h b/src/microstrain/common/serialization.h index adc19fcf6..7a8f8e4c7 100644 --- a/src/microstrain/common/serialization.h +++ b/src/microstrain/common/serialization.h @@ -211,7 +211,7 @@ typename std::enable_if< std::is_enum::value, void>::type template bool insert(const T& value, uint8_t* buffer, size_t bufferSize, size_t offset=0) { - Buffer serializer(buffer, bufferSize, offset); + ::microstrain::Buffer serializer(buffer, bufferSize, offset); insert(serializer, value); return !!serializer; } @@ -268,7 +268,7 @@ typename std::enable_if< std::is_enum::value, void>::type template bool extract(T& value_out, const uint8_t* buffer, size_t bufferSize, size_t offset=0, bool exact_size=false) { - Buffer serializer(buffer, bufferSize, offset); + ::microstrain::Buffer serializer(buffer, bufferSize, offset); extract(serializer, value_out); return exact_size ? serializer.isComplete() : serializer.isOk(); } diff --git a/src/mip/definitions/commands_3dm.cpp b/src/mip/definitions/commands_3dm.cpp index 8e01096ba..35aee6847 100644 --- a/src/mip/definitions/commands_3dm.cpp +++ b/src/mip/definitions/commands_3dm.cpp @@ -66,7 +66,7 @@ void extract(::microstrain::Buffer& serializer, PollImuMessage& self) { extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -75,7 +75,7 @@ void extract(::microstrain::Buffer& serializer, PollImuMessage& self) TypedResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -103,7 +103,7 @@ void extract(::microstrain::Buffer& serializer, PollGnssMessage& self) { extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -112,7 +112,7 @@ void extract(::microstrain::Buffer& serializer, PollGnssMessage& self) TypedResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -140,7 +140,7 @@ void extract(::microstrain::Buffer& serializer, PollFilterMessage& self) { extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -149,7 +149,7 @@ void extract(::microstrain::Buffer& serializer, PollFilterMessage& self) TypedResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -182,7 +182,7 @@ void extract(::microstrain::Buffer& serializer, ImuMessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -199,7 +199,7 @@ void insert(::microstrain::Buffer& serializer, const ImuMessageFormat::Response& } void extract(::microstrain::Buffer& serializer, ImuMessageFormat::Response& self) { - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -208,7 +208,7 @@ void extract(::microstrain::Buffer& serializer, ImuMessageFormat::Response& self TypedResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, numDescriptors); @@ -224,7 +224,7 @@ TypedResult writeImuMessageFormat(C::mip_interface& device, ui TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -234,9 +234,9 @@ TypedResult readImuMessageFormat(C::mip_interface& device, uin if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); - C::extract_count(&deserializer, numDescriptorsOut, numDescriptorsOutMax); + extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); for(unsigned int i=0; i < *numDescriptorsOut; i++) extract(deserializer, descriptorsOut[i]); @@ -249,7 +249,7 @@ TypedResult readImuMessageFormat(C::mip_interface& device, uin TypedResult saveImuMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -259,7 +259,7 @@ TypedResult saveImuMessageFormat(C::mip_interface& device) TypedResult loadImuMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -269,7 +269,7 @@ TypedResult loadImuMessageFormat(C::mip_interface& device) TypedResult defaultImuMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -295,7 +295,7 @@ void extract(::microstrain::Buffer& serializer, GpsMessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -312,7 +312,7 @@ void insert(::microstrain::Buffer& serializer, const GpsMessageFormat::Response& } void extract(::microstrain::Buffer& serializer, GpsMessageFormat::Response& self) { - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -321,7 +321,7 @@ void extract(::microstrain::Buffer& serializer, GpsMessageFormat::Response& self TypedResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, numDescriptors); @@ -337,7 +337,7 @@ TypedResult writeGpsMessageFormat(C::mip_interface& device, ui TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -347,9 +347,9 @@ TypedResult readGpsMessageFormat(C::mip_interface& device, uin if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); - C::extract_count(&deserializer, numDescriptorsOut, numDescriptorsOutMax); + extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); for(unsigned int i=0; i < *numDescriptorsOut; i++) extract(deserializer, descriptorsOut[i]); @@ -362,7 +362,7 @@ TypedResult readGpsMessageFormat(C::mip_interface& device, uin TypedResult saveGpsMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -372,7 +372,7 @@ TypedResult saveGpsMessageFormat(C::mip_interface& device) TypedResult loadGpsMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -382,7 +382,7 @@ TypedResult loadGpsMessageFormat(C::mip_interface& device) TypedResult defaultGpsMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -408,7 +408,7 @@ void extract(::microstrain::Buffer& serializer, FilterMessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -425,7 +425,7 @@ void insert(::microstrain::Buffer& serializer, const FilterMessageFormat::Respon } void extract(::microstrain::Buffer& serializer, FilterMessageFormat::Response& self) { - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -434,7 +434,7 @@ void extract(::microstrain::Buffer& serializer, FilterMessageFormat::Response& s TypedResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, numDescriptors); @@ -450,7 +450,7 @@ TypedResult writeFilterMessageFormat(C::mip_interface& devi TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -460,9 +460,9 @@ TypedResult readFilterMessageFormat(C::mip_interface& devic if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); - C::extract_count(&deserializer, numDescriptorsOut, numDescriptorsOutMax); + extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); for(unsigned int i=0; i < *numDescriptorsOut; i++) extract(deserializer, descriptorsOut[i]); @@ -475,7 +475,7 @@ TypedResult readFilterMessageFormat(C::mip_interface& devic TypedResult saveFilterMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -485,7 +485,7 @@ TypedResult saveFilterMessageFormat(C::mip_interface& devic TypedResult loadFilterMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -495,7 +495,7 @@ TypedResult loadFilterMessageFormat(C::mip_interface& devic TypedResult defaultFilterMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -533,7 +533,7 @@ TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* r if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(rateOut); extract(deserializer, *rateOut); @@ -574,7 +574,7 @@ TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* r if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(rateOut); extract(deserializer, *rateOut); @@ -615,7 +615,7 @@ TypedResult filterGetBaseRate(C::mip_interface& device, uint1 if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(rateOut); extract(deserializer, *rateOut); @@ -643,7 +643,7 @@ void extract(::microstrain::Buffer& serializer, PollData& self) extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -652,7 +652,7 @@ void extract(::microstrain::Buffer& serializer, PollData& self) TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, descSet); @@ -697,7 +697,7 @@ void extract(::microstrain::Buffer& serializer, GetBaseRate::Response& self) TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, descSet); @@ -708,7 +708,7 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -743,7 +743,7 @@ void extract(::microstrain::Buffer& serializer, MessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -764,7 +764,7 @@ void extract(::microstrain::Buffer& serializer, MessageFormat::Response& self) { extract(serializer, self.desc_set); - C::extract_count(&serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) extract(serializer, self.descriptors[i]); @@ -773,7 +773,7 @@ void extract(::microstrain::Buffer& serializer, MessageFormat::Response& self) TypedResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, descSet); @@ -791,7 +791,7 @@ TypedResult writeMessageFormat(C::mip_interface& device, uint8_t TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, descSet); @@ -803,11 +803,11 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, descSet); - C::extract_count(&deserializer, numDescriptorsOut, numDescriptorsOutMax); + extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); for(unsigned int i=0; i < *numDescriptorsOut; i++) extract(deserializer, descriptorsOut[i]); @@ -820,7 +820,7 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d TypedResult saveMessageFormat(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, descSet); @@ -832,7 +832,7 @@ TypedResult saveMessageFormat(C::mip_interface& device, uint8_t d TypedResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, descSet); @@ -844,7 +844,7 @@ TypedResult loadMessageFormat(C::mip_interface& device, uint8_t d TypedResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, descSet); @@ -867,7 +867,7 @@ void extract(::microstrain::Buffer& serializer, NmeaPollData& self) { extract(serializer, self.suppress_ack); - C::extract_count(&serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); + extract_count(serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); for(unsigned int i=0; i < self.count; i++) extract(serializer, self.format_entries[i]); @@ -876,7 +876,7 @@ void extract(::microstrain::Buffer& serializer, NmeaPollData& self) TypedResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -909,7 +909,7 @@ void extract(::microstrain::Buffer& serializer, NmeaMessageFormat& self) if( self.function == FunctionSelector::WRITE ) { - C::extract_count(&serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); + extract_count(serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); for(unsigned int i=0; i < self.count; i++) extract(serializer, self.format_entries[i]); @@ -926,7 +926,7 @@ void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat::Response } void extract(::microstrain::Buffer& serializer, NmeaMessageFormat::Response& self) { - C::extract_count(&serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); + extract_count(serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); for(unsigned int i=0; i < self.count; i++) extract(serializer, self.format_entries[i]); @@ -935,7 +935,7 @@ void extract(::microstrain::Buffer& serializer, NmeaMessageFormat::Response& sel TypedResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, count); @@ -951,7 +951,7 @@ TypedResult writeNmeaMessageFormat(C::mip_interface& device, TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -961,9 +961,9 @@ TypedResult readNmeaMessageFormat(C::mip_interface& device, u if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); - C::extract_count(&deserializer, countOut, countOutMax); + extract_count(deserializer, countOut, countOutMax); assert(formatEntriesOut || (countOut == 0)); for(unsigned int i=0; i < *countOut; i++) extract(deserializer, formatEntriesOut[i]); @@ -976,7 +976,7 @@ TypedResult readNmeaMessageFormat(C::mip_interface& device, u TypedResult saveNmeaMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -986,7 +986,7 @@ TypedResult saveNmeaMessageFormat(C::mip_interface& device) TypedResult loadNmeaMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -996,7 +996,7 @@ TypedResult loadNmeaMessageFormat(C::mip_interface& device) TypedResult defaultNmeaMessageFormat(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1017,7 +1017,7 @@ void extract(::microstrain::Buffer& serializer, DeviceSettings& self) TypedResult saveDeviceSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1027,7 +1027,7 @@ TypedResult saveDeviceSettings(C::mip_interface& device) TypedResult loadDeviceSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1037,7 +1037,7 @@ TypedResult loadDeviceSettings(C::mip_interface& device) TypedResult defaultDeviceSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1079,7 +1079,7 @@ void extract(::microstrain::Buffer& serializer, UartBaudrate::Response& self) TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, baud); @@ -1091,7 +1091,7 @@ TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t b TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1101,7 +1101,7 @@ TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* b if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(baudOut); extract(deserializer, *baudOut); @@ -1114,7 +1114,7 @@ TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* b TypedResult saveUartBaudrate(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1124,7 +1124,7 @@ TypedResult saveUartBaudrate(C::mip_interface& device) TypedResult loadUartBaudrate(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1134,7 +1134,7 @@ TypedResult loadUartBaudrate(C::mip_interface& device) TypedResult defaultUartBaudrate(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1159,7 +1159,7 @@ void extract(::microstrain::Buffer& serializer, FactoryStreaming& self) TypedResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, action); @@ -1212,7 +1212,7 @@ void extract(::microstrain::Buffer& serializer, DatastreamControl::Response& sel TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, descSet); @@ -1226,7 +1226,7 @@ TypedResult writeDatastreamControl(C::mip_interface& device, TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, descSet); @@ -1238,7 +1238,7 @@ TypedResult readDatastreamControl(C::mip_interface& device, u if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -1253,7 +1253,7 @@ TypedResult readDatastreamControl(C::mip_interface& device, u TypedResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, descSet); @@ -1265,7 +1265,7 @@ TypedResult saveDatastreamControl(C::mip_interface& device, u TypedResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, descSet); @@ -1277,7 +1277,7 @@ TypedResult loadDatastreamControl(C::mip_interface& device, u TypedResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, descSet); @@ -1309,7 +1309,7 @@ void extract(::microstrain::Buffer& serializer, ConstellationSettings& self) { extract(serializer, self.max_channels); - C::extract_count(&serializer, &self.config_count, sizeof(self.settings)/sizeof(self.settings[0])); + extract_count(serializer, &self.config_count, sizeof(self.settings)/sizeof(self.settings[0])); for(unsigned int i=0; i < self.config_count; i++) extract(serializer, self.settings[i]); @@ -1334,7 +1334,7 @@ void extract(::microstrain::Buffer& serializer, ConstellationSettings::Response& extract(serializer, self.max_channels_use); - C::extract_count(&serializer, &self.config_count, sizeof(self.settings)/sizeof(self.settings[0])); + extract_count(serializer, &self.config_count, sizeof(self.settings)/sizeof(self.settings[0])); for(unsigned int i=0; i < self.config_count; i++) extract(serializer, self.settings[i]); @@ -1370,7 +1370,7 @@ void extract(::microstrain::Buffer& serializer, ConstellationSettings::Settings& TypedResult writeConstellationSettings(C::mip_interface& device, uint16_t maxChannels, uint8_t configCount, const ConstellationSettings::Settings* settings) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, maxChannels); @@ -1388,7 +1388,7 @@ TypedResult writeConstellationSettings(C::mip_interface& TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1398,7 +1398,7 @@ TypedResult readConstellationSettings(C::mip_interface& d if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(maxChannelsAvailableOut); extract(deserializer, *maxChannelsAvailableOut); @@ -1406,7 +1406,7 @@ TypedResult readConstellationSettings(C::mip_interface& d assert(maxChannelsUseOut); extract(deserializer, *maxChannelsUseOut); - C::extract_count(&deserializer, configCountOut, configCountOutMax); + extract_count(deserializer, configCountOut, configCountOutMax); assert(settingsOut || (configCountOut == 0)); for(unsigned int i=0; i < *configCountOut; i++) extract(deserializer, settingsOut[i]); @@ -1419,7 +1419,7 @@ TypedResult readConstellationSettings(C::mip_interface& d TypedResult saveConstellationSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1429,7 +1429,7 @@ TypedResult saveConstellationSettings(C::mip_interface& d TypedResult loadConstellationSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1439,7 +1439,7 @@ TypedResult loadConstellationSettings(C::mip_interface& d TypedResult defaultConstellationSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1473,7 +1473,7 @@ void extract(::microstrain::Buffer& serializer, GnssSbasSettings& self) extract(serializer, self.sbas_options); - C::extract_count(&serializer, &self.num_included_prns, sizeof(self.included_prns)/sizeof(self.included_prns[0])); + extract_count(serializer, &self.num_included_prns, sizeof(self.included_prns)/sizeof(self.included_prns[0])); for(unsigned int i=0; i < self.num_included_prns; i++) extract(serializer, self.included_prns[i]); @@ -1498,7 +1498,7 @@ void extract(::microstrain::Buffer& serializer, GnssSbasSettings::Response& self extract(serializer, self.sbas_options); - C::extract_count(&serializer, &self.num_included_prns, sizeof(self.included_prns)/sizeof(self.included_prns[0])); + extract_count(serializer, &self.num_included_prns, sizeof(self.included_prns)/sizeof(self.included_prns[0])); for(unsigned int i=0; i < self.num_included_prns; i++) extract(serializer, self.included_prns[i]); @@ -1507,7 +1507,7 @@ void extract(::microstrain::Buffer& serializer, GnssSbasSettings::Response& self TypedResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enableSbas); @@ -1527,7 +1527,7 @@ TypedResult writeGnssSbasSettings(C::mip_interface& device, ui TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1537,7 +1537,7 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableSbasOut); extract(deserializer, *enableSbasOut); @@ -1545,7 +1545,7 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin assert(sbasOptionsOut); extract(deserializer, *sbasOptionsOut); - C::extract_count(&deserializer, numIncludedPrnsOut, numIncludedPrnsOutMax); + extract_count(deserializer, numIncludedPrnsOut, numIncludedPrnsOutMax); assert(includedPrnsOut || (numIncludedPrnsOut == 0)); for(unsigned int i=0; i < *numIncludedPrnsOut; i++) extract(deserializer, includedPrnsOut[i]); @@ -1558,7 +1558,7 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin TypedResult saveGnssSbasSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1568,7 +1568,7 @@ TypedResult saveGnssSbasSettings(C::mip_interface& device) TypedResult loadGnssSbasSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1578,7 +1578,7 @@ TypedResult loadGnssSbasSettings(C::mip_interface& device) TypedResult defaultGnssSbasSettings(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1628,7 +1628,7 @@ void extract(::microstrain::Buffer& serializer, GnssAssistedFix::Response& self) TypedResult writeGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption option, uint8_t flags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, option); @@ -1642,7 +1642,7 @@ TypedResult writeGnssAssistedFix(C::mip_interface& device, Gnss TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1652,7 +1652,7 @@ TypedResult readGnssAssistedFix(C::mip_interface& device, GnssA if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(optionOut); extract(deserializer, *optionOut); @@ -1668,7 +1668,7 @@ TypedResult readGnssAssistedFix(C::mip_interface& device, GnssA TypedResult saveGnssAssistedFix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1678,7 +1678,7 @@ TypedResult saveGnssAssistedFix(C::mip_interface& device) TypedResult loadGnssAssistedFix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1688,7 +1688,7 @@ TypedResult loadGnssAssistedFix(C::mip_interface& device) TypedResult defaultGnssAssistedFix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1746,7 +1746,7 @@ void extract(::microstrain::Buffer& serializer, GnssTimeAssistance::Response& se TypedResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, tow); @@ -1762,7 +1762,7 @@ TypedResult writeGnssTimeAssistance(C::mip_interface& device TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1772,7 +1772,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(towOut); extract(deserializer, *towOut); @@ -1855,7 +1855,7 @@ void extract(::microstrain::Buffer& serializer, ImuLowpassFilter::Response& self TypedResult writeImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, targetDescriptor); @@ -1875,7 +1875,7 @@ TypedResult writeImuLowpassFilter(C::mip_interface& device, ui TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, targetDescriptor); @@ -1887,7 +1887,7 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, targetDescriptor); @@ -1911,7 +1911,7 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin TypedResult saveImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, targetDescriptor); @@ -1923,7 +1923,7 @@ TypedResult saveImuLowpassFilter(C::mip_interface& device, uin TypedResult loadImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, targetDescriptor); @@ -1935,7 +1935,7 @@ TypedResult loadImuLowpassFilter(C::mip_interface& device, uin TypedResult defaultImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, targetDescriptor); @@ -1979,7 +1979,7 @@ void extract(::microstrain::Buffer& serializer, PpsSource::Response& self) TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -1991,7 +1991,7 @@ TypedResult writePpsSource(C::mip_interface& device, PpsSource::Sourc TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2001,7 +2001,7 @@ TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -2014,7 +2014,7 @@ TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source TypedResult savePpsSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2024,7 +2024,7 @@ TypedResult savePpsSource(C::mip_interface& device) TypedResult loadPpsSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2034,7 +2034,7 @@ TypedResult loadPpsSource(C::mip_interface& device) TypedResult defaultPpsSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2100,7 +2100,7 @@ void extract(::microstrain::Buffer& serializer, GpioConfig::Response& self) TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, pin); @@ -2118,7 +2118,7 @@ TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, G TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, pin); @@ -2130,7 +2130,7 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, pin); @@ -2151,7 +2151,7 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, pin); @@ -2163,7 +2163,7 @@ TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, pin); @@ -2175,7 +2175,7 @@ TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, pin); @@ -2233,7 +2233,7 @@ void extract(::microstrain::Buffer& serializer, GpioState::Response& self) TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, pin); @@ -2247,7 +2247,7 @@ TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, boo TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, pin); @@ -2259,7 +2259,7 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, pin); @@ -2322,7 +2322,7 @@ void extract(::microstrain::Buffer& serializer, Odometer::Response& self) TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); @@ -2338,7 +2338,7 @@ TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mod TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2348,7 +2348,7 @@ TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* mod if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -2367,7 +2367,7 @@ TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* mod TypedResult saveOdometer(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2377,7 +2377,7 @@ TypedResult saveOdometer(C::mip_interface& device) TypedResult loadOdometer(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2387,7 +2387,7 @@ TypedResult loadOdometer(C::mip_interface& device) TypedResult defaultOdometer(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2423,7 +2423,7 @@ void extract(::microstrain::Buffer& serializer, GetEventSupport::Response& self) extract(serializer, self.max_instances); - C::extract_count(&serializer, &self.num_entries, sizeof(self.entries)/sizeof(self.entries[0])); + extract_count(serializer, &self.num_entries, sizeof(self.entries)/sizeof(self.entries[0])); for(unsigned int i=0; i < self.num_entries; i++) extract(serializer, self.entries[i]); @@ -2447,7 +2447,7 @@ void extract(::microstrain::Buffer& serializer, GetEventSupport::Info& self) TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, query); @@ -2458,14 +2458,14 @@ TypedResult getEventSupport(C::mip_interface& device, GetEventS if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, query); assert(maxInstancesOut); extract(deserializer, *maxInstancesOut); - C::extract_count(&deserializer, numEntriesOut, numEntriesOutMax); + extract_count(deserializer, numEntriesOut, numEntriesOutMax); assert(entriesOut || (numEntriesOut == 0)); for(unsigned int i=0; i < *numEntriesOut; i++) extract(deserializer, entriesOut[i]); @@ -2518,7 +2518,7 @@ void extract(::microstrain::Buffer& serializer, EventControl::Response& self) TypedResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, instance); @@ -2532,7 +2532,7 @@ TypedResult writeEventControl(C::mip_interface& device, uint8_t in TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, instance); @@ -2544,7 +2544,7 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, instance); @@ -2559,7 +2559,7 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins TypedResult saveEventControl(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, instance); @@ -2571,7 +2571,7 @@ TypedResult saveEventControl(C::mip_interface& device, uint8_t ins TypedResult loadEventControl(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, instance); @@ -2583,7 +2583,7 @@ TypedResult loadEventControl(C::mip_interface& device, uint8_t ins TypedResult defaultEventControl(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, instance); @@ -2602,7 +2602,7 @@ void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus& self } void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus& self) { - C::extract_count(&serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); + extract_count(serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); for(unsigned int i=0; i < self.requested_count; i++) extract(serializer, self.requested_instances[i]); @@ -2618,7 +2618,7 @@ void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Resp } void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Response& self) { - C::extract_count(&serializer, &self.count, sizeof(self.triggers)/sizeof(self.triggers[0])); + extract_count(serializer, &self.count, sizeof(self.triggers)/sizeof(self.triggers[0])); for(unsigned int i=0; i < self.count; i++) extract(serializer, self.triggers[i]); @@ -2642,7 +2642,7 @@ void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Entry& se TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, requestedCount); @@ -2657,9 +2657,9 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); - C::extract_count(&deserializer, countOut, countOutMax); + extract_count(deserializer, countOut, countOutMax); assert(triggersOut || (countOut == 0)); for(unsigned int i=0; i < *countOut; i++) extract(deserializer, triggersOut[i]); @@ -2679,7 +2679,7 @@ void insert(::microstrain::Buffer& serializer, const GetEventActionStatus& self) } void extract(::microstrain::Buffer& serializer, GetEventActionStatus& self) { - C::extract_count(&serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); + extract_count(serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); for(unsigned int i=0; i < self.requested_count; i++) extract(serializer, self.requested_instances[i]); @@ -2695,7 +2695,7 @@ void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Respo } void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Response& self) { - C::extract_count(&serializer, &self.count, sizeof(self.actions)/sizeof(self.actions[0])); + extract_count(serializer, &self.count, sizeof(self.actions)/sizeof(self.actions[0])); for(unsigned int i=0; i < self.count; i++) extract(serializer, self.actions[i]); @@ -2719,7 +2719,7 @@ void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Entry& sel TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, requestedCount); @@ -2734,9 +2734,9 @@ TypedResult getEventActionStatus(C::mip_interface& device, if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); - C::extract_count(&deserializer, countOut, countOutMax); + extract_count(deserializer, countOut, countOutMax); assert(actionsOut || (countOut == 0)); for(unsigned int i=0; i < *countOut; i++) extract(deserializer, actionsOut[i]); @@ -2944,7 +2944,7 @@ void extract(::microstrain::Buffer& serializer, EventTrigger::CombinationParams& TypedResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, instance); @@ -2973,7 +2973,7 @@ TypedResult writeEventTrigger(C::mip_interface& device, uint8_t in TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, instance); @@ -2985,7 +2985,7 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, instance); @@ -3015,7 +3015,7 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins TypedResult saveEventTrigger(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, instance); @@ -3027,7 +3027,7 @@ TypedResult saveEventTrigger(C::mip_interface& device, uint8_t ins TypedResult loadEventTrigger(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, instance); @@ -3039,7 +3039,7 @@ TypedResult loadEventTrigger(C::mip_interface& device, uint8_t ins TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, instance); @@ -3169,7 +3169,7 @@ void extract(::microstrain::Buffer& serializer, EventAction::MessageParams& self extract(serializer, self.decimation); - C::extract_count(&serializer, &self.num_fields, sizeof(self.descriptors)/sizeof(self.descriptors[0])); + extract_count(serializer, &self.num_fields, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_fields; i++) extract(serializer, self.descriptors[i]); @@ -3178,7 +3178,7 @@ void extract(::microstrain::Buffer& serializer, EventAction::MessageParams& self TypedResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, instance); @@ -3204,7 +3204,7 @@ TypedResult writeEventAction(C::mip_interface& device, uint8_t inst TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, instance); @@ -3216,7 +3216,7 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, instance); @@ -3244,7 +3244,7 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta TypedResult saveEventAction(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, instance); @@ -3256,7 +3256,7 @@ TypedResult saveEventAction(C::mip_interface& device, uint8_t insta TypedResult loadEventAction(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, instance); @@ -3268,7 +3268,7 @@ TypedResult loadEventAction(C::mip_interface& device, uint8_t insta TypedResult defaultEventAction(C::mip_interface& device, uint8_t instance) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, instance); @@ -3316,7 +3316,7 @@ void extract(::microstrain::Buffer& serializer, AccelBias::Response& self) TypedResult writeAccelBias(C::mip_interface& device, const float* bias) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(bias || (3 == 0)); @@ -3330,7 +3330,7 @@ TypedResult writeAccelBias(C::mip_interface& device, const float* bia TypedResult readAccelBias(C::mip_interface& device, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3340,7 +3340,7 @@ TypedResult readAccelBias(C::mip_interface& device, float* biasOut) if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(biasOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3354,7 +3354,7 @@ TypedResult readAccelBias(C::mip_interface& device, float* biasOut) TypedResult saveAccelBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3364,7 +3364,7 @@ TypedResult saveAccelBias(C::mip_interface& device) TypedResult loadAccelBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3374,7 +3374,7 @@ TypedResult loadAccelBias(C::mip_interface& device) TypedResult defaultAccelBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3420,7 +3420,7 @@ void extract(::microstrain::Buffer& serializer, GyroBias::Response& self) TypedResult writeGyroBias(C::mip_interface& device, const float* bias) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(bias || (3 == 0)); @@ -3434,7 +3434,7 @@ TypedResult writeGyroBias(C::mip_interface& device, const float* bias) TypedResult readGyroBias(C::mip_interface& device, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3444,7 +3444,7 @@ TypedResult readGyroBias(C::mip_interface& device, float* biasOut) if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(biasOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3458,7 +3458,7 @@ TypedResult readGyroBias(C::mip_interface& device, float* biasOut) TypedResult saveGyroBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3468,7 +3468,7 @@ TypedResult saveGyroBias(C::mip_interface& device) TypedResult loadGyroBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3478,7 +3478,7 @@ TypedResult loadGyroBias(C::mip_interface& device) TypedResult defaultGyroBias(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3512,7 +3512,7 @@ void extract(::microstrain::Buffer& serializer, CaptureGyroBias::Response& self) TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, averagingTimeMs); @@ -3523,7 +3523,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(biasOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3573,7 +3573,7 @@ void extract(::microstrain::Buffer& serializer, MagHardIronOffset::Response& sel TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (3 == 0)); @@ -3587,7 +3587,7 @@ TypedResult writeMagHardIronOffset(C::mip_interface& device, TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3597,7 +3597,7 @@ TypedResult readMagHardIronOffset(C::mip_interface& device, f if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(offsetOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3611,7 +3611,7 @@ TypedResult readMagHardIronOffset(C::mip_interface& device, f TypedResult saveMagHardIronOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3621,7 +3621,7 @@ TypedResult saveMagHardIronOffset(C::mip_interface& device) TypedResult loadMagHardIronOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3631,7 +3631,7 @@ TypedResult loadMagHardIronOffset(C::mip_interface& device) TypedResult defaultMagHardIronOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3677,7 +3677,7 @@ void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix::Response& sel TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (9 == 0)); @@ -3691,7 +3691,7 @@ TypedResult writeMagSoftIronMatrix(C::mip_interface& device, TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3701,7 +3701,7 @@ TypedResult readMagSoftIronMatrix(C::mip_interface& device, f if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(offsetOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -3715,7 +3715,7 @@ TypedResult readMagSoftIronMatrix(C::mip_interface& device, f TypedResult saveMagSoftIronMatrix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3725,7 +3725,7 @@ TypedResult saveMagSoftIronMatrix(C::mip_interface& device) TypedResult loadMagSoftIronMatrix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3735,7 +3735,7 @@ TypedResult loadMagSoftIronMatrix(C::mip_interface& device) TypedResult defaultMagSoftIronMatrix(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3777,7 +3777,7 @@ void extract(::microstrain::Buffer& serializer, ConingScullingEnable::Response& TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -3789,7 +3789,7 @@ TypedResult writeConingScullingEnable(C::mip_interface& de TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3799,7 +3799,7 @@ TypedResult readConingScullingEnable(C::mip_interface& dev if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -3812,7 +3812,7 @@ TypedResult readConingScullingEnable(C::mip_interface& dev TypedResult saveConingScullingEnable(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3822,7 +3822,7 @@ TypedResult saveConingScullingEnable(C::mip_interface& dev TypedResult loadConingScullingEnable(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3832,7 +3832,7 @@ TypedResult loadConingScullingEnable(C::mip_interface& dev TypedResult defaultConingScullingEnable(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3890,7 +3890,7 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler::Re TypedResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, roll); @@ -3906,7 +3906,7 @@ TypedResult writeSensor2VehicleTransformEuler(C::m TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3916,7 +3916,7 @@ TypedResult readSensor2VehicleTransformEuler(C::mi if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(rollOut); extract(deserializer, *rollOut); @@ -3935,7 +3935,7 @@ TypedResult readSensor2VehicleTransformEuler(C::mi TypedResult saveSensor2VehicleTransformEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3945,7 +3945,7 @@ TypedResult saveSensor2VehicleTransformEuler(C::mi TypedResult loadSensor2VehicleTransformEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3955,7 +3955,7 @@ TypedResult loadSensor2VehicleTransformEuler(C::mi TypedResult defaultSensor2VehicleTransformEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -4001,7 +4001,7 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternio TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(q || (4 == 0)); @@ -4015,7 +4015,7 @@ TypedResult writeSensor2VehicleTransformQuate TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4025,7 +4025,7 @@ TypedResult readSensor2VehicleTransformQuater if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(qOut || (4 == 0)); for(unsigned int i=0; i < 4; i++) @@ -4039,7 +4039,7 @@ TypedResult readSensor2VehicleTransformQuater TypedResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4049,7 +4049,7 @@ TypedResult saveSensor2VehicleTransformQuater TypedResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4059,7 +4059,7 @@ TypedResult loadSensor2VehicleTransformQuater TypedResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -4105,7 +4105,7 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm::Resp TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(dcm || (9 == 0)); @@ -4119,7 +4119,7 @@ TypedResult writeSensor2VehicleTransformDcm(C::mip_i TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4129,7 +4129,7 @@ TypedResult readSensor2VehicleTransformDcm(C::mip_in if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(dcmOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -4143,7 +4143,7 @@ TypedResult readSensor2VehicleTransformDcm(C::mip_in TypedResult saveSensor2VehicleTransformDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4153,7 +4153,7 @@ TypedResult saveSensor2VehicleTransformDcm(C::mip_in TypedResult loadSensor2VehicleTransformDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4163,7 +4163,7 @@ TypedResult loadSensor2VehicleTransformDcm(C::mip_in TypedResult defaultSensor2VehicleTransformDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -4229,7 +4229,7 @@ void extract(::microstrain::Buffer& serializer, ComplementaryFilter::Response& s TypedResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, pitchRollEnable); @@ -4247,7 +4247,7 @@ TypedResult writeComplementaryFilter(C::mip_interface& devi TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4257,7 +4257,7 @@ TypedResult readComplementaryFilter(C::mip_interface& devic if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(pitchRollEnableOut); extract(deserializer, *pitchRollEnableOut); @@ -4279,7 +4279,7 @@ TypedResult readComplementaryFilter(C::mip_interface& devic TypedResult saveComplementaryFilter(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4289,7 +4289,7 @@ TypedResult saveComplementaryFilter(C::mip_interface& devic TypedResult loadComplementaryFilter(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4299,7 +4299,7 @@ TypedResult loadComplementaryFilter(C::mip_interface& devic TypedResult defaultComplementaryFilter(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -4349,7 +4349,7 @@ void extract(::microstrain::Buffer& serializer, SensorRange::Response& self) TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, sensor); @@ -4363,7 +4363,7 @@ TypedResult writeSensorRange(C::mip_interface& device, SensorRangeT TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, sensor); @@ -4375,7 +4375,7 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, sensor); @@ -4390,7 +4390,7 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy TypedResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, sensor); @@ -4402,7 +4402,7 @@ TypedResult saveSensorRange(C::mip_interface& device, SensorRangeTy TypedResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, sensor); @@ -4414,7 +4414,7 @@ TypedResult loadSensorRange(C::mip_interface& device, SensorRangeTy TypedResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, sensor); @@ -4448,7 +4448,7 @@ void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Response { extract(serializer, self.sensor); - C::extract_count(&serializer, &self.num_ranges, sizeof(self.ranges)/sizeof(self.ranges[0])); + extract_count(serializer, &self.num_ranges, sizeof(self.ranges)/sizeof(self.ranges[0])); for(unsigned int i=0; i < self.num_ranges; i++) extract(serializer, self.ranges[i]); @@ -4472,7 +4472,7 @@ void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Entry& s TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, sensor); @@ -4483,11 +4483,11 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, sensor); - C::extract_count(&deserializer, numRangesOut, numRangesOutMax); + extract_count(deserializer, numRangesOut, numRangesOutMax); assert(rangesOut || (numRangesOut == 0)); for(unsigned int i=0; i < *numRangesOut; i++) extract(deserializer, rangesOut[i]); @@ -4564,7 +4564,7 @@ void extract(::microstrain::Buffer& serializer, LowpassFilter::Response& self) TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool enable, bool manual, float frequency) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, descSet); @@ -4584,7 +4584,7 @@ TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, descSet); @@ -4598,7 +4598,7 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -4621,7 +4621,7 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, descSet); @@ -4635,7 +4635,7 @@ TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t d TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, descSet); @@ -4649,7 +4649,7 @@ TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t d TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, descSet); diff --git a/src/mip/definitions/commands_aiding.cpp b/src/mip/definitions/commands_aiding.cpp index 6b1505cc7..52cfeb67a 100644 --- a/src/mip/definitions/commands_aiding.cpp +++ b/src/mip/definitions/commands_aiding.cpp @@ -157,7 +157,7 @@ void extract(::microstrain::Buffer& serializer, FrameConfig::Response& self) TypedResult writeFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool trackingEnabled, const float* translation, const FrameConfig::Rotation& rotation) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, frameId); @@ -187,7 +187,7 @@ TypedResult writeFrameConfig(C::mip_interface& device, uint8_t fram TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, frameId); @@ -201,7 +201,7 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, frameId); @@ -232,7 +232,7 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frameId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, frameId); @@ -244,7 +244,7 @@ TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frame TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frameId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, frameId); @@ -256,7 +256,7 @@ TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frame TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t frameId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, frameId); @@ -300,7 +300,7 @@ void extract(::microstrain::Buffer& serializer, AidingEchoControl::Response& sel TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); @@ -312,7 +312,7 @@ TypedResult writeAidingEchoControl(C::mip_interface& device, TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -322,7 +322,7 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -335,7 +335,7 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A TypedResult saveAidingEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -345,7 +345,7 @@ TypedResult saveAidingEchoControl(C::mip_interface& device) TypedResult loadAidingEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -355,7 +355,7 @@ TypedResult loadAidingEchoControl(C::mip_interface& device) TypedResult defaultAidingEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -396,7 +396,7 @@ void extract(::microstrain::Buffer& serializer, EcefPos& self) TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -456,7 +456,7 @@ void extract(::microstrain::Buffer& serializer, LlhPos& self) TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -508,7 +508,7 @@ void extract(::microstrain::Buffer& serializer, Height& self) TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -558,7 +558,7 @@ void extract(::microstrain::Buffer& serializer, EcefVel& self) TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -612,7 +612,7 @@ void extract(::microstrain::Buffer& serializer, NedVel& self) TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -666,7 +666,7 @@ void extract(::microstrain::Buffer& serializer, VehicleFixedFrameVelocity& self) TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -716,7 +716,7 @@ void extract(::microstrain::Buffer& serializer, TrueHeading& self) TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -766,7 +766,7 @@ void extract(::microstrain::Buffer& serializer, MagneticField& self) TypedResult magneticField(C::mip_interface& device, const Time& time, uint8_t frameId, const float* magneticField, const float* uncertainty, MagneticField::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -816,7 +816,7 @@ void extract(::microstrain::Buffer& serializer, Pressure& self) TypedResult pressure(C::mip_interface& device, const Time& time, uint8_t frameId, float pressure, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); diff --git a/src/mip/definitions/commands_base.cpp b/src/mip/definitions/commands_base.cpp index 0a7748b1e..512d98b2d 100644 --- a/src/mip/definitions/commands_base.cpp +++ b/src/mip/definitions/commands_base.cpp @@ -130,7 +130,7 @@ TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInf if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(deviceInfoOut); extract(deserializer, *deviceInfoOut); @@ -173,7 +173,7 @@ TypedResult getDeviceDescriptors(C::mip_interface& device, if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) extract(deserializer, descriptorsOut[*descriptorsOutCount]); @@ -214,7 +214,7 @@ TypedResult builtInTest(C::mip_interface& device, uint32_t* resultO if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(resultOut); extract(deserializer, *resultOut); @@ -272,7 +272,7 @@ TypedResult getExtendedDescriptors(C::mip_interface& dev if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) extract(deserializer, descriptorsOut[*descriptorsOutCount]); @@ -315,7 +315,7 @@ TypedResult continuousBit(C::mip_interface& device, uint8_t* resu if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(resultOut || (16 == 0)); for(unsigned int i=0; i < 16; i++) @@ -369,7 +369,7 @@ void extract(::microstrain::Buffer& serializer, CommSpeed::Response& self) TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, port); @@ -383,7 +383,7 @@ TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, ui TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, port); @@ -395,7 +395,7 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, port); @@ -410,7 +410,7 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, port); @@ -422,7 +422,7 @@ TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, port); @@ -434,7 +434,7 @@ TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, port); @@ -471,7 +471,7 @@ void extract(::microstrain::Buffer& serializer, GpsTimeUpdate& self) TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, fieldId); diff --git a/src/mip/definitions/commands_filter.cpp b/src/mip/definitions/commands_filter.cpp index ce9640252..d60ddd37a 100644 --- a/src/mip/definitions/commands_filter.cpp +++ b/src/mip/definitions/commands_filter.cpp @@ -67,7 +67,7 @@ void extract(::microstrain::Buffer& serializer, SetInitialAttitude& self) TypedResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, roll); @@ -114,7 +114,7 @@ void extract(::microstrain::Buffer& serializer, EstimationControl::Response& sel TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -126,7 +126,7 @@ TypedResult writeEstimationControl(C::mip_interface& device, TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -136,7 +136,7 @@ TypedResult readEstimationControl(C::mip_interface& device, E if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -149,7 +149,7 @@ TypedResult readEstimationControl(C::mip_interface& device, E TypedResult saveEstimationControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -159,7 +159,7 @@ TypedResult saveEstimationControl(C::mip_interface& device) TypedResult loadEstimationControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -169,7 +169,7 @@ TypedResult loadEstimationControl(C::mip_interface& device) TypedResult defaultEstimationControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -224,7 +224,7 @@ void extract(::microstrain::Buffer& serializer, ExternalGnssUpdate& self) TypedResult externalGnssUpdate(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, double latitude, double longitude, double height, const float* velocity, const float* posUncertainty, const float* velUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, gpsTime); @@ -274,7 +274,7 @@ void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdate& self) TypedResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, heading); @@ -316,7 +316,7 @@ void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdateWithTime& s TypedResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, gpsTime); @@ -367,7 +367,7 @@ void extract(::microstrain::Buffer& serializer, TareOrientation::Response& self) TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, axes); @@ -379,7 +379,7 @@ TypedResult writeTareOrientation(C::mip_interface& device, Tare TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -389,7 +389,7 @@ TypedResult readTareOrientation(C::mip_interface& device, TareO if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(axesOut); extract(deserializer, *axesOut); @@ -402,7 +402,7 @@ TypedResult readTareOrientation(C::mip_interface& device, TareO TypedResult saveTareOrientation(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -412,7 +412,7 @@ TypedResult saveTareOrientation(C::mip_interface& device) TypedResult loadTareOrientation(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -422,7 +422,7 @@ TypedResult loadTareOrientation(C::mip_interface& device) TypedResult defaultTareOrientation(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -464,7 +464,7 @@ void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode::Response& s TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); @@ -476,7 +476,7 @@ TypedResult writeVehicleDynamicsMode(C::mip_interface& devi TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -486,7 +486,7 @@ TypedResult readVehicleDynamicsMode(C::mip_interface& devic if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -499,7 +499,7 @@ TypedResult readVehicleDynamicsMode(C::mip_interface& devic TypedResult saveVehicleDynamicsMode(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -509,7 +509,7 @@ TypedResult saveVehicleDynamicsMode(C::mip_interface& devic TypedResult loadVehicleDynamicsMode(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -519,7 +519,7 @@ TypedResult loadVehicleDynamicsMode(C::mip_interface& devic TypedResult defaultVehicleDynamicsMode(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -577,7 +577,7 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler::Re TypedResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, roll); @@ -593,7 +593,7 @@ TypedResult writeSensorToVehicleRotationEuler(C::m TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -603,7 +603,7 @@ TypedResult readSensorToVehicleRotationEuler(C::mi if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(rollOut); extract(deserializer, *rollOut); @@ -622,7 +622,7 @@ TypedResult readSensorToVehicleRotationEuler(C::mi TypedResult saveSensorToVehicleRotationEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -632,7 +632,7 @@ TypedResult saveSensorToVehicleRotationEuler(C::mi TypedResult loadSensorToVehicleRotationEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -642,7 +642,7 @@ TypedResult loadSensorToVehicleRotationEuler(C::mi TypedResult defaultSensorToVehicleRotationEuler(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -688,7 +688,7 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm::Resp TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(dcm || (9 == 0)); @@ -702,7 +702,7 @@ TypedResult writeSensorToVehicleRotationDcm(C::mip_i TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -712,7 +712,7 @@ TypedResult readSensorToVehicleRotationDcm(C::mip_in if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(dcmOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -726,7 +726,7 @@ TypedResult readSensorToVehicleRotationDcm(C::mip_in TypedResult saveSensorToVehicleRotationDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -736,7 +736,7 @@ TypedResult saveSensorToVehicleRotationDcm(C::mip_in TypedResult loadSensorToVehicleRotationDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -746,7 +746,7 @@ TypedResult loadSensorToVehicleRotationDcm(C::mip_in TypedResult defaultSensorToVehicleRotationDcm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -792,7 +792,7 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternio TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(quat || (4 == 0)); @@ -806,7 +806,7 @@ TypedResult writeSensorToVehicleRotationQuate TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -816,7 +816,7 @@ TypedResult readSensorToVehicleRotationQuater if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(quatOut || (4 == 0)); for(unsigned int i=0; i < 4; i++) @@ -830,7 +830,7 @@ TypedResult readSensorToVehicleRotationQuater TypedResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -840,7 +840,7 @@ TypedResult saveSensorToVehicleRotationQuater TypedResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -850,7 +850,7 @@ TypedResult loadSensorToVehicleRotationQuater TypedResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -896,7 +896,7 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset::Response& TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (3 == 0)); @@ -910,7 +910,7 @@ TypedResult writeSensorToVehicleOffset(C::mip_interface& TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -920,7 +920,7 @@ TypedResult readSensorToVehicleOffset(C::mip_interface& d if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(offsetOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -934,7 +934,7 @@ TypedResult readSensorToVehicleOffset(C::mip_interface& d TypedResult saveSensorToVehicleOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -944,7 +944,7 @@ TypedResult saveSensorToVehicleOffset(C::mip_interface& d TypedResult loadSensorToVehicleOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -954,7 +954,7 @@ TypedResult loadSensorToVehicleOffset(C::mip_interface& d TypedResult defaultSensorToVehicleOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1000,7 +1000,7 @@ void extract(::microstrain::Buffer& serializer, AntennaOffset::Response& self) TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (3 == 0)); @@ -1014,7 +1014,7 @@ TypedResult writeAntennaOffset(C::mip_interface& device, const fl TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1024,7 +1024,7 @@ TypedResult readAntennaOffset(C::mip_interface& device, float* of if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(offsetOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1038,7 +1038,7 @@ TypedResult readAntennaOffset(C::mip_interface& device, float* of TypedResult saveAntennaOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1048,7 +1048,7 @@ TypedResult saveAntennaOffset(C::mip_interface& device) TypedResult loadAntennaOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1058,7 +1058,7 @@ TypedResult loadAntennaOffset(C::mip_interface& device) TypedResult defaultAntennaOffset(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1100,7 +1100,7 @@ void extract(::microstrain::Buffer& serializer, GnssSource::Response& self) TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -1112,7 +1112,7 @@ TypedResult writeGnssSource(C::mip_interface& device, GnssSource::So TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1122,7 +1122,7 @@ TypedResult readGnssSource(C::mip_interface& device, GnssSource::Sou if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -1135,7 +1135,7 @@ TypedResult readGnssSource(C::mip_interface& device, GnssSource::Sou TypedResult saveGnssSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1145,7 +1145,7 @@ TypedResult saveGnssSource(C::mip_interface& device) TypedResult loadGnssSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1155,7 +1155,7 @@ TypedResult loadGnssSource(C::mip_interface& device) TypedResult defaultGnssSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1197,7 +1197,7 @@ void extract(::microstrain::Buffer& serializer, HeadingSource::Response& self) TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -1209,7 +1209,7 @@ TypedResult writeHeadingSource(C::mip_interface& device, HeadingS TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1219,7 +1219,7 @@ TypedResult readHeadingSource(C::mip_interface& device, HeadingSo if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -1232,7 +1232,7 @@ TypedResult readHeadingSource(C::mip_interface& device, HeadingSo TypedResult saveHeadingSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1242,7 +1242,7 @@ TypedResult saveHeadingSource(C::mip_interface& device) TypedResult loadHeadingSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1252,7 +1252,7 @@ TypedResult loadHeadingSource(C::mip_interface& device) TypedResult defaultHeadingSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1294,7 +1294,7 @@ void extract(::microstrain::Buffer& serializer, AutoInitControl::Response& self) TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -1306,7 +1306,7 @@ TypedResult writeAutoInitControl(C::mip_interface& device, uint TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1316,7 +1316,7 @@ TypedResult readAutoInitControl(C::mip_interface& device, uint8 if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -1329,7 +1329,7 @@ TypedResult readAutoInitControl(C::mip_interface& device, uint8 TypedResult saveAutoInitControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1339,7 +1339,7 @@ TypedResult saveAutoInitControl(C::mip_interface& device) TypedResult loadAutoInitControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1349,7 +1349,7 @@ TypedResult loadAutoInitControl(C::mip_interface& device) TypedResult defaultAutoInitControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1395,7 +1395,7 @@ void extract(::microstrain::Buffer& serializer, AccelNoise::Response& self) TypedResult writeAccelNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -1409,7 +1409,7 @@ TypedResult writeAccelNoise(C::mip_interface& device, const float* n TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1419,7 +1419,7 @@ TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1433,7 +1433,7 @@ TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut TypedResult saveAccelNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1443,7 +1443,7 @@ TypedResult saveAccelNoise(C::mip_interface& device) TypedResult loadAccelNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1453,7 +1453,7 @@ TypedResult loadAccelNoise(C::mip_interface& device) TypedResult defaultAccelNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1499,7 +1499,7 @@ void extract(::microstrain::Buffer& serializer, GyroNoise::Response& self) TypedResult writeGyroNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -1513,7 +1513,7 @@ TypedResult writeGyroNoise(C::mip_interface& device, const float* noi TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1523,7 +1523,7 @@ TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1537,7 +1537,7 @@ TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) TypedResult saveGyroNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1547,7 +1547,7 @@ TypedResult saveGyroNoise(C::mip_interface& device) TypedResult loadGyroNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1557,7 +1557,7 @@ TypedResult loadGyroNoise(C::mip_interface& device) TypedResult defaultGyroNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1615,7 +1615,7 @@ void extract(::microstrain::Buffer& serializer, AccelBiasModel::Response& self) TypedResult writeAccelBiasModel(C::mip_interface& device, const float* beta, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(beta || (3 == 0)); @@ -1633,7 +1633,7 @@ TypedResult writeAccelBiasModel(C::mip_interface& device, const TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1643,7 +1643,7 @@ TypedResult readAccelBiasModel(C::mip_interface& device, float* if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(betaOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1661,7 +1661,7 @@ TypedResult readAccelBiasModel(C::mip_interface& device, float* TypedResult saveAccelBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1671,7 +1671,7 @@ TypedResult saveAccelBiasModel(C::mip_interface& device) TypedResult loadAccelBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1681,7 +1681,7 @@ TypedResult loadAccelBiasModel(C::mip_interface& device) TypedResult defaultAccelBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1739,7 +1739,7 @@ void extract(::microstrain::Buffer& serializer, GyroBiasModel::Response& self) TypedResult writeGyroBiasModel(C::mip_interface& device, const float* beta, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(beta || (3 == 0)); @@ -1757,7 +1757,7 @@ TypedResult writeGyroBiasModel(C::mip_interface& device, const fl TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1767,7 +1767,7 @@ TypedResult readGyroBiasModel(C::mip_interface& device, float* be if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(betaOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1785,7 +1785,7 @@ TypedResult readGyroBiasModel(C::mip_interface& device, float* be TypedResult saveGyroBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1795,7 +1795,7 @@ TypedResult saveGyroBiasModel(C::mip_interface& device) TypedResult loadGyroBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1805,7 +1805,7 @@ TypedResult loadGyroBiasModel(C::mip_interface& device) TypedResult defaultGyroBiasModel(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1847,7 +1847,7 @@ void extract(::microstrain::Buffer& serializer, AltitudeAiding::Response& self) TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, selector); @@ -1859,7 +1859,7 @@ TypedResult writeAltitudeAiding(C::mip_interface& device, Altitu TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1869,7 +1869,7 @@ TypedResult readAltitudeAiding(C::mip_interface& device, Altitud if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(selectorOut); extract(deserializer, *selectorOut); @@ -1882,7 +1882,7 @@ TypedResult readAltitudeAiding(C::mip_interface& device, Altitud TypedResult saveAltitudeAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1892,7 +1892,7 @@ TypedResult saveAltitudeAiding(C::mip_interface& device) TypedResult loadAltitudeAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1902,7 +1902,7 @@ TypedResult loadAltitudeAiding(C::mip_interface& device) TypedResult defaultAltitudeAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -1944,7 +1944,7 @@ void extract(::microstrain::Buffer& serializer, PitchRollAiding::Response& self) TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -1956,7 +1956,7 @@ TypedResult writePitchRollAiding(C::mip_interface& device, Pitc TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1966,7 +1966,7 @@ TypedResult readPitchRollAiding(C::mip_interface& device, Pitch if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -1979,7 +1979,7 @@ TypedResult readPitchRollAiding(C::mip_interface& device, Pitch TypedResult savePitchRollAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1989,7 +1989,7 @@ TypedResult savePitchRollAiding(C::mip_interface& device) TypedResult loadPitchRollAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1999,7 +1999,7 @@ TypedResult loadPitchRollAiding(C::mip_interface& device) TypedResult defaultPitchRollAiding(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2049,7 +2049,7 @@ void extract(::microstrain::Buffer& serializer, AutoZupt::Response& self) TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -2063,7 +2063,7 @@ TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, fl TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2073,7 +2073,7 @@ TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -2089,7 +2089,7 @@ TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, TypedResult saveAutoZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2099,7 +2099,7 @@ TypedResult saveAutoZupt(C::mip_interface& device) TypedResult loadAutoZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2109,7 +2109,7 @@ TypedResult loadAutoZupt(C::mip_interface& device) TypedResult defaultAutoZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2159,7 +2159,7 @@ void extract(::microstrain::Buffer& serializer, AutoAngularZupt::Response& self) TypedResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -2173,7 +2173,7 @@ TypedResult writeAutoAngularZupt(C::mip_interface& device, uint TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2183,7 +2183,7 @@ TypedResult readAutoAngularZupt(C::mip_interface& device, uint8 if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -2199,7 +2199,7 @@ TypedResult readAutoAngularZupt(C::mip_interface& device, uint8 TypedResult saveAutoAngularZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2209,7 +2209,7 @@ TypedResult saveAutoAngularZupt(C::mip_interface& device) TypedResult loadAutoAngularZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2219,7 +2219,7 @@ TypedResult loadAutoAngularZupt(C::mip_interface& device) TypedResult defaultAutoAngularZupt(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2270,7 +2270,7 @@ void extract(::microstrain::Buffer& serializer, MagCaptureAutoCal& self) TypedResult writeMagCaptureAutoCal(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(serializer.isOk()); @@ -2280,7 +2280,7 @@ TypedResult writeMagCaptureAutoCal(C::mip_interface& device) TypedResult saveMagCaptureAutoCal(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2326,7 +2326,7 @@ void extract(::microstrain::Buffer& serializer, GravityNoise::Response& self) TypedResult writeGravityNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -2340,7 +2340,7 @@ TypedResult writeGravityNoise(C::mip_interface& device, const floa TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2350,7 +2350,7 @@ TypedResult readGravityNoise(C::mip_interface& device, float* nois if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2364,7 +2364,7 @@ TypedResult readGravityNoise(C::mip_interface& device, float* nois TypedResult saveGravityNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2374,7 +2374,7 @@ TypedResult saveGravityNoise(C::mip_interface& device) TypedResult loadGravityNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2384,7 +2384,7 @@ TypedResult loadGravityNoise(C::mip_interface& device) TypedResult defaultGravityNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2426,7 +2426,7 @@ void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise::Response& TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, noise); @@ -2438,7 +2438,7 @@ TypedResult writePressureAltitudeNoise(C::mip_interface& TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2448,7 +2448,7 @@ TypedResult readPressureAltitudeNoise(C::mip_interface& d if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(noiseOut); extract(deserializer, *noiseOut); @@ -2461,7 +2461,7 @@ TypedResult readPressureAltitudeNoise(C::mip_interface& d TypedResult savePressureAltitudeNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2471,7 +2471,7 @@ TypedResult savePressureAltitudeNoise(C::mip_interface& d TypedResult loadPressureAltitudeNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2481,7 +2481,7 @@ TypedResult loadPressureAltitudeNoise(C::mip_interface& d TypedResult defaultPressureAltitudeNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2527,7 +2527,7 @@ void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise::Response& s TypedResult writeHardIronOffsetNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -2541,7 +2541,7 @@ TypedResult writeHardIronOffsetNoise(C::mip_interface& devi TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2551,7 +2551,7 @@ TypedResult readHardIronOffsetNoise(C::mip_interface& devic if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2565,7 +2565,7 @@ TypedResult readHardIronOffsetNoise(C::mip_interface& devic TypedResult saveHardIronOffsetNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2575,7 +2575,7 @@ TypedResult saveHardIronOffsetNoise(C::mip_interface& devic TypedResult loadHardIronOffsetNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2585,7 +2585,7 @@ TypedResult loadHardIronOffsetNoise(C::mip_interface& devic TypedResult defaultHardIronOffsetNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2631,7 +2631,7 @@ void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise::Response& s TypedResult writeSoftIronMatrixNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (9 == 0)); @@ -2645,7 +2645,7 @@ TypedResult writeSoftIronMatrixNoise(C::mip_interface& devi TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2655,7 +2655,7 @@ TypedResult readSoftIronMatrixNoise(C::mip_interface& devic if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(noiseOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -2669,7 +2669,7 @@ TypedResult readSoftIronMatrixNoise(C::mip_interface& devic TypedResult saveSoftIronMatrixNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2679,7 +2679,7 @@ TypedResult saveSoftIronMatrixNoise(C::mip_interface& devic TypedResult loadSoftIronMatrixNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2689,7 +2689,7 @@ TypedResult loadSoftIronMatrixNoise(C::mip_interface& devic TypedResult defaultSoftIronMatrixNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2735,7 +2735,7 @@ void extract(::microstrain::Buffer& serializer, MagNoise::Response& self) TypedResult writeMagNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -2749,7 +2749,7 @@ TypedResult writeMagNoise(C::mip_interface& device, const float* noise TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2759,7 +2759,7 @@ TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2773,7 +2773,7 @@ TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) TypedResult saveMagNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2783,7 +2783,7 @@ TypedResult saveMagNoise(C::mip_interface& device) TypedResult loadMagNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2793,7 +2793,7 @@ TypedResult loadMagNoise(C::mip_interface& device) TypedResult defaultMagNoise(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2843,7 +2843,7 @@ void extract(::microstrain::Buffer& serializer, InclinationSource::Response& sel TypedResult writeInclinationSource(C::mip_interface& device, FilterMagParamSource source, float inclination) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -2857,7 +2857,7 @@ TypedResult writeInclinationSource(C::mip_interface& device, TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2867,7 +2867,7 @@ TypedResult readInclinationSource(C::mip_interface& device, F if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -2883,7 +2883,7 @@ TypedResult readInclinationSource(C::mip_interface& device, F TypedResult saveInclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2893,7 +2893,7 @@ TypedResult saveInclinationSource(C::mip_interface& device) TypedResult loadInclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2903,7 +2903,7 @@ TypedResult loadInclinationSource(C::mip_interface& device) TypedResult defaultInclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -2953,7 +2953,7 @@ void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource::Respo TypedResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource source, float declination) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -2967,7 +2967,7 @@ TypedResult writeMagneticDeclinationSource(C::mip_int TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2977,7 +2977,7 @@ TypedResult readMagneticDeclinationSource(C::mip_inte if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -2993,7 +2993,7 @@ TypedResult readMagneticDeclinationSource(C::mip_inte TypedResult saveMagneticDeclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3003,7 +3003,7 @@ TypedResult saveMagneticDeclinationSource(C::mip_inte TypedResult loadMagneticDeclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3013,7 +3013,7 @@ TypedResult loadMagneticDeclinationSource(C::mip_inte TypedResult defaultMagneticDeclinationSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3063,7 +3063,7 @@ void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource::Respons TypedResult writeMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource source, float magnitude) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -3077,7 +3077,7 @@ TypedResult writeMagFieldMagnitudeSource(C::mip_interfa TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3087,7 +3087,7 @@ TypedResult readMagFieldMagnitudeSource(C::mip_interfac if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -3103,7 +3103,7 @@ TypedResult readMagFieldMagnitudeSource(C::mip_interfac TypedResult saveMagFieldMagnitudeSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3113,7 +3113,7 @@ TypedResult saveMagFieldMagnitudeSource(C::mip_interfac TypedResult loadMagFieldMagnitudeSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3123,7 +3123,7 @@ TypedResult loadMagFieldMagnitudeSource(C::mip_interfac TypedResult defaultMagFieldMagnitudeSource(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3189,7 +3189,7 @@ void extract(::microstrain::Buffer& serializer, ReferencePosition::Response& sel TypedResult writeReferencePosition(C::mip_interface& device, bool enable, double latitude, double longitude, double altitude) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -3207,7 +3207,7 @@ TypedResult writeReferencePosition(C::mip_interface& device, TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3217,7 +3217,7 @@ TypedResult readReferencePosition(C::mip_interface& device, b if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -3239,7 +3239,7 @@ TypedResult readReferencePosition(C::mip_interface& device, b TypedResult saveReferencePosition(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3249,7 +3249,7 @@ TypedResult saveReferencePosition(C::mip_interface& device) TypedResult loadReferencePosition(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3259,7 +3259,7 @@ TypedResult loadReferencePosition(C::mip_interface& device) TypedResult defaultReferencePosition(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3349,7 +3349,7 @@ void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasu TypedResult writeAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, adaptiveMeasurement); @@ -3373,7 +3373,7 @@ TypedResult writeAccelMagnitudeErrorAdap TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3383,7 +3383,7 @@ TypedResult readAccelMagnitudeErrorAdapt if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(adaptiveMeasurementOut); extract(deserializer, *adaptiveMeasurementOut); @@ -3414,7 +3414,7 @@ TypedResult readAccelMagnitudeErrorAdapt TypedResult saveAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3424,7 +3424,7 @@ TypedResult saveAccelMagnitudeErrorAdapt TypedResult loadAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3434,7 +3434,7 @@ TypedResult loadAccelMagnitudeErrorAdapt TypedResult defaultAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3524,7 +3524,7 @@ void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasure TypedResult writeMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, adaptiveMeasurement); @@ -3548,7 +3548,7 @@ TypedResult writeMagMagnitudeErrorAdaptive TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3558,7 +3558,7 @@ TypedResult readMagMagnitudeErrorAdaptiveM if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(adaptiveMeasurementOut); extract(deserializer, *adaptiveMeasurementOut); @@ -3589,7 +3589,7 @@ TypedResult readMagMagnitudeErrorAdaptiveM TypedResult saveMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3599,7 +3599,7 @@ TypedResult saveMagMagnitudeErrorAdaptiveM TypedResult loadMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3609,7 +3609,7 @@ TypedResult loadMagMagnitudeErrorAdaptiveM TypedResult defaultMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3683,7 +3683,7 @@ void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurem TypedResult writeMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool enable, float frequency, float highLimit, float highLimitUncertainty, float minimumUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -3703,7 +3703,7 @@ TypedResult writeMagDipAngleErrorAdaptiveMe TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3713,7 +3713,7 @@ TypedResult readMagDipAngleErrorAdaptiveMea if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -3738,7 +3738,7 @@ TypedResult readMagDipAngleErrorAdaptiveMea TypedResult saveMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3748,7 +3748,7 @@ TypedResult saveMagDipAngleErrorAdaptiveMea TypedResult loadMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3758,7 +3758,7 @@ TypedResult loadMagDipAngleErrorAdaptiveMea TypedResult defaultMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -3808,7 +3808,7 @@ void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable::Respons TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, aidingSource); @@ -3822,7 +3822,7 @@ TypedResult writeAidingMeasurementEnable(C::mip_interfa TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, aidingSource); @@ -3834,7 +3834,7 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, aidingSource); @@ -3849,7 +3849,7 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac TypedResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, aidingSource); @@ -3861,7 +3861,7 @@ TypedResult saveAidingMeasurementEnable(C::mip_interfac TypedResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, aidingSource); @@ -3873,7 +3873,7 @@ TypedResult loadAidingMeasurementEnable(C::mip_interfac TypedResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, aidingSource); @@ -3948,7 +3948,7 @@ void extract(::microstrain::Buffer& serializer, KinematicConstraint::Response& s TypedResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, accelerationConstraintSelection); @@ -3964,7 +3964,7 @@ TypedResult writeKinematicConstraint(C::mip_interface& devi TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3974,7 +3974,7 @@ TypedResult readKinematicConstraint(C::mip_interface& devic if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(accelerationConstraintSelectionOut); extract(deserializer, *accelerationConstraintSelectionOut); @@ -3993,7 +3993,7 @@ TypedResult readKinematicConstraint(C::mip_interface& devic TypedResult saveKinematicConstraint(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4003,7 +4003,7 @@ TypedResult saveKinematicConstraint(C::mip_interface& devic TypedResult loadKinematicConstraint(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4013,7 +4013,7 @@ TypedResult loadKinematicConstraint(C::mip_interface& devic TypedResult defaultKinematicConstraint(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -4127,7 +4127,7 @@ void extract(::microstrain::Buffer& serializer, InitializationConfiguration::Res TypedResult writeInitializationConfiguration(C::mip_interface& device, uint8_t waitForRunCommand, InitializationConfiguration::InitialConditionSource initialCondSrc, InitializationConfiguration::AlignmentSelector autoHeadingAlignmentSelector, float initialHeading, float initialPitch, float initialRoll, const float* initialPosition, const float* initialVelocity, FilterReferenceFrame referenceFrameSelector) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, waitForRunCommand); @@ -4159,7 +4159,7 @@ TypedResult writeInitializationConfiguration(C::mip TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4169,7 +4169,7 @@ TypedResult readInitializationConfiguration(C::mip_ if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(waitForRunCommandOut); extract(deserializer, *waitForRunCommandOut); @@ -4208,7 +4208,7 @@ TypedResult readInitializationConfiguration(C::mip_ TypedResult saveInitializationConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4218,7 +4218,7 @@ TypedResult saveInitializationConfiguration(C::mip_ TypedResult loadInitializationConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4228,7 +4228,7 @@ TypedResult loadInitializationConfiguration(C::mip_ TypedResult defaultInitializationConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -4278,7 +4278,7 @@ void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions::Response& TypedResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, level); @@ -4292,7 +4292,7 @@ TypedResult writeAdaptiveFilterOptions(C::mip_interface& TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4302,7 +4302,7 @@ TypedResult readAdaptiveFilterOptions(C::mip_interface& d if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(levelOut); extract(deserializer, *levelOut); @@ -4318,7 +4318,7 @@ TypedResult readAdaptiveFilterOptions(C::mip_interface& d TypedResult saveAdaptiveFilterOptions(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4328,7 +4328,7 @@ TypedResult saveAdaptiveFilterOptions(C::mip_interface& d TypedResult loadAdaptiveFilterOptions(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4338,7 +4338,7 @@ TypedResult loadAdaptiveFilterOptions(C::mip_interface& d TypedResult defaultAdaptiveFilterOptions(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -4392,7 +4392,7 @@ void extract(::microstrain::Buffer& serializer, MultiAntennaOffset::Response& se TypedResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, receiverId); @@ -4408,7 +4408,7 @@ TypedResult writeMultiAntennaOffset(C::mip_interface& device TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, receiverId); @@ -4420,7 +4420,7 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, receiverId); @@ -4436,7 +4436,7 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, TypedResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, receiverId); @@ -4448,7 +4448,7 @@ TypedResult saveMultiAntennaOffset(C::mip_interface& device, TypedResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, receiverId); @@ -4460,7 +4460,7 @@ TypedResult loadMultiAntennaOffset(C::mip_interface& device, TypedResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, receiverId); @@ -4524,7 +4524,7 @@ void extract(::microstrain::Buffer& serializer, RelPosConfiguration::Response& s TypedResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -4542,7 +4542,7 @@ TypedResult writeRelPosConfiguration(C::mip_interface& devi TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4552,7 +4552,7 @@ TypedResult readRelPosConfiguration(C::mip_interface& devic if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -4572,7 +4572,7 @@ TypedResult readRelPosConfiguration(C::mip_interface& devic TypedResult saveRelPosConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4582,7 +4582,7 @@ TypedResult saveRelPosConfiguration(C::mip_interface& devic TypedResult loadRelPosConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4592,7 +4592,7 @@ TypedResult loadRelPosConfiguration(C::mip_interface& devic TypedResult defaultRelPosConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -4646,7 +4646,7 @@ void extract(::microstrain::Buffer& serializer, RefPointLeverArm::Response& self TypedResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, refPointSel); @@ -4662,7 +4662,7 @@ TypedResult writeRefPointLeverArm(C::mip_interface& device, Re TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4672,7 +4672,7 @@ TypedResult readRefPointLeverArm(C::mip_interface& device, Ref if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(refPointSelOut); extract(deserializer, *refPointSelOut); @@ -4689,7 +4689,7 @@ TypedResult readRefPointLeverArm(C::mip_interface& device, Ref TypedResult saveRefPointLeverArm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4699,7 +4699,7 @@ TypedResult saveRefPointLeverArm(C::mip_interface& device) TypedResult loadRefPointLeverArm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4709,7 +4709,7 @@ TypedResult loadRefPointLeverArm(C::mip_interface& device) TypedResult defaultRefPointLeverArm(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -4742,7 +4742,7 @@ void extract(::microstrain::Buffer& serializer, SpeedMeasurement& self) TypedResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, source); @@ -4803,7 +4803,7 @@ void extract(::microstrain::Buffer& serializer, SpeedLeverArm::Response& self) TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -4819,7 +4819,7 @@ TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, source); @@ -4831,7 +4831,7 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); extract(deserializer, source); @@ -4847,7 +4847,7 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, source); @@ -4859,7 +4859,7 @@ TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t s TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, source); @@ -4871,7 +4871,7 @@ TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t s TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, source); @@ -4915,7 +4915,7 @@ void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl: TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -4927,7 +4927,7 @@ TypedResult writeWheeledVehicleConstraintContro TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4937,7 +4937,7 @@ TypedResult readWheeledVehicleConstraintControl if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -4950,7 +4950,7 @@ TypedResult readWheeledVehicleConstraintControl TypedResult saveWheeledVehicleConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4960,7 +4960,7 @@ TypedResult saveWheeledVehicleConstraintControl TypedResult loadWheeledVehicleConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4970,7 +4970,7 @@ TypedResult loadWheeledVehicleConstraintControl TypedResult defaultWheeledVehicleConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -5012,7 +5012,7 @@ void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl::R TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -5024,7 +5024,7 @@ TypedResult writeVerticalGyroConstraintControl(C: TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -5034,7 +5034,7 @@ TypedResult readVerticalGyroConstraintControl(C:: if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -5047,7 +5047,7 @@ TypedResult readVerticalGyroConstraintControl(C:: TypedResult saveVerticalGyroConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -5057,7 +5057,7 @@ TypedResult saveVerticalGyroConstraintControl(C:: TypedResult loadVerticalGyroConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -5067,7 +5067,7 @@ TypedResult loadVerticalGyroConstraintControl(C:: TypedResult defaultVerticalGyroConstraintControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -5117,7 +5117,7 @@ void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl::Response& TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -5131,7 +5131,7 @@ TypedResult writeGnssAntennaCalControl(C::mip_interface& TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -5141,7 +5141,7 @@ TypedResult readGnssAntennaCalControl(C::mip_interface& d if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -5157,7 +5157,7 @@ TypedResult readGnssAntennaCalControl(C::mip_interface& d TypedResult saveGnssAntennaCalControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -5167,7 +5167,7 @@ TypedResult saveGnssAntennaCalControl(C::mip_interface& d TypedResult loadGnssAntennaCalControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -5177,7 +5177,7 @@ TypedResult loadGnssAntennaCalControl(C::mip_interface& d TypedResult defaultGnssAntennaCalControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -5198,7 +5198,7 @@ void extract(::microstrain::Buffer& serializer, SetInitialHeading& self) TypedResult setInitialHeading(C::mip_interface& device, float heading) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, heading); diff --git a/src/mip/definitions/commands_gnss.cpp b/src/mip/definitions/commands_gnss.cpp index e9aab9854..05fa22987 100644 --- a/src/mip/definitions/commands_gnss.cpp +++ b/src/mip/definitions/commands_gnss.cpp @@ -50,7 +50,7 @@ void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Response& sel } void extract(::microstrain::Buffer& serializer, ReceiverInfo::Response& self) { - C::extract_count(&serializer, &self.num_receivers, sizeof(self.receiver_info)/sizeof(self.receiver_info[0])); + extract_count(serializer, &self.num_receivers, sizeof(self.receiver_info)/sizeof(self.receiver_info[0])); for(unsigned int i=0; i < self.num_receivers; i++) extract(serializer, self.receiver_info[i]); @@ -86,9 +86,9 @@ TypedResult receiverInfo(C::mip_interface& device, uint8_t* numRec if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); - C::extract_count(&deserializer, numReceiversOut, numReceiversOutMax); + extract_count(deserializer, numReceiversOut, numReceiversOutMax); assert(receiverInfoOut || (numReceiversOut == 0)); for(unsigned int i=0; i < *numReceiversOut; i++) extract(deserializer, receiverInfoOut[i]); @@ -169,7 +169,7 @@ void extract(::microstrain::Buffer& serializer, SignalConfiguration::Response& s TypedResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, gpsEnable); @@ -191,7 +191,7 @@ TypedResult writeSignalConfiguration(C::mip_interface& devi TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -201,7 +201,7 @@ TypedResult readSignalConfiguration(C::mip_interface& devic if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(gpsEnableOut); extract(deserializer, *gpsEnableOut); @@ -227,7 +227,7 @@ TypedResult readSignalConfiguration(C::mip_interface& devic TypedResult saveSignalConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -237,7 +237,7 @@ TypedResult saveSignalConfiguration(C::mip_interface& devic TypedResult loadSignalConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -247,7 +247,7 @@ TypedResult loadSignalConfiguration(C::mip_interface& devic TypedResult defaultSignalConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); @@ -301,7 +301,7 @@ void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration::Response TypedResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -317,7 +317,7 @@ TypedResult writeRtkDongleConfiguration(C::mip_interface TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -327,7 +327,7 @@ TypedResult readRtkDongleConfiguration(C::mip_interface& if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + ::microstrain::Buffer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -344,7 +344,7 @@ TypedResult readRtkDongleConfiguration(C::mip_interface& TypedResult saveRtkDongleConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -354,7 +354,7 @@ TypedResult saveRtkDongleConfiguration(C::mip_interface& TypedResult loadRtkDongleConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -364,7 +364,7 @@ TypedResult loadRtkDongleConfiguration(C::mip_interface& TypedResult defaultRtkDongleConfiguration(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); diff --git a/src/mip/definitions/commands_system.cpp b/src/mip/definitions/commands_system.cpp index ab25b0c2d..f1445e807 100644 --- a/src/mip/definitions/commands_system.cpp +++ b/src/mip/definitions/commands_system.cpp @@ -64,7 +64,7 @@ void extract(::microstrain::Buffer& serializer, CommMode::Response& self) TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); @@ -76,7 +76,7 @@ TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -86,7 +86,7 @@ TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) if( result == MIP_ACK_OK ) { - Buffer deserializer(buffer, responseLength); + microstrain::Buffer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -99,7 +99,7 @@ TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) TypedResult defaultCommMode(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Buffer serializer(buffer, sizeof(buffer)); + microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); diff --git a/src/mip/mip.hpp b/src/mip/mip.hpp index 55c326ba9..27821f21a 100644 --- a/src/mip/mip.hpp +++ b/src/mip/mip.hpp @@ -191,9 +191,9 @@ class PacketRef : public C::mip_packet bool ok = isOk(); if(ok) - C::mip_packet_realloc_last_field(&m_packet, pointer(), length()); + C::mip_packet_realloc_last_field(&m_packet, basePointer(), length()); else - C::mip_packet_cancel_last_field(&m_packet, pointer()); + C::mip_packet_cancel_last_field(&m_packet, basePointer()); return ok; } From 062cc5213510b7c768f0b5dbcf721b876ed2d04c Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 28 May 2024 13:02:34 -0400 Subject: [PATCH 012/147] Fix compilation error. --- src/mip/mip.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mip/mip.hpp b/src/mip/mip.hpp index 27821f21a..8f5c4398f 100644 --- a/src/mip/mip.hpp +++ b/src/mip/mip.hpp @@ -183,7 +183,7 @@ class PacketRef : public C::mip_packet { public: AllocatedField(mip::PacketRef& packet, uint8_t* buffer, size_t space) : Buffer(buffer, space), m_packet(packet) {} - AllocatedField(const AllocatedField&) = delete; + //AllocatedField(const AllocatedField&) = delete; AllocatedField& operator=(const AllocatedField&) = delete; bool commit() From 82fd30a88015b8b250a5ee774b031ff77193bbae Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 28 May 2024 13:32:50 -0400 Subject: [PATCH 013/147] Move connection.hpp to common. --- src/microstrain/common/CMakeLists.txt | 1 + src/microstrain/{connections => common}/connection.hpp | 0 src/microstrain/connections/recording/CMakeLists.txt | 2 +- src/microstrain/connections/recording/recording_connection.hpp | 2 +- src/microstrain/connections/serial/CMakeLists.txt | 2 +- src/microstrain/connections/serial/serial_connection.hpp | 2 +- src/microstrain/connections/tcp/CMakeLists.txt | 2 +- src/microstrain/connections/tcp/tcp_connection.hpp | 2 +- src/mip/mip_device.cpp | 2 +- 9 files changed, 8 insertions(+), 7 deletions(-) rename src/microstrain/{connections => common}/connection.hpp (100%) diff --git a/src/microstrain/common/CMakeLists.txt b/src/microstrain/common/CMakeLists.txt index b0abf0bfb..e582a5082 100644 --- a/src/microstrain/common/CMakeLists.txt +++ b/src/microstrain/common/CMakeLists.txt @@ -5,6 +5,7 @@ set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max set(SOURCES buffer.hpp + connection.hpp descriptor_id.hpp index.hpp logging.h diff --git a/src/microstrain/connections/connection.hpp b/src/microstrain/common/connection.hpp similarity index 100% rename from src/microstrain/connections/connection.hpp rename to src/microstrain/common/connection.hpp diff --git a/src/microstrain/connections/recording/CMakeLists.txt b/src/microstrain/connections/recording/CMakeLists.txt index 4ca575742..b1a72eaa2 100644 --- a/src/microstrain/connections/recording/CMakeLists.txt +++ b/src/microstrain/connections/recording/CMakeLists.txt @@ -3,7 +3,7 @@ set(SOURCES recording_connection.cpp recording_connection.hpp - ../connection.hpp + ../../common/connection.hpp ) add_library(microstrain_recording_connection ${SOURCES}) diff --git a/src/microstrain/connections/recording/recording_connection.hpp b/src/microstrain/connections/recording/recording_connection.hpp index 94b50f0f2..c320bb433 100644 --- a/src/microstrain/connections/recording/recording_connection.hpp +++ b/src/microstrain/connections/recording/recording_connection.hpp @@ -1,6 +1,6 @@ #pragma once -#include +#include #include #include diff --git a/src/microstrain/connections/serial/CMakeLists.txt b/src/microstrain/connections/serial/CMakeLists.txt index 18a8e6c78..acc3ce820 100644 --- a/src/microstrain/connections/serial/CMakeLists.txt +++ b/src/microstrain/connections/serial/CMakeLists.txt @@ -5,7 +5,7 @@ set(SOURCES serial_connection.hpp serial_port.h serial_port.c - ../connection.hpp + ../../common/connection.hpp ) add_library(microstrain_serial ${SOURCES}) diff --git a/src/microstrain/connections/serial/serial_connection.hpp b/src/microstrain/connections/serial/serial_connection.hpp index 6ec3840ec..544c34d4e 100644 --- a/src/microstrain/connections/serial/serial_connection.hpp +++ b/src/microstrain/connections/serial/serial_connection.hpp @@ -1,7 +1,7 @@ #pragma once #include "mip/mip_device.hpp" -#include "../connection.hpp" +#include #include "serial_port.h" #include diff --git a/src/microstrain/connections/tcp/CMakeLists.txt b/src/microstrain/connections/tcp/CMakeLists.txt index 4f90572ee..7da5a076f 100644 --- a/src/microstrain/connections/tcp/CMakeLists.txt +++ b/src/microstrain/connections/tcp/CMakeLists.txt @@ -5,7 +5,7 @@ set(SOURCES tcp_connection.hpp tcp_socket.h tcp_socket.c - ../connection.hpp + ../../common/connection.hpp ) add_library(microstrain_socket ${SOURCES}) diff --git a/src/microstrain/connections/tcp/tcp_connection.hpp b/src/microstrain/connections/tcp/tcp_connection.hpp index 4f39e20e0..76c8fbb7b 100644 --- a/src/microstrain/connections/tcp/tcp_connection.hpp +++ b/src/microstrain/connections/tcp/tcp_connection.hpp @@ -1,6 +1,6 @@ #pragma once -#include +#include #include "tcp_socket.h" diff --git a/src/mip/mip_device.cpp b/src/mip/mip_device.cpp index 7e83d6a86..ecc6ef7dd 100644 --- a/src/mip/mip_device.cpp +++ b/src/mip/mip_device.cpp @@ -1,7 +1,7 @@ #include "mip_device.hpp" -#include "../microstrain/connections/connection.hpp" +#include namespace mip { From 39d690ce08b097436293cf4cde3bd111ec165576 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 28 May 2024 15:57:24 -0400 Subject: [PATCH 014/147] Move C++ code to .hpp/.cpp files. --- examples/example_utils.hpp | 2 +- examples/watch_imu.c | 2 +- src/microstrain/common/descriptor_id.hpp | 2 +- .../connections/serial/serial_connection.hpp | 2 +- src/microstrain/extras/composite_result.hpp | 4 +- src/mip/CMakeLists.txt | 30 +- src/mip/definitions/commands_3dm.cpp | 483 +++++++------- src/mip/definitions/commands_3dm.h | 2 +- src/mip/definitions/commands_3dm.hpp | 9 +- src/mip/definitions/commands_aiding.cpp | 46 +- src/mip/definitions/commands_aiding.h | 2 +- src/mip/definitions/commands_aiding.hpp | 4 +- src/mip/definitions/commands_base.cpp | 46 +- src/mip/definitions/commands_base.h | 2 +- src/mip/definitions/commands_base.hpp | 4 +- src/mip/definitions/commands_filter.cpp | 604 +++++++++--------- src/mip/definitions/commands_filter.h | 2 +- src/mip/definitions/commands_filter.hpp | 4 +- src/mip/definitions/commands_gnss.cpp | 34 +- src/mip/definitions/commands_gnss.h | 2 +- src/mip/definitions/commands_gnss.hpp | 4 +- src/mip/definitions/commands_rtk.cpp | 66 +- src/mip/definitions/commands_rtk.h | 2 +- src/mip/definitions/commands_rtk.hpp | 4 +- src/mip/definitions/commands_system.cpp | 10 +- src/mip/definitions/commands_system.h | 2 +- src/mip/definitions/commands_system.hpp | 4 +- src/mip/definitions/common.c | 4 +- src/mip/definitions/common.h | 305 +-------- src/mip/definitions/common.hpp | 124 ++++ src/mip/definitions/data_filter.h | 2 +- src/mip/definitions/data_filter.hpp | 4 +- src/mip/definitions/data_gnss.h | 2 +- src/mip/definitions/data_gnss.hpp | 4 +- src/mip/definitions/data_sensor.h | 2 +- src/mip/definitions/data_sensor.hpp | 4 +- src/mip/definitions/data_shared.h | 2 +- src/mip/definitions/data_shared.hpp | 4 +- src/mip/definitions/data_system.h | 2 +- src/mip/definitions/data_system.hpp | 4 +- src/mip/mip.hpp | 514 +-------------- src/mip/mip_all.h | 2 +- src/mip/mip_all.hpp | 22 +- src/mip/mip_cmdqueue.hpp | 113 ++++ .../descriptors.c => mip_descriptors.c} | 2 +- src/mip/mip_descriptors.h | 65 ++ .../descriptors.h => mip_descriptors.hpp} | 64 +- src/mip/mip_dispatch.h | 42 +- src/mip/mip_field.c | 2 +- src/mip/mip_field.hpp | 103 +++ src/mip/mip_interface.c | 2 +- src/mip/{mip_device.cpp => mip_interface.cpp} | 2 +- src/mip/{mip_device.hpp => mip_interface.hpp} | 114 +--- src/mip/mip_packet.c | 2 +- src/mip/mip_packet.hpp | 329 ++++++++++ src/mip/mip_parser.hpp | 122 ++++ src/mip/mip_result.h | 86 +-- src/mip/mip_result.hpp | 76 +++ 58 files changed, 1710 insertions(+), 1793 deletions(-) create mode 100644 src/mip/definitions/common.hpp create mode 100644 src/mip/mip_cmdqueue.hpp rename src/mip/{definitions/descriptors.c => mip_descriptors.c} (99%) create mode 100644 src/mip/mip_descriptors.h rename src/mip/{definitions/descriptors.h => mip_descriptors.hpp} (68%) create mode 100644 src/mip/mip_field.hpp rename src/mip/{mip_device.cpp => mip_interface.cpp} (98%) rename src/mip/{mip_device.hpp => mip_interface.hpp} (85%) create mode 100644 src/mip/mip_packet.hpp create mode 100644 src/mip/mip_parser.hpp create mode 100644 src/mip/mip_result.hpp diff --git a/examples/example_utils.hpp b/examples/example_utils.hpp index b20daf939..2b5e2d866 100644 --- a/examples/example_utils.hpp +++ b/examples/example_utils.hpp @@ -12,7 +12,7 @@ #endif -#include +#include #include #include diff --git a/examples/watch_imu.c b/examples/watch_imu.c index a802bd5af..baac4a14e 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -7,7 +7,7 @@ #include "microstrain/common/logging.h" #include "microstrain/common/serialization.h" -#include +#include "mip/mip_descriptors.h" #include #include #include diff --git a/src/microstrain/common/descriptor_id.hpp b/src/microstrain/common/descriptor_id.hpp index b43a0ed6a..1fd1cac49 100644 --- a/src/microstrain/common/descriptor_id.hpp +++ b/src/microstrain/common/descriptor_id.hpp @@ -1,6 +1,6 @@ #pragma once -#include "mip/definitions/descriptors.h" +#include "mip/mip_descriptors.h" #include diff --git a/src/microstrain/connections/serial/serial_connection.hpp b/src/microstrain/connections/serial/serial_connection.hpp index 544c34d4e..5408486dc 100644 --- a/src/microstrain/connections/serial/serial_connection.hpp +++ b/src/microstrain/connections/serial/serial_connection.hpp @@ -1,6 +1,6 @@ #pragma once -#include "mip/mip_device.hpp" +#include "mip/mip_interface.hpp" #include #include "serial_port.h" diff --git a/src/microstrain/extras/composite_result.hpp b/src/microstrain/extras/composite_result.hpp index 569825cf0..056761c64 100644 --- a/src/microstrain/extras/composite_result.hpp +++ b/src/microstrain/extras/composite_result.hpp @@ -2,9 +2,9 @@ #include "microstrain/common/descriptor_id.hpp" -#include "mip/mip_device.hpp" +#include "mip/mip_interface.hpp" #include "mip/mip_result.h" -#include "mip/definitions/descriptors.h" +#include "mip/mip_descriptors.h" #include diff --git a/src/mip/CMakeLists.txt b/src/mip/CMakeLists.txt index 36da16faa..498549bfd 100644 --- a/src/mip/CMakeLists.txt +++ b/src/mip/CMakeLists.txt @@ -20,14 +20,18 @@ set(UTILS_SOURCES # MIP Control # -set(MIP_SOURCES +set(MIP_SOURCES_C "${VERSION_OUT_FILE}" "${MIP_DIR}/mip_cmdqueue.c" "${MIP_DIR}/mip_cmdqueue.h" + "${MIP_DIR}/mip_descriptors.c" + "${MIP_DIR}/mip_descriptors.h" "${MIP_DIR}/mip_dispatch.c" "${MIP_DIR}/mip_dispatch.h" "${MIP_DIR}/mip_field.c" "${MIP_DIR}/mip_field.h" + "${MIP_DIR}/mip_interface.c" + "${MIP_DIR}/mip_interface.h" "${MIP_DIR}/mip_offsets.h" "${MIP_DIR}/mip_packet.c" "${MIP_DIR}/mip_packet.h" @@ -38,18 +42,20 @@ set(MIP_SOURCES "${MIP_DIR}/mip_types.h" "${MIP_DIR}/definitions/common.c" "${MIP_DIR}/definitions/common.h" - "${MIP_DIR}/definitions/descriptors.c" - "${MIP_DIR}/definitions/descriptors.h" - "${MIP_DIR}/mip.hpp" "${MIP_DIR}/mip_all.h" - "${MIP_DIR}/mip_all.hpp" ) -set(MIPDEV_SOURCES - "${MIP_DIR}/mip_interface.c" - "${MIP_DIR}/mip_interface.h" - "${MIP_DIR}/mip_device.cpp" - "${MIP_DIR}/mip_device.hpp" +set(MIP_SOURCES_CPP + "mip.hpp" + "mip_all.hpp" + "mip_cmdqueue.hpp" + "mip_descriptors.hpp" + "mip_field.hpp" + "mip_packet.hpp" + "mip_parser.hpp" + "mip_result.hpp" + "mip_interface.cpp" + "mip_interface.hpp" ) set(MIPDEF_SOURCES @@ -86,8 +92,8 @@ string(REGEX REPLACE "\.c(;|$)" ".cpp\\1" MIPDEF_CPP_SOURCES "${MIPDEF_HPP_SOURC set(ALL_MIP_SOURCES ${MIPDEF_SOURCES} ${MIPDEF_CPP_SOURCES} - ${MIPDEV_SOURCES} - ${MIP_SOURCES} + ${MIP_SOURCES_C} + ${MIP_SOURCES_CPP} ${UTILS_SOURCES} ${MIP_CPP_HEADERS} ${MIP_INTERFACE_SOURCES} diff --git a/src/mip/definitions/commands_3dm.cpp b/src/mip/definitions/commands_3dm.cpp index 35aee6847..2a705af6e 100644 --- a/src/mip/definitions/commands_3dm.cpp +++ b/src/mip/definitions/commands_3dm.cpp @@ -8,8 +8,6 @@ namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -18,7 +16,6 @@ namespace commands_3dm { using ::microstrain::insert; using ::microstrain::extract; -using namespace ::mip::C; //////////////////////////////////////////////////////////////////////////////// // Shared Type Definitions @@ -74,7 +71,7 @@ void extract(::microstrain::Buffer& serializer, PollImuMessage& self) TypedResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -111,7 +108,7 @@ void extract(::microstrain::Buffer& serializer, PollGnssMessage& self) TypedResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -148,7 +145,7 @@ void extract(::microstrain::Buffer& serializer, PollFilterMessage& self) TypedResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -207,7 +204,7 @@ void extract(::microstrain::Buffer& serializer, ImuMessageFormat::Response& self TypedResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -223,7 +220,7 @@ TypedResult writeImuMessageFormat(C::mip_interface& device, ui } TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -232,7 +229,7 @@ TypedResult readImuMessageFormat(C::mip_interface& device, uin uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_IMU_MESSAGE_FORMAT, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -242,13 +239,13 @@ TypedResult readImuMessageFormat(C::mip_interface& device, uin extract(deserializer, descriptorsOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveImuMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -258,7 +255,7 @@ TypedResult saveImuMessageFormat(C::mip_interface& device) } TypedResult loadImuMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -268,7 +265,7 @@ TypedResult loadImuMessageFormat(C::mip_interface& device) } TypedResult defaultImuMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -320,7 +317,7 @@ void extract(::microstrain::Buffer& serializer, GpsMessageFormat::Response& self TypedResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -336,7 +333,7 @@ TypedResult writeGpsMessageFormat(C::mip_interface& device, ui } TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -345,7 +342,7 @@ TypedResult readGpsMessageFormat(C::mip_interface& device, uin uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_GNSS_MESSAGE_FORMAT, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -355,13 +352,13 @@ TypedResult readGpsMessageFormat(C::mip_interface& device, uin extract(deserializer, descriptorsOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGpsMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -371,7 +368,7 @@ TypedResult saveGpsMessageFormat(C::mip_interface& device) } TypedResult loadGpsMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -381,7 +378,7 @@ TypedResult loadGpsMessageFormat(C::mip_interface& device) } TypedResult defaultGpsMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -433,7 +430,7 @@ void extract(::microstrain::Buffer& serializer, FilterMessageFormat::Response& s TypedResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -449,7 +446,7 @@ TypedResult writeFilterMessageFormat(C::mip_interface& devi } TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -458,7 +455,7 @@ TypedResult readFilterMessageFormat(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_FILTER_MESSAGE_FORMAT, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -468,13 +465,13 @@ TypedResult readFilterMessageFormat(C::mip_interface& devic extract(deserializer, descriptorsOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveFilterMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -484,7 +481,7 @@ TypedResult saveFilterMessageFormat(C::mip_interface& devic } TypedResult loadFilterMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -494,7 +491,7 @@ TypedResult loadFilterMessageFormat(C::mip_interface& devic } TypedResult defaultFilterMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -526,12 +523,12 @@ void extract(::microstrain::Buffer& serializer, ImuGetBaseRate::Response& self) TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_IMU_BASE_RATE, NULL, 0, REPLY_IMU_BASE_RATE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -539,7 +536,7 @@ TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* r extract(deserializer, *rateOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -567,12 +564,12 @@ void extract(::microstrain::Buffer& serializer, GpsGetBaseRate::Response& self) TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_GNSS_BASE_RATE, NULL, 0, REPLY_GNSS_BASE_RATE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -580,7 +577,7 @@ TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* r extract(deserializer, *rateOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -608,12 +605,12 @@ void extract(::microstrain::Buffer& serializer, FilterGetBaseRate::Response& sel TypedResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_FILTER_BASE_RATE, NULL, 0, REPLY_FILTER_BASE_RATE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -621,7 +618,7 @@ TypedResult filterGetBaseRate(C::mip_interface& device, uint1 extract(deserializer, *rateOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -651,7 +648,7 @@ void extract(::microstrain::Buffer& serializer, PollData& self) TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, descSet); @@ -696,7 +693,7 @@ void extract(::microstrain::Buffer& serializer, GetBaseRate::Response& self) TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, descSet); @@ -706,7 +703,7 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_BASE_RATE, buffer, (uint8_t)serializer.length(), REPLY_BASE_RATE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -716,7 +713,7 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, extract(deserializer, *rateOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -772,7 +769,7 @@ void extract(::microstrain::Buffer& serializer, MessageFormat::Response& self) TypedResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -790,7 +787,7 @@ TypedResult writeMessageFormat(C::mip_interface& device, uint8_t } TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -801,7 +798,7 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_MESSAGE_FORMAT, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -813,13 +810,13 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d extract(deserializer, descriptorsOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveMessageFormat(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -831,7 +828,7 @@ TypedResult saveMessageFormat(C::mip_interface& device, uint8_t d } TypedResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -843,7 +840,7 @@ TypedResult loadMessageFormat(C::mip_interface& device, uint8_t d } TypedResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -875,7 +872,7 @@ void extract(::microstrain::Buffer& serializer, NmeaPollData& self) TypedResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -934,7 +931,7 @@ void extract(::microstrain::Buffer& serializer, NmeaMessageFormat::Response& sel TypedResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -950,7 +947,7 @@ TypedResult writeNmeaMessageFormat(C::mip_interface& device, } TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -959,7 +956,7 @@ TypedResult readNmeaMessageFormat(C::mip_interface& device, u uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_NMEA_MESSAGE_FORMAT, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -969,13 +966,13 @@ TypedResult readNmeaMessageFormat(C::mip_interface& device, u extract(deserializer, formatEntriesOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveNmeaMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -985,7 +982,7 @@ TypedResult saveNmeaMessageFormat(C::mip_interface& device) } TypedResult loadNmeaMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -995,7 +992,7 @@ TypedResult loadNmeaMessageFormat(C::mip_interface& device) } TypedResult defaultNmeaMessageFormat(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1016,7 +1013,7 @@ void extract(::microstrain::Buffer& serializer, DeviceSettings& self) TypedResult saveDeviceSettings(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1026,7 +1023,7 @@ TypedResult saveDeviceSettings(C::mip_interface& device) } TypedResult loadDeviceSettings(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1036,7 +1033,7 @@ TypedResult loadDeviceSettings(C::mip_interface& device) } TypedResult defaultDeviceSettings(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1078,7 +1075,7 @@ void extract(::microstrain::Buffer& serializer, UartBaudrate::Response& self) TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1090,7 +1087,7 @@ TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t b } TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1099,7 +1096,7 @@ TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* b uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length(), REPLY_UART_BAUDRATE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1107,13 +1104,13 @@ TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* b extract(deserializer, *baudOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveUartBaudrate(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1123,7 +1120,7 @@ TypedResult saveUartBaudrate(C::mip_interface& device) } TypedResult loadUartBaudrate(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1133,7 +1130,7 @@ TypedResult loadUartBaudrate(C::mip_interface& device) } TypedResult defaultUartBaudrate(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1158,7 +1155,7 @@ void extract(::microstrain::Buffer& serializer, FactoryStreaming& self) TypedResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, action); @@ -1211,7 +1208,7 @@ void extract(::microstrain::Buffer& serializer, DatastreamControl::Response& sel TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1225,7 +1222,7 @@ TypedResult writeDatastreamControl(C::mip_interface& device, } TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1236,7 +1233,7 @@ TypedResult readDatastreamControl(C::mip_interface& device, u uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length(), REPLY_DATASTREAM_ENABLE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1246,13 +1243,13 @@ TypedResult readDatastreamControl(C::mip_interface& device, u extract(deserializer, *enabledOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1264,7 +1261,7 @@ TypedResult saveDatastreamControl(C::mip_interface& device, u } TypedResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1276,7 +1273,7 @@ TypedResult loadDatastreamControl(C::mip_interface& device, u } TypedResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1369,7 +1366,7 @@ void extract(::microstrain::Buffer& serializer, ConstellationSettings::Settings& TypedResult writeConstellationSettings(C::mip_interface& device, uint16_t maxChannels, uint8_t configCount, const ConstellationSettings::Settings* settings) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1387,7 +1384,7 @@ TypedResult writeConstellationSettings(C::mip_interface& } TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1396,7 +1393,7 @@ TypedResult readConstellationSettings(C::mip_interface& d uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1412,13 +1409,13 @@ TypedResult readConstellationSettings(C::mip_interface& d extract(deserializer, settingsOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveConstellationSettings(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1428,7 +1425,7 @@ TypedResult saveConstellationSettings(C::mip_interface& d } TypedResult loadConstellationSettings(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1438,7 +1435,7 @@ TypedResult loadConstellationSettings(C::mip_interface& d } TypedResult defaultConstellationSettings(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1506,7 +1503,7 @@ void extract(::microstrain::Buffer& serializer, GnssSbasSettings::Response& self TypedResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1526,7 +1523,7 @@ TypedResult writeGnssSbasSettings(C::mip_interface& device, ui } TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1535,7 +1532,7 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_SBAS_SETTINGS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1551,13 +1548,13 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin extract(deserializer, includedPrnsOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGnssSbasSettings(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1567,7 +1564,7 @@ TypedResult saveGnssSbasSettings(C::mip_interface& device) } TypedResult loadGnssSbasSettings(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1577,7 +1574,7 @@ TypedResult loadGnssSbasSettings(C::mip_interface& device) } TypedResult defaultGnssSbasSettings(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1627,7 +1624,7 @@ void extract(::microstrain::Buffer& serializer, GnssAssistedFix::Response& self) TypedResult writeGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption option, uint8_t flags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1641,7 +1638,7 @@ TypedResult writeGnssAssistedFix(C::mip_interface& device, Gnss } TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1650,7 +1647,7 @@ TypedResult readGnssAssistedFix(C::mip_interface& device, GnssA uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1661,13 +1658,13 @@ TypedResult readGnssAssistedFix(C::mip_interface& device, GnssA extract(deserializer, *flagsOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGnssAssistedFix(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1677,7 +1674,7 @@ TypedResult saveGnssAssistedFix(C::mip_interface& device) } TypedResult loadGnssAssistedFix(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1687,7 +1684,7 @@ TypedResult loadGnssAssistedFix(C::mip_interface& device) } TypedResult defaultGnssAssistedFix(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1745,7 +1742,7 @@ void extract(::microstrain::Buffer& serializer, GnssTimeAssistance::Response& se TypedResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1761,7 +1758,7 @@ TypedResult writeGnssTimeAssistance(C::mip_interface& device } TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1770,7 +1767,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)serializer.length(), REPLY_GNSS_TIME_ASSISTANCE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1784,7 +1781,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, extract(deserializer, *accuracyOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -1854,7 +1851,7 @@ void extract(::microstrain::Buffer& serializer, ImuLowpassFilter::Response& self TypedResult writeImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1874,7 +1871,7 @@ TypedResult writeImuLowpassFilter(C::mip_interface& device, ui } TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1885,7 +1882,7 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length(), REPLY_ADVANCED_DATA_FILTER, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1904,13 +1901,13 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin extract(deserializer, *reservedOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1922,7 +1919,7 @@ TypedResult saveImuLowpassFilter(C::mip_interface& device, uin } TypedResult loadImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1934,7 +1931,7 @@ TypedResult loadImuLowpassFilter(C::mip_interface& device, uin } TypedResult defaultImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1978,7 +1975,7 @@ void extract(::microstrain::Buffer& serializer, PpsSource::Response& self) TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1990,7 +1987,7 @@ TypedResult writePpsSource(C::mip_interface& device, PpsSource::Sourc } TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1999,7 +1996,7 @@ TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_PPS_SOURCE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2007,13 +2004,13 @@ TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source extract(deserializer, *sourceOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult savePpsSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2023,7 +2020,7 @@ TypedResult savePpsSource(C::mip_interface& device) } TypedResult loadPpsSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2033,7 +2030,7 @@ TypedResult loadPpsSource(C::mip_interface& device) } TypedResult defaultPpsSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2099,7 +2096,7 @@ void extract(::microstrain::Buffer& serializer, GpioConfig::Response& self) TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2117,7 +2114,7 @@ TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, G } TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2128,7 +2125,7 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_GPIO_CONFIG, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2144,13 +2141,13 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp extract(deserializer, *pinModeOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2162,7 +2159,7 @@ TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) } TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2174,7 +2171,7 @@ TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) } TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2232,7 +2229,7 @@ void extract(::microstrain::Buffer& serializer, GpioState::Response& self) TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2246,7 +2243,7 @@ TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, boo } TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2257,7 +2254,7 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)serializer.length(), REPLY_GPIO_STATE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2267,7 +2264,7 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool extract(deserializer, *stateOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -2321,7 +2318,7 @@ void extract(::microstrain::Buffer& serializer, Odometer::Response& self) TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2337,7 +2334,7 @@ TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mod } TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2346,7 +2343,7 @@ TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* mod uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_ODOMETER_CONFIG, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2360,13 +2357,13 @@ TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* mod extract(deserializer, *uncertaintyOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveOdometer(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2376,7 +2373,7 @@ TypedResult saveOdometer(C::mip_interface& device) } TypedResult loadOdometer(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2386,7 +2383,7 @@ TypedResult loadOdometer(C::mip_interface& device) } TypedResult defaultOdometer(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2446,7 +2443,7 @@ void extract(::microstrain::Buffer& serializer, GetEventSupport::Info& self) TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, query); @@ -2456,7 +2453,7 @@ TypedResult getEventSupport(C::mip_interface& device, GetEventS uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_SUPPORT, buffer, (uint8_t)serializer.length(), REPLY_EVENT_SUPPORT, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2471,7 +2468,7 @@ TypedResult getEventSupport(C::mip_interface& device, GetEventS extract(deserializer, entriesOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -2517,7 +2514,7 @@ void extract(::microstrain::Buffer& serializer, EventControl::Response& self) TypedResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2531,7 +2528,7 @@ TypedResult writeEventControl(C::mip_interface& device, uint8_t in } TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2542,7 +2539,7 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_EVENT_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2552,13 +2549,13 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins extract(deserializer, *modeOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveEventControl(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2570,7 +2567,7 @@ TypedResult saveEventControl(C::mip_interface& device, uint8_t ins } TypedResult loadEventControl(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2582,7 +2579,7 @@ TypedResult loadEventControl(C::mip_interface& device, uint8_t ins } TypedResult defaultEventControl(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2641,7 +2638,7 @@ void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Entry& se TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, requestedCount); @@ -2655,7 +2652,7 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_STATUS, buffer, (uint8_t)serializer.length(), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2665,7 +2662,7 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic extract(deserializer, triggersOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -2718,7 +2715,7 @@ void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Entry& sel TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, requestedCount); @@ -2732,7 +2729,7 @@ TypedResult getEventActionStatus(C::mip_interface& device, uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_STATUS, buffer, (uint8_t)serializer.length(), REPLY_EVENT_ACTION_STATUS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2742,7 +2739,7 @@ TypedResult getEventActionStatus(C::mip_interface& device, extract(deserializer, actionsOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -2943,7 +2940,7 @@ void extract(::microstrain::Buffer& serializer, EventTrigger::CombinationParams& TypedResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2972,7 +2969,7 @@ TypedResult writeEventTrigger(C::mip_interface& device, uint8_t in } TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2983,7 +2980,7 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_EVENT_TRIGGER_CONFIG, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3008,13 +3005,13 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins } if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveEventTrigger(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3026,7 +3023,7 @@ TypedResult saveEventTrigger(C::mip_interface& device, uint8_t ins } TypedResult loadEventTrigger(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3038,7 +3035,7 @@ TypedResult loadEventTrigger(C::mip_interface& device, uint8_t ins } TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3177,7 +3174,7 @@ void extract(::microstrain::Buffer& serializer, EventAction::MessageParams& self TypedResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3203,7 +3200,7 @@ TypedResult writeEventAction(C::mip_interface& device, uint8_t inst } TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3214,7 +3211,7 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_EVENT_ACTION_CONFIG, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3237,13 +3234,13 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta } if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveEventAction(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3255,7 +3252,7 @@ TypedResult saveEventAction(C::mip_interface& device, uint8_t insta } TypedResult loadEventAction(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3267,7 +3264,7 @@ TypedResult loadEventAction(C::mip_interface& device, uint8_t insta } TypedResult defaultEventAction(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3315,7 +3312,7 @@ void extract(::microstrain::Buffer& serializer, AccelBias::Response& self) TypedResult writeAccelBias(C::mip_interface& device, const float* bias) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3329,7 +3326,7 @@ TypedResult writeAccelBias(C::mip_interface& device, const float* bia } TypedResult readAccelBias(C::mip_interface& device, float* biasOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3338,7 +3335,7 @@ TypedResult readAccelBias(C::mip_interface& device, float* biasOut) uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_BIAS_VECTOR, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3347,13 +3344,13 @@ TypedResult readAccelBias(C::mip_interface& device, float* biasOut) extract(deserializer, biasOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAccelBias(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3363,7 +3360,7 @@ TypedResult saveAccelBias(C::mip_interface& device) } TypedResult loadAccelBias(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3373,7 +3370,7 @@ TypedResult loadAccelBias(C::mip_interface& device) } TypedResult defaultAccelBias(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3419,7 +3416,7 @@ void extract(::microstrain::Buffer& serializer, GyroBias::Response& self) TypedResult writeGyroBias(C::mip_interface& device, const float* bias) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3433,7 +3430,7 @@ TypedResult writeGyroBias(C::mip_interface& device, const float* bias) } TypedResult readGyroBias(C::mip_interface& device, float* biasOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3442,7 +3439,7 @@ TypedResult readGyroBias(C::mip_interface& device, float* biasOut) uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3451,13 +3448,13 @@ TypedResult readGyroBias(C::mip_interface& device, float* biasOut) extract(deserializer, biasOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGyroBias(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3467,7 +3464,7 @@ TypedResult saveGyroBias(C::mip_interface& device) } TypedResult loadGyroBias(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3477,7 +3474,7 @@ TypedResult loadGyroBias(C::mip_interface& device) } TypedResult defaultGyroBias(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3511,7 +3508,7 @@ void extract(::microstrain::Buffer& serializer, CaptureGyroBias::Response& self) TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, averagingTimeMs); @@ -3521,7 +3518,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CAPTURE_GYRO_BIAS, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3530,7 +3527,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t extract(deserializer, biasOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -3572,7 +3569,7 @@ void extract(::microstrain::Buffer& serializer, MagHardIronOffset::Response& sel TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3586,7 +3583,7 @@ TypedResult writeMagHardIronOffset(C::mip_interface& device, } TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3595,7 +3592,7 @@ TypedResult readMagHardIronOffset(C::mip_interface& device, f uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3604,13 +3601,13 @@ TypedResult readMagHardIronOffset(C::mip_interface& device, f extract(deserializer, offsetOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveMagHardIronOffset(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3620,7 +3617,7 @@ TypedResult saveMagHardIronOffset(C::mip_interface& device) } TypedResult loadMagHardIronOffset(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3630,7 +3627,7 @@ TypedResult loadMagHardIronOffset(C::mip_interface& device) } TypedResult defaultMagHardIronOffset(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3676,7 +3673,7 @@ void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix::Response& sel TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3690,7 +3687,7 @@ TypedResult writeMagSoftIronMatrix(C::mip_interface& device, } TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3699,7 +3696,7 @@ TypedResult readMagSoftIronMatrix(C::mip_interface& device, f uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length(), REPLY_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3708,13 +3705,13 @@ TypedResult readMagSoftIronMatrix(C::mip_interface& device, f extract(deserializer, offsetOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveMagSoftIronMatrix(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3724,7 +3721,7 @@ TypedResult saveMagSoftIronMatrix(C::mip_interface& device) } TypedResult loadMagSoftIronMatrix(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3734,7 +3731,7 @@ TypedResult loadMagSoftIronMatrix(C::mip_interface& device) } TypedResult defaultMagSoftIronMatrix(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3776,7 +3773,7 @@ void extract(::microstrain::Buffer& serializer, ConingScullingEnable::Response& TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3788,7 +3785,7 @@ TypedResult writeConingScullingEnable(C::mip_interface& de } TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3797,7 +3794,7 @@ TypedResult readConingScullingEnable(C::mip_interface& dev uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length(), REPLY_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3805,13 +3802,13 @@ TypedResult readConingScullingEnable(C::mip_interface& dev extract(deserializer, *enableOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveConingScullingEnable(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3821,7 +3818,7 @@ TypedResult saveConingScullingEnable(C::mip_interface& dev } TypedResult loadConingScullingEnable(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3831,7 +3828,7 @@ TypedResult loadConingScullingEnable(C::mip_interface& dev } TypedResult defaultConingScullingEnable(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3889,7 +3886,7 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler::Re TypedResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3905,7 +3902,7 @@ TypedResult writeSensor2VehicleTransformEuler(C::m } TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3914,7 +3911,7 @@ TypedResult readSensor2VehicleTransformEuler(C::mi uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3928,13 +3925,13 @@ TypedResult readSensor2VehicleTransformEuler(C::mi extract(deserializer, *yawOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSensor2VehicleTransformEuler(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3944,7 +3941,7 @@ TypedResult saveSensor2VehicleTransformEuler(C::mi } TypedResult loadSensor2VehicleTransformEuler(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3954,7 +3951,7 @@ TypedResult loadSensor2VehicleTransformEuler(C::mi } TypedResult defaultSensor2VehicleTransformEuler(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4000,7 +3997,7 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternio TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4014,7 +4011,7 @@ TypedResult writeSensor2VehicleTransformQuate } TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4023,7 +4020,7 @@ TypedResult readSensor2VehicleTransformQuater uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4032,13 +4029,13 @@ TypedResult readSensor2VehicleTransformQuater extract(deserializer, qOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4048,7 +4045,7 @@ TypedResult saveSensor2VehicleTransformQuater } TypedResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4058,7 +4055,7 @@ TypedResult loadSensor2VehicleTransformQuater } TypedResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4104,7 +4101,7 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm::Resp TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4118,7 +4115,7 @@ TypedResult writeSensor2VehicleTransformDcm(C::mip_i } TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4127,7 +4124,7 @@ TypedResult readSensor2VehicleTransformDcm(C::mip_in uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4136,13 +4133,13 @@ TypedResult readSensor2VehicleTransformDcm(C::mip_in extract(deserializer, dcmOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSensor2VehicleTransformDcm(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4152,7 +4149,7 @@ TypedResult saveSensor2VehicleTransformDcm(C::mip_in } TypedResult loadSensor2VehicleTransformDcm(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4162,7 +4159,7 @@ TypedResult loadSensor2VehicleTransformDcm(C::mip_in } TypedResult defaultSensor2VehicleTransformDcm(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4228,7 +4225,7 @@ void extract(::microstrain::Buffer& serializer, ComplementaryFilter::Response& s TypedResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4246,7 +4243,7 @@ TypedResult writeComplementaryFilter(C::mip_interface& devi } TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4255,7 +4252,7 @@ TypedResult readComplementaryFilter(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length(), REPLY_LEGACY_COMP_FILTER, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4272,13 +4269,13 @@ TypedResult readComplementaryFilter(C::mip_interface& devic extract(deserializer, *headingTimeConstantOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveComplementaryFilter(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4288,7 +4285,7 @@ TypedResult saveComplementaryFilter(C::mip_interface& devic } TypedResult loadComplementaryFilter(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4298,7 +4295,7 @@ TypedResult loadComplementaryFilter(C::mip_interface& devic } TypedResult defaultComplementaryFilter(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4348,7 +4345,7 @@ void extract(::microstrain::Buffer& serializer, SensorRange::Response& self) TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4362,7 +4359,7 @@ TypedResult writeSensorRange(C::mip_interface& device, SensorRangeT } TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4373,7 +4370,7 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length(), REPLY_SENSOR_RANGE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4383,13 +4380,13 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy extract(deserializer, *settingOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4401,7 +4398,7 @@ TypedResult saveSensorRange(C::mip_interface& device, SensorRangeTy } TypedResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4413,7 +4410,7 @@ TypedResult loadSensorRange(C::mip_interface& device, SensorRangeTy } TypedResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4471,7 +4468,7 @@ void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Entry& s TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, sensor); @@ -4481,7 +4478,7 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CALIBRATED_RANGES, buffer, (uint8_t)serializer.length(), REPLY_CALIBRATED_RANGES, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4493,7 +4490,7 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev extract(deserializer, rangesOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -4563,7 +4560,7 @@ void extract(::microstrain::Buffer& serializer, LowpassFilter::Response& self) TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool enable, bool manual, float frequency) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4583,7 +4580,7 @@ TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t } TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4596,7 +4593,7 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length(), REPLY_LOWPASS_FILTER, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4614,13 +4611,13 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d extract(deserializer, *frequencyOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4634,7 +4631,7 @@ TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t d } TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4648,7 +4645,7 @@ TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t d } TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); diff --git a/src/mip/definitions/commands_3dm.h b/src/mip/definitions/commands_3dm.h index 0aec3750e..467678aba 100644 --- a/src/mip/definitions/commands_3dm.h +++ b/src/mip/definitions/commands_3dm.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_3dm.hpp b/src/mip/definitions/commands_3dm.hpp index 8ca163811..5fe7aae89 100644 --- a/src/mip/definitions/commands_3dm.hpp +++ b/src/mip/definitions/commands_3dm.hpp @@ -1,18 +1,13 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include #include #include -namespace microstrain -{ -class Buffer; -} - namespace mip { namespace C { struct mip_interface; diff --git a/src/mip/definitions/commands_aiding.cpp b/src/mip/definitions/commands_aiding.cpp index 52cfeb67a..93f4d5221 100644 --- a/src/mip/definitions/commands_aiding.cpp +++ b/src/mip/definitions/commands_aiding.cpp @@ -156,7 +156,7 @@ void extract(::microstrain::Buffer& serializer, FrameConfig::Response& self) TypedResult writeFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool trackingEnabled, const float* translation, const FrameConfig::Rotation& rotation) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -186,7 +186,7 @@ TypedResult writeFrameConfig(C::mip_interface& device, uint8_t fram } TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -199,7 +199,7 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_FRAME_CONFIG, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -225,13 +225,13 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame } if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frameId) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -243,7 +243,7 @@ TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frame } TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frameId) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -255,7 +255,7 @@ TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frame } TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t frameId) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -299,7 +299,7 @@ void extract(::microstrain::Buffer& serializer, AidingEchoControl::Response& sel TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -311,7 +311,7 @@ TypedResult writeAidingEchoControl(C::mip_interface& device, } TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -320,7 +320,7 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -328,13 +328,13 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A extract(deserializer, *modeOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAidingEchoControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -344,7 +344,7 @@ TypedResult saveAidingEchoControl(C::mip_interface& device) } TypedResult loadAidingEchoControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -354,7 +354,7 @@ TypedResult loadAidingEchoControl(C::mip_interface& device) } TypedResult defaultAidingEchoControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -395,7 +395,7 @@ void extract(::microstrain::Buffer& serializer, EcefPos& self) TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -455,7 +455,7 @@ void extract(::microstrain::Buffer& serializer, LlhPos& self) TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -507,7 +507,7 @@ void extract(::microstrain::Buffer& serializer, Height& self) TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -557,7 +557,7 @@ void extract(::microstrain::Buffer& serializer, EcefVel& self) TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -611,7 +611,7 @@ void extract(::microstrain::Buffer& serializer, NedVel& self) TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -665,7 +665,7 @@ void extract(::microstrain::Buffer& serializer, VehicleFixedFrameVelocity& self) TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -715,7 +715,7 @@ void extract(::microstrain::Buffer& serializer, TrueHeading& self) TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -765,7 +765,7 @@ void extract(::microstrain::Buffer& serializer, MagneticField& self) TypedResult magneticField(C::mip_interface& device, const Time& time, uint8_t frameId, const float* magneticField, const float* uncertainty, MagneticField::ValidFlags validFlags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -815,7 +815,7 @@ void extract(::microstrain::Buffer& serializer, Pressure& self) TypedResult pressure(C::mip_interface& device, const Time& time, uint8_t frameId, float pressure, float uncertainty, uint16_t validFlags) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, time); diff --git a/src/mip/definitions/commands_aiding.h b/src/mip/definitions/commands_aiding.h index c207411b1..55b1bb374 100644 --- a/src/mip/definitions/commands_aiding.h +++ b/src/mip/definitions/commands_aiding.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_aiding.hpp b/src/mip/definitions/commands_aiding.hpp index be1d6d877..f2b7bd23e 100644 --- a/src/mip/definitions/commands_aiding.hpp +++ b/src/mip/definitions/commands_aiding.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_base.cpp b/src/mip/definitions/commands_base.cpp index 512d98b2d..43d34a490 100644 --- a/src/mip/definitions/commands_base.cpp +++ b/src/mip/definitions/commands_base.cpp @@ -123,12 +123,12 @@ void extract(::microstrain::Buffer& serializer, GetDeviceInfo::Response& self) TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_INFO, NULL, 0, REPLY_DEVICE_INFO, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -136,7 +136,7 @@ TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInf extract(deserializer, *deviceInfoOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -166,12 +166,12 @@ void extract(::microstrain::Buffer& serializer, GetDeviceDescriptors::Response& TypedResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_DESCRIPTORS, NULL, 0, REPLY_DEVICE_DESCRIPTORS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -179,7 +179,7 @@ TypedResult getDeviceDescriptors(C::mip_interface& device, extract(deserializer, descriptorsOut[*descriptorsOutCount]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -207,12 +207,12 @@ void extract(::microstrain::Buffer& serializer, BuiltInTest::Response& self) TypedResult builtInTest(C::mip_interface& device, uint32_t* resultOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_BUILT_IN_TEST, NULL, 0, REPLY_BUILT_IN_TEST, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -220,7 +220,7 @@ TypedResult builtInTest(C::mip_interface& device, uint32_t* resultO extract(deserializer, *resultOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -265,12 +265,12 @@ void extract(::microstrain::Buffer& serializer, GetExtendedDescriptors::Response TypedResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_EXTENDED_DESCRIPTORS, NULL, 0, REPLY_GET_EXTENDED_DESCRIPTORS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -278,7 +278,7 @@ TypedResult getExtendedDescriptors(C::mip_interface& dev extract(deserializer, descriptorsOut[*descriptorsOutCount]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -308,12 +308,12 @@ void extract(::microstrain::Buffer& serializer, ContinuousBit::Response& self) TypedResult continuousBit(C::mip_interface& device, uint8_t* resultOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTINUOUS_BIT, NULL, 0, REPLY_CONTINUOUS_BIT, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -322,7 +322,7 @@ TypedResult continuousBit(C::mip_interface& device, uint8_t* resu extract(deserializer, resultOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -368,7 +368,7 @@ void extract(::microstrain::Buffer& serializer, CommSpeed::Response& self) TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -382,7 +382,7 @@ TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, ui } TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -393,7 +393,7 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length(), REPLY_COMM_SPEED, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -403,13 +403,13 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin extract(deserializer, *baudOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -421,7 +421,7 @@ TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) } TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -433,7 +433,7 @@ TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) } TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -470,7 +470,7 @@ void extract(::microstrain::Buffer& serializer, GpsTimeUpdate& self) TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); diff --git a/src/mip/definitions/commands_base.h b/src/mip/definitions/commands_base.h index 2e43634ec..d225677af 100644 --- a/src/mip/definitions/commands_base.h +++ b/src/mip/definitions/commands_base.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_base.hpp b/src/mip/definitions/commands_base.hpp index 003a44734..b62a413ff 100644 --- a/src/mip/definitions/commands_base.hpp +++ b/src/mip/definitions/commands_base.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_filter.cpp b/src/mip/definitions/commands_filter.cpp index d60ddd37a..4ee016e8f 100644 --- a/src/mip/definitions/commands_filter.cpp +++ b/src/mip/definitions/commands_filter.cpp @@ -66,7 +66,7 @@ void extract(::microstrain::Buffer& serializer, SetInitialAttitude& self) TypedResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, roll); @@ -113,7 +113,7 @@ void extract(::microstrain::Buffer& serializer, EstimationControl::Response& sel TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -125,7 +125,7 @@ TypedResult writeEstimationControl(C::mip_interface& device, } TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -134,7 +134,7 @@ TypedResult readEstimationControl(C::mip_interface& device, E uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length(), REPLY_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -142,13 +142,13 @@ TypedResult readEstimationControl(C::mip_interface& device, E extract(deserializer, *enableOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveEstimationControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -158,7 +158,7 @@ TypedResult saveEstimationControl(C::mip_interface& device) } TypedResult loadEstimationControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -168,7 +168,7 @@ TypedResult loadEstimationControl(C::mip_interface& device) } TypedResult defaultEstimationControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -223,7 +223,7 @@ void extract(::microstrain::Buffer& serializer, ExternalGnssUpdate& self) TypedResult externalGnssUpdate(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, double latitude, double longitude, double height, const float* velocity, const float* posUncertainty, const float* velUncertainty) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, gpsTime); @@ -273,7 +273,7 @@ void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdate& self) TypedResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, heading); @@ -315,7 +315,7 @@ void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdateWithTime& s TypedResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, gpsTime); @@ -366,7 +366,7 @@ void extract(::microstrain::Buffer& serializer, TareOrientation::Response& self) TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -378,7 +378,7 @@ TypedResult writeTareOrientation(C::mip_interface& device, Tare } TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -387,7 +387,7 @@ TypedResult readTareOrientation(C::mip_interface& device, TareO uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length(), REPLY_TARE_ORIENTATION, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -395,13 +395,13 @@ TypedResult readTareOrientation(C::mip_interface& device, TareO extract(deserializer, *axesOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveTareOrientation(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -411,7 +411,7 @@ TypedResult saveTareOrientation(C::mip_interface& device) } TypedResult loadTareOrientation(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -421,7 +421,7 @@ TypedResult loadTareOrientation(C::mip_interface& device) } TypedResult defaultTareOrientation(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -463,7 +463,7 @@ void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode::Response& s TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -475,7 +475,7 @@ TypedResult writeVehicleDynamicsMode(C::mip_interface& devi } TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -484,7 +484,7 @@ TypedResult readVehicleDynamicsMode(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length(), REPLY_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -492,13 +492,13 @@ TypedResult readVehicleDynamicsMode(C::mip_interface& devic extract(deserializer, *modeOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveVehicleDynamicsMode(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -508,7 +508,7 @@ TypedResult saveVehicleDynamicsMode(C::mip_interface& devic } TypedResult loadVehicleDynamicsMode(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -518,7 +518,7 @@ TypedResult loadVehicleDynamicsMode(C::mip_interface& devic } TypedResult defaultVehicleDynamicsMode(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -576,7 +576,7 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler::Re TypedResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -592,7 +592,7 @@ TypedResult writeSensorToVehicleRotationEuler(C::m } TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -601,7 +601,7 @@ TypedResult readSensorToVehicleRotationEuler(C::mi uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -615,13 +615,13 @@ TypedResult readSensorToVehicleRotationEuler(C::mi extract(deserializer, *yawOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSensorToVehicleRotationEuler(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -631,7 +631,7 @@ TypedResult saveSensorToVehicleRotationEuler(C::mi } TypedResult loadSensorToVehicleRotationEuler(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -641,7 +641,7 @@ TypedResult loadSensorToVehicleRotationEuler(C::mi } TypedResult defaultSensorToVehicleRotationEuler(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -687,7 +687,7 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm::Resp TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -701,7 +701,7 @@ TypedResult writeSensorToVehicleRotationDcm(C::mip_i } TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -710,7 +710,7 @@ TypedResult readSensorToVehicleRotationDcm(C::mip_in uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -719,13 +719,13 @@ TypedResult readSensorToVehicleRotationDcm(C::mip_in extract(deserializer, dcmOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSensorToVehicleRotationDcm(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -735,7 +735,7 @@ TypedResult saveSensorToVehicleRotationDcm(C::mip_in } TypedResult loadSensorToVehicleRotationDcm(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -745,7 +745,7 @@ TypedResult loadSensorToVehicleRotationDcm(C::mip_in } TypedResult defaultSensorToVehicleRotationDcm(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -791,7 +791,7 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternio TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -805,7 +805,7 @@ TypedResult writeSensorToVehicleRotationQuate } TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -814,7 +814,7 @@ TypedResult readSensorToVehicleRotationQuater uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -823,13 +823,13 @@ TypedResult readSensorToVehicleRotationQuater extract(deserializer, quatOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -839,7 +839,7 @@ TypedResult saveSensorToVehicleRotationQuater } TypedResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -849,7 +849,7 @@ TypedResult loadSensorToVehicleRotationQuater } TypedResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -895,7 +895,7 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset::Response& TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -909,7 +909,7 @@ TypedResult writeSensorToVehicleOffset(C::mip_interface& } TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -918,7 +918,7 @@ TypedResult readSensorToVehicleOffset(C::mip_interface& d uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -927,13 +927,13 @@ TypedResult readSensorToVehicleOffset(C::mip_interface& d extract(deserializer, offsetOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSensorToVehicleOffset(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -943,7 +943,7 @@ TypedResult saveSensorToVehicleOffset(C::mip_interface& d } TypedResult loadSensorToVehicleOffset(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -953,7 +953,7 @@ TypedResult loadSensorToVehicleOffset(C::mip_interface& d } TypedResult defaultSensorToVehicleOffset(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -999,7 +999,7 @@ void extract(::microstrain::Buffer& serializer, AntennaOffset::Response& self) TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1013,7 +1013,7 @@ TypedResult writeAntennaOffset(C::mip_interface& device, const fl } TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1022,7 +1022,7 @@ TypedResult readAntennaOffset(C::mip_interface& device, float* of uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_ANTENNA_OFFSET, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1031,13 +1031,13 @@ TypedResult readAntennaOffset(C::mip_interface& device, float* of extract(deserializer, offsetOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAntennaOffset(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1047,7 +1047,7 @@ TypedResult saveAntennaOffset(C::mip_interface& device) } TypedResult loadAntennaOffset(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1057,7 +1057,7 @@ TypedResult loadAntennaOffset(C::mip_interface& device) } TypedResult defaultAntennaOffset(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1099,7 +1099,7 @@ void extract(::microstrain::Buffer& serializer, GnssSource::Response& self) TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1111,7 +1111,7 @@ TypedResult writeGnssSource(C::mip_interface& device, GnssSource::So } TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1120,7 +1120,7 @@ TypedResult readGnssSource(C::mip_interface& device, GnssSource::Sou uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_GNSS_SOURCE_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1128,13 +1128,13 @@ TypedResult readGnssSource(C::mip_interface& device, GnssSource::Sou extract(deserializer, *sourceOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGnssSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1144,7 +1144,7 @@ TypedResult saveGnssSource(C::mip_interface& device) } TypedResult loadGnssSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1154,7 +1154,7 @@ TypedResult loadGnssSource(C::mip_interface& device) } TypedResult defaultGnssSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1196,7 +1196,7 @@ void extract(::microstrain::Buffer& serializer, HeadingSource::Response& self) TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1208,7 +1208,7 @@ TypedResult writeHeadingSource(C::mip_interface& device, HeadingS } TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1217,7 +1217,7 @@ TypedResult readHeadingSource(C::mip_interface& device, HeadingSo uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_HEADING_UPDATE_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1225,13 +1225,13 @@ TypedResult readHeadingSource(C::mip_interface& device, HeadingSo extract(deserializer, *sourceOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveHeadingSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1241,7 +1241,7 @@ TypedResult saveHeadingSource(C::mip_interface& device) } TypedResult loadHeadingSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1251,7 +1251,7 @@ TypedResult loadHeadingSource(C::mip_interface& device) } TypedResult defaultHeadingSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1293,7 +1293,7 @@ void extract(::microstrain::Buffer& serializer, AutoInitControl::Response& self) TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1305,7 +1305,7 @@ TypedResult writeAutoInitControl(C::mip_interface& device, uint } TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1314,7 +1314,7 @@ TypedResult readAutoInitControl(C::mip_interface& device, uint8 uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_AUTOINIT_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1322,13 +1322,13 @@ TypedResult readAutoInitControl(C::mip_interface& device, uint8 extract(deserializer, *enableOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAutoInitControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1338,7 +1338,7 @@ TypedResult saveAutoInitControl(C::mip_interface& device) } TypedResult loadAutoInitControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1348,7 +1348,7 @@ TypedResult loadAutoInitControl(C::mip_interface& device) } TypedResult defaultAutoInitControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1394,7 +1394,7 @@ void extract(::microstrain::Buffer& serializer, AccelNoise::Response& self) TypedResult writeAccelNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1408,7 +1408,7 @@ TypedResult writeAccelNoise(C::mip_interface& device, const float* n } TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1417,7 +1417,7 @@ TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_NOISE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1426,13 +1426,13 @@ TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut extract(deserializer, noiseOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAccelNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1442,7 +1442,7 @@ TypedResult saveAccelNoise(C::mip_interface& device) } TypedResult loadAccelNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1452,7 +1452,7 @@ TypedResult loadAccelNoise(C::mip_interface& device) } TypedResult defaultAccelNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1498,7 +1498,7 @@ void extract(::microstrain::Buffer& serializer, GyroNoise::Response& self) TypedResult writeGyroNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1512,7 +1512,7 @@ TypedResult writeGyroNoise(C::mip_interface& device, const float* noi } TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1521,7 +1521,7 @@ TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length(), REPLY_GYRO_NOISE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1530,13 +1530,13 @@ TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) extract(deserializer, noiseOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGyroNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1546,7 +1546,7 @@ TypedResult saveGyroNoise(C::mip_interface& device) } TypedResult loadGyroNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1556,7 +1556,7 @@ TypedResult loadGyroNoise(C::mip_interface& device) } TypedResult defaultGyroNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1614,7 +1614,7 @@ void extract(::microstrain::Buffer& serializer, AccelBiasModel::Response& self) TypedResult writeAccelBiasModel(C::mip_interface& device, const float* beta, const float* noise) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1632,7 +1632,7 @@ TypedResult writeAccelBiasModel(C::mip_interface& device, const } TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1641,7 +1641,7 @@ TypedResult readAccelBiasModel(C::mip_interface& device, float* uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_BIAS_MODEL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1654,13 +1654,13 @@ TypedResult readAccelBiasModel(C::mip_interface& device, float* extract(deserializer, noiseOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAccelBiasModel(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1670,7 +1670,7 @@ TypedResult saveAccelBiasModel(C::mip_interface& device) } TypedResult loadAccelBiasModel(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1680,7 +1680,7 @@ TypedResult loadAccelBiasModel(C::mip_interface& device) } TypedResult defaultAccelBiasModel(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1738,7 +1738,7 @@ void extract(::microstrain::Buffer& serializer, GyroBiasModel::Response& self) TypedResult writeGyroBiasModel(C::mip_interface& device, const float* beta, const float* noise) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1756,7 +1756,7 @@ TypedResult writeGyroBiasModel(C::mip_interface& device, const fl } TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1765,7 +1765,7 @@ TypedResult readGyroBiasModel(C::mip_interface& device, float* be uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_MODEL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1778,13 +1778,13 @@ TypedResult readGyroBiasModel(C::mip_interface& device, float* be extract(deserializer, noiseOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGyroBiasModel(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1794,7 +1794,7 @@ TypedResult saveGyroBiasModel(C::mip_interface& device) } TypedResult loadGyroBiasModel(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1804,7 +1804,7 @@ TypedResult loadGyroBiasModel(C::mip_interface& device) } TypedResult defaultGyroBiasModel(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1846,7 +1846,7 @@ void extract(::microstrain::Buffer& serializer, AltitudeAiding::Response& self) TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1858,7 +1858,7 @@ TypedResult writeAltitudeAiding(C::mip_interface& device, Altitu } TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1867,7 +1867,7 @@ TypedResult readAltitudeAiding(C::mip_interface& device, Altitud uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1875,13 +1875,13 @@ TypedResult readAltitudeAiding(C::mip_interface& device, Altitud extract(deserializer, *selectorOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAltitudeAiding(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1891,7 +1891,7 @@ TypedResult saveAltitudeAiding(C::mip_interface& device) } TypedResult loadAltitudeAiding(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1901,7 +1901,7 @@ TypedResult loadAltitudeAiding(C::mip_interface& device) } TypedResult defaultAltitudeAiding(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -1943,7 +1943,7 @@ void extract(::microstrain::Buffer& serializer, PitchRollAiding::Response& self) TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -1955,7 +1955,7 @@ TypedResult writePitchRollAiding(C::mip_interface& device, Pitc } TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -1964,7 +1964,7 @@ TypedResult readPitchRollAiding(C::mip_interface& device, Pitch uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -1972,13 +1972,13 @@ TypedResult readPitchRollAiding(C::mip_interface& device, Pitch extract(deserializer, *sourceOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult savePitchRollAiding(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -1988,7 +1988,7 @@ TypedResult savePitchRollAiding(C::mip_interface& device) } TypedResult loadPitchRollAiding(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -1998,7 +1998,7 @@ TypedResult loadPitchRollAiding(C::mip_interface& device) } TypedResult defaultPitchRollAiding(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2048,7 +2048,7 @@ void extract(::microstrain::Buffer& serializer, AutoZupt::Response& self) TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2062,7 +2062,7 @@ TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, fl } TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2071,7 +2071,7 @@ TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ZUPT_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2082,13 +2082,13 @@ TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, extract(deserializer, *thresholdOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAutoZupt(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2098,7 +2098,7 @@ TypedResult saveAutoZupt(C::mip_interface& device) } TypedResult loadAutoZupt(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2108,7 +2108,7 @@ TypedResult loadAutoZupt(C::mip_interface& device) } TypedResult defaultAutoZupt(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2158,7 +2158,7 @@ void extract(::microstrain::Buffer& serializer, AutoAngularZupt::Response& self) TypedResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2172,7 +2172,7 @@ TypedResult writeAutoAngularZupt(C::mip_interface& device, uint } TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2181,7 +2181,7 @@ TypedResult readAutoAngularZupt(C::mip_interface& device, uint8 uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2192,13 +2192,13 @@ TypedResult readAutoAngularZupt(C::mip_interface& device, uint8 extract(deserializer, *thresholdOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAutoAngularZupt(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2208,7 +2208,7 @@ TypedResult saveAutoAngularZupt(C::mip_interface& device) } TypedResult loadAutoAngularZupt(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2218,7 +2218,7 @@ TypedResult loadAutoAngularZupt(C::mip_interface& device) } TypedResult defaultAutoAngularZupt(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2269,7 +2269,7 @@ void extract(::microstrain::Buffer& serializer, MagCaptureAutoCal& self) TypedResult writeMagCaptureAutoCal(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2279,7 +2279,7 @@ TypedResult writeMagCaptureAutoCal(C::mip_interface& device) } TypedResult saveMagCaptureAutoCal(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2325,7 +2325,7 @@ void extract(::microstrain::Buffer& serializer, GravityNoise::Response& self) TypedResult writeGravityNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2339,7 +2339,7 @@ TypedResult writeGravityNoise(C::mip_interface& device, const floa } TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2348,7 +2348,7 @@ TypedResult readGravityNoise(C::mip_interface& device, float* nois uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length(), REPLY_GRAVITY_NOISE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2357,13 +2357,13 @@ TypedResult readGravityNoise(C::mip_interface& device, float* nois extract(deserializer, noiseOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGravityNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2373,7 +2373,7 @@ TypedResult saveGravityNoise(C::mip_interface& device) } TypedResult loadGravityNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2383,7 +2383,7 @@ TypedResult loadGravityNoise(C::mip_interface& device) } TypedResult defaultGravityNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2425,7 +2425,7 @@ void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise::Response& TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2437,7 +2437,7 @@ TypedResult writePressureAltitudeNoise(C::mip_interface& } TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2446,7 +2446,7 @@ TypedResult readPressureAltitudeNoise(C::mip_interface& d uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length(), REPLY_PRESSURE_NOISE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2454,13 +2454,13 @@ TypedResult readPressureAltitudeNoise(C::mip_interface& d extract(deserializer, *noiseOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult savePressureAltitudeNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2470,7 +2470,7 @@ TypedResult savePressureAltitudeNoise(C::mip_interface& d } TypedResult loadPressureAltitudeNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2480,7 +2480,7 @@ TypedResult loadPressureAltitudeNoise(C::mip_interface& d } TypedResult defaultPressureAltitudeNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2526,7 +2526,7 @@ void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise::Response& s TypedResult writeHardIronOffsetNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2540,7 +2540,7 @@ TypedResult writeHardIronOffsetNoise(C::mip_interface& devi } TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2549,7 +2549,7 @@ TypedResult readHardIronOffsetNoise(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length(), REPLY_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2558,13 +2558,13 @@ TypedResult readHardIronOffsetNoise(C::mip_interface& devic extract(deserializer, noiseOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveHardIronOffsetNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2574,7 +2574,7 @@ TypedResult saveHardIronOffsetNoise(C::mip_interface& devic } TypedResult loadHardIronOffsetNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2584,7 +2584,7 @@ TypedResult loadHardIronOffsetNoise(C::mip_interface& devic } TypedResult defaultHardIronOffsetNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2630,7 +2630,7 @@ void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise::Response& s TypedResult writeSoftIronMatrixNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2644,7 +2644,7 @@ TypedResult writeSoftIronMatrixNoise(C::mip_interface& devi } TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2653,7 +2653,7 @@ TypedResult readSoftIronMatrixNoise(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length(), REPLY_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2662,13 +2662,13 @@ TypedResult readSoftIronMatrixNoise(C::mip_interface& devic extract(deserializer, noiseOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSoftIronMatrixNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2678,7 +2678,7 @@ TypedResult saveSoftIronMatrixNoise(C::mip_interface& devic } TypedResult loadSoftIronMatrixNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2688,7 +2688,7 @@ TypedResult loadSoftIronMatrixNoise(C::mip_interface& devic } TypedResult defaultSoftIronMatrixNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2734,7 +2734,7 @@ void extract(::microstrain::Buffer& serializer, MagNoise::Response& self) TypedResult writeMagNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2748,7 +2748,7 @@ TypedResult writeMagNoise(C::mip_interface& device, const float* noise } TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2757,7 +2757,7 @@ TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length(), REPLY_MAG_NOISE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2766,13 +2766,13 @@ TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) extract(deserializer, noiseOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveMagNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2782,7 +2782,7 @@ TypedResult saveMagNoise(C::mip_interface& device) } TypedResult loadMagNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2792,7 +2792,7 @@ TypedResult loadMagNoise(C::mip_interface& device) } TypedResult defaultMagNoise(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2842,7 +2842,7 @@ void extract(::microstrain::Buffer& serializer, InclinationSource::Response& sel TypedResult writeInclinationSource(C::mip_interface& device, FilterMagParamSource source, float inclination) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2856,7 +2856,7 @@ TypedResult writeInclinationSource(C::mip_interface& device, } TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2865,7 +2865,7 @@ TypedResult readInclinationSource(C::mip_interface& device, F uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_INCLINATION_SOURCE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2876,13 +2876,13 @@ TypedResult readInclinationSource(C::mip_interface& device, F extract(deserializer, *inclinationOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveInclinationSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -2892,7 +2892,7 @@ TypedResult saveInclinationSource(C::mip_interface& device) } TypedResult loadInclinationSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -2902,7 +2902,7 @@ TypedResult loadInclinationSource(C::mip_interface& device) } TypedResult defaultInclinationSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -2952,7 +2952,7 @@ void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource::Respo TypedResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource source, float declination) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -2966,7 +2966,7 @@ TypedResult writeMagneticDeclinationSource(C::mip_int } TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -2975,7 +2975,7 @@ TypedResult readMagneticDeclinationSource(C::mip_inte uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_DECLINATION_SOURCE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -2986,13 +2986,13 @@ TypedResult readMagneticDeclinationSource(C::mip_inte extract(deserializer, *declinationOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveMagneticDeclinationSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3002,7 +3002,7 @@ TypedResult saveMagneticDeclinationSource(C::mip_inte } TypedResult loadMagneticDeclinationSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3012,7 +3012,7 @@ TypedResult loadMagneticDeclinationSource(C::mip_inte } TypedResult defaultMagneticDeclinationSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3062,7 +3062,7 @@ void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource::Respons TypedResult writeMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource source, float magnitude) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3076,7 +3076,7 @@ TypedResult writeMagFieldMagnitudeSource(C::mip_interfa } TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3085,7 +3085,7 @@ TypedResult readMagFieldMagnitudeSource(C::mip_interfac uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3096,13 +3096,13 @@ TypedResult readMagFieldMagnitudeSource(C::mip_interfac extract(deserializer, *magnitudeOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveMagFieldMagnitudeSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3112,7 +3112,7 @@ TypedResult saveMagFieldMagnitudeSource(C::mip_interfac } TypedResult loadMagFieldMagnitudeSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3122,7 +3122,7 @@ TypedResult loadMagFieldMagnitudeSource(C::mip_interfac } TypedResult defaultMagFieldMagnitudeSource(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3188,7 +3188,7 @@ void extract(::microstrain::Buffer& serializer, ReferencePosition::Response& sel TypedResult writeReferencePosition(C::mip_interface& device, bool enable, double latitude, double longitude, double altitude) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3206,7 +3206,7 @@ TypedResult writeReferencePosition(C::mip_interface& device, } TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3215,7 +3215,7 @@ TypedResult readReferencePosition(C::mip_interface& device, b uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length(), REPLY_REFERENCE_POSITION, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3232,13 +3232,13 @@ TypedResult readReferencePosition(C::mip_interface& device, b extract(deserializer, *altitudeOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveReferencePosition(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3248,7 +3248,7 @@ TypedResult saveReferencePosition(C::mip_interface& device) } TypedResult loadReferencePosition(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3258,7 +3258,7 @@ TypedResult loadReferencePosition(C::mip_interface& device) } TypedResult defaultReferencePosition(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3348,7 +3348,7 @@ void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasu TypedResult writeAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3372,7 +3372,7 @@ TypedResult writeAccelMagnitudeErrorAdap } TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3381,7 +3381,7 @@ TypedResult readAccelMagnitudeErrorAdapt uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3407,13 +3407,13 @@ TypedResult readAccelMagnitudeErrorAdapt extract(deserializer, *minimumUncertaintyOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3423,7 +3423,7 @@ TypedResult saveAccelMagnitudeErrorAdapt } TypedResult loadAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3433,7 +3433,7 @@ TypedResult loadAccelMagnitudeErrorAdapt } TypedResult defaultAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3523,7 +3523,7 @@ void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasure TypedResult writeMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3547,7 +3547,7 @@ TypedResult writeMagMagnitudeErrorAdaptive } TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3556,7 +3556,7 @@ TypedResult readMagMagnitudeErrorAdaptiveM uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3582,13 +3582,13 @@ TypedResult readMagMagnitudeErrorAdaptiveM extract(deserializer, *minimumUncertaintyOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3598,7 +3598,7 @@ TypedResult saveMagMagnitudeErrorAdaptiveM } TypedResult loadMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3608,7 +3608,7 @@ TypedResult loadMagMagnitudeErrorAdaptiveM } TypedResult defaultMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3682,7 +3682,7 @@ void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurem TypedResult writeMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool enable, float frequency, float highLimit, float highLimitUncertainty, float minimumUncertainty) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3702,7 +3702,7 @@ TypedResult writeMagDipAngleErrorAdaptiveMe } TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3711,7 +3711,7 @@ TypedResult readMagDipAngleErrorAdaptiveMea uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3731,13 +3731,13 @@ TypedResult readMagDipAngleErrorAdaptiveMea extract(deserializer, *minimumUncertaintyOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3747,7 +3747,7 @@ TypedResult saveMagDipAngleErrorAdaptiveMea } TypedResult loadMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3757,7 +3757,7 @@ TypedResult loadMagDipAngleErrorAdaptiveMea } TypedResult defaultMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3807,7 +3807,7 @@ void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable::Respons TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3821,7 +3821,7 @@ TypedResult writeAidingMeasurementEnable(C::mip_interfa } TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3832,7 +3832,7 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length(), REPLY_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3842,13 +3842,13 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac extract(deserializer, *enableOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -3860,7 +3860,7 @@ TypedResult saveAidingMeasurementEnable(C::mip_interfac } TypedResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -3872,7 +3872,7 @@ TypedResult loadAidingMeasurementEnable(C::mip_interfac } TypedResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -3947,7 +3947,7 @@ void extract(::microstrain::Buffer& serializer, KinematicConstraint::Response& s TypedResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -3963,7 +3963,7 @@ TypedResult writeKinematicConstraint(C::mip_interface& devi } TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -3972,7 +3972,7 @@ TypedResult readKinematicConstraint(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length(), REPLY_KINEMATIC_CONSTRAINT, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -3986,13 +3986,13 @@ TypedResult readKinematicConstraint(C::mip_interface& devic extract(deserializer, *angularConstraintSelectionOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveKinematicConstraint(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4002,7 +4002,7 @@ TypedResult saveKinematicConstraint(C::mip_interface& devic } TypedResult loadKinematicConstraint(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4012,7 +4012,7 @@ TypedResult loadKinematicConstraint(C::mip_interface& devic } TypedResult defaultKinematicConstraint(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4126,7 +4126,7 @@ void extract(::microstrain::Buffer& serializer, InitializationConfiguration::Res TypedResult writeInitializationConfiguration(C::mip_interface& device, uint8_t waitForRunCommand, InitializationConfiguration::InitialConditionSource initialCondSrc, InitializationConfiguration::AlignmentSelector autoHeadingAlignmentSelector, float initialHeading, float initialPitch, float initialRoll, const float* initialPosition, const float* initialVelocity, FilterReferenceFrame referenceFrameSelector) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4158,7 +4158,7 @@ TypedResult writeInitializationConfiguration(C::mip } TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4167,7 +4167,7 @@ TypedResult readInitializationConfiguration(C::mip_ uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_INITIALIZATION_CONFIGURATION, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4201,13 +4201,13 @@ TypedResult readInitializationConfiguration(C::mip_ extract(deserializer, *referenceFrameSelectorOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveInitializationConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4217,7 +4217,7 @@ TypedResult saveInitializationConfiguration(C::mip_ } TypedResult loadInitializationConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4227,7 +4227,7 @@ TypedResult loadInitializationConfiguration(C::mip_ } TypedResult defaultInitializationConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4277,7 +4277,7 @@ void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions::Response& TypedResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4291,7 +4291,7 @@ TypedResult writeAdaptiveFilterOptions(C::mip_interface& } TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4300,7 +4300,7 @@ TypedResult readAdaptiveFilterOptions(C::mip_interface& d uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length(), REPLY_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4311,13 +4311,13 @@ TypedResult readAdaptiveFilterOptions(C::mip_interface& d extract(deserializer, *timeLimitOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveAdaptiveFilterOptions(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4327,7 +4327,7 @@ TypedResult saveAdaptiveFilterOptions(C::mip_interface& d } TypedResult loadAdaptiveFilterOptions(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4337,7 +4337,7 @@ TypedResult loadAdaptiveFilterOptions(C::mip_interface& d } TypedResult defaultAdaptiveFilterOptions(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4391,7 +4391,7 @@ void extract(::microstrain::Buffer& serializer, MultiAntennaOffset::Response& se TypedResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4407,7 +4407,7 @@ TypedResult writeMultiAntennaOffset(C::mip_interface& device } TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4418,7 +4418,7 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_MULTI_ANTENNA_OFFSET, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4429,13 +4429,13 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, extract(deserializer, antennaOffsetOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4447,7 +4447,7 @@ TypedResult saveMultiAntennaOffset(C::mip_interface& device, } TypedResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4459,7 +4459,7 @@ TypedResult loadMultiAntennaOffset(C::mip_interface& device, } TypedResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4523,7 +4523,7 @@ void extract(::microstrain::Buffer& serializer, RelPosConfiguration::Response& s TypedResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4541,7 +4541,7 @@ TypedResult writeRelPosConfiguration(C::mip_interface& devi } TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4550,7 +4550,7 @@ TypedResult readRelPosConfiguration(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_REL_POS_CONFIGURATION, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4565,13 +4565,13 @@ TypedResult readRelPosConfiguration(C::mip_interface& devic extract(deserializer, referenceCoordinatesOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveRelPosConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4581,7 +4581,7 @@ TypedResult saveRelPosConfiguration(C::mip_interface& devic } TypedResult loadRelPosConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4591,7 +4591,7 @@ TypedResult loadRelPosConfiguration(C::mip_interface& devic } TypedResult defaultRelPosConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4645,7 +4645,7 @@ void extract(::microstrain::Buffer& serializer, RefPointLeverArm::Response& self TypedResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4661,7 +4661,7 @@ TypedResult writeRefPointLeverArm(C::mip_interface& device, Re } TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4670,7 +4670,7 @@ TypedResult readRefPointLeverArm(C::mip_interface& device, Ref uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length(), REPLY_REF_POINT_LEVER_ARM, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4682,13 +4682,13 @@ TypedResult readRefPointLeverArm(C::mip_interface& device, Ref extract(deserializer, leverArmOffsetOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveRefPointLeverArm(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4698,7 +4698,7 @@ TypedResult saveRefPointLeverArm(C::mip_interface& device) } TypedResult loadRefPointLeverArm(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4708,7 +4708,7 @@ TypedResult loadRefPointLeverArm(C::mip_interface& device) } TypedResult defaultRefPointLeverArm(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4741,7 +4741,7 @@ void extract(::microstrain::Buffer& serializer, SpeedMeasurement& self) TypedResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, source); @@ -4802,7 +4802,7 @@ void extract(::microstrain::Buffer& serializer, SpeedLeverArm::Response& self) TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4818,7 +4818,7 @@ TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t } TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4829,7 +4829,7 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length(), REPLY_SPEED_LEVER_ARM, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4840,13 +4840,13 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s extract(deserializer, leverArmOffsetOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4858,7 +4858,7 @@ TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t s } TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4870,7 +4870,7 @@ TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t s } TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -4914,7 +4914,7 @@ void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl: TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -4926,7 +4926,7 @@ TypedResult writeWheeledVehicleConstraintContro } TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -4935,7 +4935,7 @@ TypedResult readWheeledVehicleConstraintControl uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -4943,13 +4943,13 @@ TypedResult readWheeledVehicleConstraintControl extract(deserializer, *enableOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveWheeledVehicleConstraintControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -4959,7 +4959,7 @@ TypedResult saveWheeledVehicleConstraintControl } TypedResult loadWheeledVehicleConstraintControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -4969,7 +4969,7 @@ TypedResult loadWheeledVehicleConstraintControl } TypedResult defaultWheeledVehicleConstraintControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -5011,7 +5011,7 @@ void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl::R TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -5023,7 +5023,7 @@ TypedResult writeVerticalGyroConstraintControl(C: } TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -5032,7 +5032,7 @@ TypedResult readVerticalGyroConstraintControl(C:: uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -5040,13 +5040,13 @@ TypedResult readVerticalGyroConstraintControl(C:: extract(deserializer, *enableOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveVerticalGyroConstraintControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -5056,7 +5056,7 @@ TypedResult saveVerticalGyroConstraintControl(C:: } TypedResult loadVerticalGyroConstraintControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -5066,7 +5066,7 @@ TypedResult loadVerticalGyroConstraintControl(C:: } TypedResult defaultVerticalGyroConstraintControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -5116,7 +5116,7 @@ void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl::Response& TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -5130,7 +5130,7 @@ TypedResult writeGnssAntennaCalControl(C::mip_interface& } TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -5139,7 +5139,7 @@ TypedResult readGnssAntennaCalControl(C::mip_interface& d uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -5150,13 +5150,13 @@ TypedResult readGnssAntennaCalControl(C::mip_interface& d extract(deserializer, *maxOffsetOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveGnssAntennaCalControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -5166,7 +5166,7 @@ TypedResult saveGnssAntennaCalControl(C::mip_interface& d } TypedResult loadGnssAntennaCalControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -5176,7 +5176,7 @@ TypedResult loadGnssAntennaCalControl(C::mip_interface& d } TypedResult defaultGnssAntennaCalControl(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -5197,7 +5197,7 @@ void extract(::microstrain::Buffer& serializer, SetInitialHeading& self) TypedResult setInitialHeading(C::mip_interface& device, float heading) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, heading); diff --git a/src/mip/definitions/commands_filter.h b/src/mip/definitions/commands_filter.h index 778acc061..6b98182d1 100644 --- a/src/mip/definitions/commands_filter.h +++ b/src/mip/definitions/commands_filter.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_filter.hpp b/src/mip/definitions/commands_filter.hpp index fe38fd00f..0cbfb8b1e 100644 --- a/src/mip/definitions/commands_filter.hpp +++ b/src/mip/definitions/commands_filter.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_gnss.cpp b/src/mip/definitions/commands_gnss.cpp index 05fa22987..ead46ca62 100644 --- a/src/mip/definitions/commands_gnss.cpp +++ b/src/mip/definitions/commands_gnss.cpp @@ -79,12 +79,12 @@ void extract(::microstrain::Buffer& serializer, ReceiverInfo::Info& self) TypedResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8_t numReceiversOutMax, ReceiverInfo::Info* receiverInfoOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LIST_RECEIVERS, NULL, 0, REPLY_LIST_RECEIVERS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -94,7 +94,7 @@ TypedResult receiverInfo(C::mip_interface& device, uint8_t* numRec extract(deserializer, receiverInfoOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -168,7 +168,7 @@ void extract(::microstrain::Buffer& serializer, SignalConfiguration::Response& s TypedResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -190,7 +190,7 @@ TypedResult writeSignalConfiguration(C::mip_interface& devi } TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -199,7 +199,7 @@ TypedResult readSignalConfiguration(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_SIGNAL_CONFIGURATION, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -220,13 +220,13 @@ TypedResult readSignalConfiguration(C::mip_interface& devic extract(deserializer, reservedOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveSignalConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -236,7 +236,7 @@ TypedResult saveSignalConfiguration(C::mip_interface& devic } TypedResult loadSignalConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -246,7 +246,7 @@ TypedResult loadSignalConfiguration(C::mip_interface& devic } TypedResult defaultSignalConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -300,7 +300,7 @@ void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration::Response TypedResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -316,7 +316,7 @@ TypedResult writeRtkDongleConfiguration(C::mip_interface } TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -325,7 +325,7 @@ TypedResult readRtkDongleConfiguration(C::mip_interface& uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { ::microstrain::Buffer deserializer(buffer, responseLength); @@ -337,13 +337,13 @@ TypedResult readRtkDongleConfiguration(C::mip_interface& extract(deserializer, reservedOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveRtkDongleConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -353,7 +353,7 @@ TypedResult saveRtkDongleConfiguration(C::mip_interface& } TypedResult loadRtkDongleConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -363,7 +363,7 @@ TypedResult loadRtkDongleConfiguration(C::mip_interface& } TypedResult defaultRtkDongleConfiguration(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; ::microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); diff --git a/src/mip/definitions/commands_gnss.h b/src/mip/definitions/commands_gnss.h index 9fd75a0ee..34c3c09d4 100644 --- a/src/mip/definitions/commands_gnss.h +++ b/src/mip/definitions/commands_gnss.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_gnss.hpp b/src/mip/definitions/commands_gnss.hpp index d739b187b..6eeb5e109 100644 --- a/src/mip/definitions/commands_gnss.hpp +++ b/src/mip/definitions/commands_gnss.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_rtk.cpp b/src/mip/definitions/commands_rtk.cpp index 1540615fd..6333fa2df 100644 --- a/src/mip/definitions/commands_rtk.cpp +++ b/src/mip/definitions/commands_rtk.cpp @@ -53,12 +53,12 @@ void extract(::microstrain::Buffer& serializer, GetStatusFlags::Response& self) TypedResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_STATUS_FLAGS, NULL, 0, REPLY_GET_STATUS_FLAGS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -66,7 +66,7 @@ TypedResult getStatusFlags(C::mip_interface& device, GetStatusFl extract(deserializer, *flagsOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -96,12 +96,12 @@ void extract(::microstrain::Buffer& serializer, GetImei::Response& self) TypedResult getImei(C::mip_interface& device, char* imeiOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_IMEI, NULL, 0, REPLY_GET_IMEI, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -110,7 +110,7 @@ TypedResult getImei(C::mip_interface& device, char* imeiOut) extract(deserializer, imeiOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -140,12 +140,12 @@ void extract(::microstrain::Buffer& serializer, GetImsi::Response& self) TypedResult getImsi(C::mip_interface& device, char* imsiOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_IMSI, NULL, 0, REPLY_GET_IMSI, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -154,7 +154,7 @@ TypedResult getImsi(C::mip_interface& device, char* imsiOut) extract(deserializer, imsiOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -184,12 +184,12 @@ void extract(::microstrain::Buffer& serializer, GetIccid::Response& self) TypedResult getIccid(C::mip_interface& device, char* iccidOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_ICCID, NULL, 0, REPLY_GET_ICCID, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -198,7 +198,7 @@ TypedResult getIccid(C::mip_interface& device, char* iccidOut) extract(deserializer, iccidOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -236,7 +236,7 @@ void extract(::microstrain::Buffer& serializer, ConnectedDeviceType::Response& s TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -248,7 +248,7 @@ TypedResult writeConnectedDeviceType(C::mip_interface& devi } TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -257,7 +257,7 @@ TypedResult readConnectedDeviceType(C::mip_interface& devic uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length(), REPLY_CONNECTED_DEVICE_TYPE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -265,13 +265,13 @@ TypedResult readConnectedDeviceType(C::mip_interface& devic extract(deserializer, *devtypeOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult saveConnectedDeviceType(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); @@ -281,7 +281,7 @@ TypedResult saveConnectedDeviceType(C::mip_interface& devic } TypedResult loadConnectedDeviceType(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); @@ -291,7 +291,7 @@ TypedResult loadConnectedDeviceType(C::mip_interface& devic } TypedResult defaultConnectedDeviceType(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); @@ -325,12 +325,12 @@ void extract(::microstrain::Buffer& serializer, GetActCode::Response& self) TypedResult getActCode(C::mip_interface& device, char* activationcodeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_ACT_CODE, NULL, 0, REPLY_GET_ACT_CODE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -339,7 +339,7 @@ TypedResult getActCode(C::mip_interface& device, char* activationcod extract(deserializer, activationcodeOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -369,12 +369,12 @@ void extract(::microstrain::Buffer& serializer, GetModemFirmwareVersion::Respons TypedResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_MODEM_FIRMWARE_VERSION, NULL, 0, REPLY_GET_MODEM_FIRMWARE_VERSION, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -383,7 +383,7 @@ TypedResult getModemFirmwareVersion(C::mip_interface& d extract(deserializer, modemfirmwareversionOut[i]); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -419,12 +419,12 @@ void extract(::microstrain::Buffer& serializer, GetRssi::Response& self) TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_RSSI, NULL, 0, REPLY_GET_RSSI, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -438,7 +438,7 @@ TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* extract(deserializer, *signalqualityOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -482,7 +482,7 @@ void extract(::microstrain::Buffer& serializer, ServiceStatus::Response& self) TypedResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* receivedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, reserved1); @@ -494,7 +494,7 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SERVICE_STATUS, buffer, (uint8_t)serializer.length(), REPLY_SERVICE_STATUS, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -511,7 +511,7 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese extract(deserializer, *lastbytestimeOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } @@ -528,7 +528,7 @@ void extract(::microstrain::Buffer& serializer, ProdEraseStorage& self) TypedResult prodEraseStorage(C::mip_interface& device, MediaSelector media) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, media); @@ -566,7 +566,7 @@ void extract(::microstrain::Buffer& serializer, LedControl& self) TypedResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); assert(primarycolor || (3 == 0)); diff --git a/src/mip/definitions/commands_rtk.h b/src/mip/definitions/commands_rtk.h index 5c4b8e0e8..4381ba91b 100644 --- a/src/mip/definitions/commands_rtk.h +++ b/src/mip/definitions/commands_rtk.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_rtk.hpp b/src/mip/definitions/commands_rtk.hpp index c99afba94..022ba181e 100644 --- a/src/mip/definitions/commands_rtk.hpp +++ b/src/mip/definitions/commands_rtk.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_system.cpp b/src/mip/definitions/commands_system.cpp index f1445e807..ac9257391 100644 --- a/src/mip/definitions/commands_system.cpp +++ b/src/mip/definitions/commands_system.cpp @@ -63,7 +63,7 @@ void extract(::microstrain::Buffer& serializer, CommMode::Response& self) TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); @@ -75,7 +75,7 @@ TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) } TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); @@ -84,7 +84,7 @@ TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.length(), REPLY_COM_MODE, buffer, &responseLength); - if( result == MIP_ACK_OK ) + if( result == CmdResult::ACK_OK ) { microstrain::Buffer deserializer(buffer, responseLength); @@ -92,13 +92,13 @@ TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) extract(deserializer, *modeOut); if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; + result = CmdResult::STATUS_ERROR; } return result; } TypedResult defaultCommMode(C::mip_interface& device) { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain::Buffer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); diff --git a/src/mip/definitions/commands_system.h b/src/mip/definitions/commands_system.h index 0442a361e..5219efcc1 100644 --- a/src/mip/definitions/commands_system.h +++ b/src/mip/definitions/commands_system.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/commands_system.hpp b/src/mip/definitions/commands_system.hpp index 306df2492..402e4657e 100644 --- a/src/mip/definitions/commands_system.hpp +++ b/src/mip/definitions/commands_system.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/common.c b/src/mip/definitions/common.c index bc12983f0..80c752de2 100644 --- a/src/mip/definitions/common.c +++ b/src/mip/definitions/common.c @@ -20,12 +20,12 @@ void extract_mip_descriptor_rate(microstrain_serializer* serializer, mip_descrip void insert_##name(microstrain_serializer* serializer, const name self) \ { \ for(unsigned int i=0; i #include #include #include #ifdef __cplusplus - -#include "microstrain/common/buffer.hpp" - #include #include #include namespace mip { namespace C { -using namespace ::microstrain::C; extern "C" { +using microstrain::C::microstrain_serializer; #endif // __cplusplus typedef struct mip_descriptor_rate @@ -26,309 +23,27 @@ typedef struct mip_descriptor_rate uint16_t decimation; } mip_descriptor_rate; -void insert_mip_descriptor_rate(microstrain_serializer* serializer, const mip_descriptor_rate* self); -void extract_mip_descriptor_rate(microstrain_serializer* serializer, mip_descriptor_rate* self); +void insert_mip_descriptor_rate(microstrain_serializer *serializer, const mip_descriptor_rate *self); +void extract_mip_descriptor_rate(microstrain_serializer *serializer, mip_descriptor_rate *self); -#define DECLARE_MIP_VECTOR_TYPE(n,type,name) \ +#define DECLARE_MIP_VECTOR_TYPE(n, type, name) \ typedef type name[n]; \ \ void insert_##name(microstrain_serializer* serializer, const name self); \ void extract_##name(microstrain_serializer* serializer, name self); -DECLARE_MIP_VECTOR_TYPE(3, float, mip_vector3f) -DECLARE_MIP_VECTOR_TYPE(4, float, mip_vector4f) -DECLARE_MIP_VECTOR_TYPE(9, float, mip_matrix3f) +DECLARE_MIP_VECTOR_TYPE(3, float, mip_vector3f) +DECLARE_MIP_VECTOR_TYPE(4, float, mip_vector4f) +DECLARE_MIP_VECTOR_TYPE(9, float, mip_matrix3f) DECLARE_MIP_VECTOR_TYPE(3, double, mip_vector3d) DECLARE_MIP_VECTOR_TYPE(4, double, mip_vector4d) DECLARE_MIP_VECTOR_TYPE(9, double, mip_matrix3d) -DECLARE_MIP_VECTOR_TYPE(4, float, mip_quatf) +DECLARE_MIP_VECTOR_TYPE(4, float, mip_quatf) #undef DECLARE_MIP_VECTOR_TYPE -//typedef struct mip_vector3f -//{ -// float m_data[3]; -//} mip_vector3f; -// -//void insert_mip_vector3(microstrain_serializer* serializer, const mip_vector3* self); -//void extract_mip_vector3(microstrain_serializer* serializer, mip_vector3* self); -// -//typedef struct mip_vector4f -//{ -// float m_data[4]; -//} mip_vector4f; -// -//void insert_mip_vector3(microstrain_serializer* serializer, const mip_vector3* self); -//void extract_mip_vector3(microstrain_serializer* serializer, mip_vector3* self); -// -//typedef struct mip_matrix3 -//{ -// float m[9]; -//} mip_matrix3; -// -//void insert_mip_matrix3(microstrain_serializer* serializer, const mip_matrix3* self); -//void extract_mip_matrix3(microstrain_serializer* serializer, mip_matrix3* self); - - #ifdef __cplusplus - } // extern "C" -} // namespace "C" - - -using DescriptorRate = C::mip_descriptor_rate; - -inline size_t insert(::microstrain::Buffer& buffer, const DescriptorRate& self) { return buffer.insert(self.descriptor, self.decimation); } -inline size_t extract(::microstrain::Buffer& buffer, DescriptorRate& self) { return buffer.extract(self.descriptor, self.decimation); } - - -////////////////////////////////////////////////////////////////////////////////// -///@brief Vector is a wrapper around an array of some type T, usually float or double. -/// -/// Implicit conversion to/from C-style pointers is provided to allow simple -/// integration with code using plain arrays. -/// -template -struct Vector -{ - /// Default constructor, no initialization. - Vector() {} - - /// Set all elements to this value (typically 0). - ///@param value - template - Vector(U value) { fill(value); } - - /// Construct from a C array of known size. - ///@param ptr - template - Vector(const U (&ptr)[N]) { copyFrom(ptr, N); } - - /// Construct from a C array of different size (smaller or larger vector). - ///@param ptr - template - explicit Vector(const U (&ptr)[M]) { static_assert(M>=N, "Input array is too small"); copyFrom(ptr, M); } - - /// Construct from a pointer and size. - ///@param ptr Pointer to data to copy. Can be NULL if n==0. - ///@param n Number of elements to copy. Clamped to N. - template - explicit Vector(const U* ptr, size_t n) { copyFrom(ptr, n); } - - /// Construct from individual elements or a braced init list. - ///@param u The first value (typically X). - ///@param v The value value (typically Y). - ///@param rest Additional optional values (typically none, Z, or Z and W). - template - Vector(U u, V v, Rest... rest) : m_data{u, v, rest...} {} - - /// Copy constructor. - Vector(const Vector&) = default; - - /// Assignment operator. - Vector& operator=(const Vector&) = default; - - /// Assignment operator from different type (e.g. float to double). - template - Vector& operator=(const Vector& other) { copyFrom(other, N); return *this; } - - - typedef T Array[N]; - -#if _MSC_VER < 1930 - // MSVC 2017 has a bug which causes operator[] to be ambiguous. - // See https://stackoverflow.com/questions/48250560/msvc-error-c2593-when-overloading-const-and-non-const-conversion-operator-return - operator T*() { return m_data; } - operator const T*() const { return m_data; } -#else - /// Implicitly convert to a C-style array (rather than a pointer) so size information is preserved. - operator Array&() { return m_data; } - operator const Array&() const { return m_data; } -#endif - - /// Explicitly convert to a C-style array. - Array& data() { return m_data; } - const Array& data() const { return m_data; } - - /// Fill all elements with a given value. - template - void fill(U value) { for(size_t i=0; i - void copyFrom(const U* ptr, size_t n) { if(n>N) n=N; for(size_t i=0; i; -using Vector4f = Vector; -using Matrix3f = Vector; -using Vector3d = Vector; -using Vector4d = Vector; -using Matrix3d = Vector; - -using Quatf = Vector4f; - -template -void insert(::microstrain::Buffer& serializer, const Vector& v) { for(size_t i=0; i -void extract(::microstrain::Buffer& serializer, Vector& v) { for(size_t i=0; i -//class Vector -//{ -//public: -// Vector() { *this = T(0); } -// Vector(const Vector&) = default; -// Vector(const T (&ptr)[N]) { copyFrom(ptr); } -// -// Vector& operator=(const Vector&) = default; -// Vector& operator=(const T* ptr) { copyFrom(ptr); return this; } -// Vector& operator=(T value) { for(size_t i=0; i -// void copyFrom(const U* ptr) { for(size_t i=0; i -// void copyTo(U* ptr) const { for(size_t i=0; i -//class Vector2 : public Vector -//{ -// using Vector::Vector; -// -// template -// Vector2(U x_, U y_) { x()=x_; y()=y_;} -// -// T& x() { return this->m_data[0]; } -// T& y() { return this->m_data[1]; } -// -// T x() const { return this->m_data[0]; } -// T y() const { return this->m_data[1]; } -//}; -// -/////@brief A 3D vector which provides .x(), .y() and .z() accessors. -///// -//template -//class Vector3 : public Vector -//{ -// //using Vector::Vector; -// template -// Vector3(const U* ptr) { copyFrom(ptr); } -// -// template -// Vector3(U x_, U y_, U z_) { x()=x_; y()=y_; z()=z_; } -// -// T& x() { return this->m_data[0]; } -// T& y() { return this->m_data[1]; } -// T& z() { return this->m_data[2]; } -// -// T x() const { return this->m_data[0]; } -// T y() const { return this->m_data[1]; } -// T z() const { return this->m_data[2]; } -//}; -// -/////@brief A 4D vector which provides .x(), .y(), .z(), and .w() accessors. -///// -//template -//class Vector4 : public Vector -//{ -// using Vector::Vector; -// -// template -// Vector4(U x_, U y_, U z_, U w_) { x()=x_; y()=y_; z()=z_; w()=w_; } -// -// T& x() { return this->m_data[0]; } -// T& y() { return this->m_data[1]; } -// T& z() { return this->m_data[2]; } -// T& w() { return this->m_data[3]; } -// -// T x() const { return this->m_data[0]; } -// T y() const { return this->m_data[1]; } -// T z() const { return this->m_data[2]; } -// T w() const { return this->m_data[3]; } -//}; -// -/////@brief A quaternion which provides .x(), .y(), .z(), and .w() accessors. -///// -//template -//class Quaternion : public Vector4 -//{ -// using Vector4::Vector; -//}; -// -//typedef Vector2 Vector2f; -//typedef Vector3 Vector3f; -//typedef Vector4 Vector4f; -// -//typedef Vector2 Vector2d; -//typedef Vector3 Vector3d; -//typedef Vector4 Vector4d; -// -//typedef Quaternion Quatf; -//typedef Vector Matrix3f; -// -//template -//void insert(Buffer& serializer, const Vector& self) -//{ -// for(size_t i=0; i -//void extract(Buffer& serializer, Vector& self) -//{ -// for(size_t i=0; i -//void insert(Buffer& serializer, const Quaternion& self) -//{ -// insert(serializer, self.w()); // w comes first in mip -// insert(serializer, self.x()); -// insert(serializer, self.y()); -// insert(serializer, self.z()); -//} -// -//template -//void extract(Buffer& serializer, Quaternion& self) -//{ -// extract(serializer, self.w()); // w comes first in mip -// extract(serializer, self.x()); -// extract(serializer, self.y()); -// extract(serializer, self.z()); -//} - - +} // namespace C } // namespace mip - #endif // __cplusplus diff --git a/src/mip/definitions/common.hpp b/src/mip/definitions/common.hpp new file mode 100644 index 000000000..3706dda96 --- /dev/null +++ b/src/mip/definitions/common.hpp @@ -0,0 +1,124 @@ +#pragma once + +#include + + +namespace mip +{ +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ + +struct DescriptorRate +{ + uint8_t descriptor; + uint16_t decimation; +}; + +inline size_t insert(microstrain::Buffer& buffer, const DescriptorRate& self) { return buffer.insert(self.descriptor, self.decimation); } +inline size_t extract(microstrain::Buffer& buffer, DescriptorRate& self) { return buffer.extract(self.descriptor, self.decimation); } + + +////////////////////////////////////////////////////////////////////////////////// +///@brief Vector is a wrapper around an array of some type T, usually float or double. +/// +/// Implicit conversion to/from C-style pointers is provided to allow simple +/// integration with code using plain arrays. +/// +template +struct Vector +{ + /// Default constructor, no initialization. + Vector() {} + + /// Set all elements to this value (typically 0). + ///@param value + template + Vector(U value) { fill(value); } + + /// Construct from a C array of known size. + ///@param ptr + template + Vector(const U (&ptr)[N]) { copyFrom(ptr, N); } + + /// Construct from a C array of different size (smaller or larger vector). + ///@param ptr + template + explicit Vector(const U (&ptr)[M]) { static_assert(M>=N, "Input array is too small"); copyFrom(ptr, M); } + + /// Construct from a pointer and size. + ///@param ptr Pointer to data to copy. Can be NULL if n==0. + ///@param n Number of elements to copy. Clamped to N. + template + explicit Vector(const U* ptr, size_t n) { copyFrom(ptr, n); } + + /// Construct from individual elements or a braced init list. + ///@param u The first value (typically X). + ///@param v The value value (typically Y). + ///@param rest Additional optional values (typically none, Z, or Z and W). + template + Vector(U u, V v, Rest... rest) : m_data{u, v, rest...} {} + + /// Copy constructor. + Vector(const Vector&) = default; + + /// Assignment operator. + Vector& operator=(const Vector&) = default; + + /// Assignment operator from different type (e.g. float to double). + template + Vector& operator=(const Vector& other) { copyFrom(other, N); return *this; } + + + typedef T Array[N]; + +#if _MSC_VER < 1930 + // MSVC 2017 has a bug which causes operator[] to be ambiguous. + // See https://stackoverflow.com/questions/48250560/msvc-error-c2593-when-overloading-const-and-non-const-conversion-operator-return + operator T*() { return m_data; } + operator const T*() const { return m_data; } +#else + /// Implicitly convert to a C-style array (rather than a pointer) so size information is preserved. + operator Array&() { return m_data; } + operator const Array&() const { return m_data; } +#endif + + /// Explicitly convert to a C-style array. + Array& data() { return m_data; } + const Array& data() const { return m_data; } + + /// Fill all elements with a given value. + template + void fill(U value) { for(size_t i=0; i + void copyFrom(const U* ptr, size_t n) { if(n>N) n=N; for(size_t i=0; i; +using Vector4f = Vector; +using Matrix3f = Vector; +using Vector3d = Vector; +using Vector4d = Vector; +using Matrix3d = Vector; + +using Quatf = Vector4f; + +template +void insert(::microstrain::Buffer& serializer, const Vector& v) { for(size_t i=0; i +void extract(::microstrain::Buffer& serializer, Vector& v) { for(size_t i=0; i diff --git a/src/mip/definitions/data_filter.hpp b/src/mip/definitions/data_filter.hpp index 04dd58e77..640643316 100644 --- a/src/mip/definitions/data_filter.hpp +++ b/src/mip/definitions/data_filter.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/data_gnss.h b/src/mip/definitions/data_gnss.h index 4b2cc9cb0..6e5613e20 100644 --- a/src/mip/definitions/data_gnss.h +++ b/src/mip/definitions/data_gnss.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/data_gnss.hpp b/src/mip/definitions/data_gnss.hpp index 2d8de607e..64fa0af5f 100644 --- a/src/mip/definitions/data_gnss.hpp +++ b/src/mip/definitions/data_gnss.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/data_sensor.h b/src/mip/definitions/data_sensor.h index 0d833b545..9cbfe03e3 100644 --- a/src/mip/definitions/data_sensor.h +++ b/src/mip/definitions/data_sensor.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/data_sensor.hpp b/src/mip/definitions/data_sensor.hpp index d7fd48366..f64032adf 100644 --- a/src/mip/definitions/data_sensor.hpp +++ b/src/mip/definitions/data_sensor.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/data_shared.h b/src/mip/definitions/data_shared.h index adaf86cb1..a597d80da 100644 --- a/src/mip/definitions/data_shared.h +++ b/src/mip/definitions/data_shared.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/data_shared.hpp b/src/mip/definitions/data_shared.hpp index 1c37600e1..6b217a597 100644 --- a/src/mip/definitions/data_shared.hpp +++ b/src/mip/definitions/data_shared.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/definitions/data_system.h b/src/mip/definitions/data_system.h index 8296188dc..c854837bd 100644 --- a/src/mip/definitions/data_system.h +++ b/src/mip/definitions/data_system.h @@ -1,7 +1,7 @@ #pragma once #include "common.h" -#include "descriptors.h" +#include "mip/mip_descriptors.h" #include "../mip_result.h" #include diff --git a/src/mip/definitions/data_system.hpp b/src/mip/definitions/data_system.hpp index 5bec37524..cc78e7499 100644 --- a/src/mip/definitions/data_system.hpp +++ b/src/mip/definitions/data_system.hpp @@ -1,7 +1,7 @@ #pragma once -#include "common.h" -#include "descriptors.h" +#include "common.hpp" +#include "mip/mip_descriptors.hpp" #include "../mip_result.h" #include diff --git a/src/mip/mip.hpp b/src/mip/mip.hpp index 8f5c4398f..df6a9d389 100644 --- a/src/mip/mip.hpp +++ b/src/mip/mip.hpp @@ -1,18 +1,6 @@ #pragma once -#include - -#include -#include - -#include "mip_packet.h" -#include "mip_field.h" -#include "mip_parser.h" -#include "mip_offsets.h" -#include "definitions/descriptors.h" -#include "mip_types.h" - -#include +#include "mip_interface.hpp" //////////////////////////////////////////////////////////////////////////////// ///@defgroup mip_cpp MIP C++ API @@ -30,503 +18,5 @@ /// namespace mip { - -template struct MipFieldInfo; - -//////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_cpp -///@{ - -//////////////////////////////////////////////////////////////////////////////// -///@brief C++ class representing a MIP field. -/// -/// This is a thin wrapper around the C mip_field struct. -/// -class Field : public C::mip_field -{ -public: - /// Construct an empty MIP field. - Field() { C::mip_field::_payload=nullptr; C::mip_field::_payload_length=0; C::mip_field::_field_descriptor=0x00; C::mip_field::_descriptor_set=0x00; C::mip_field::_remaining_length=0; } - ///@copydoc mip_field_init() - Field(uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) { C::mip_field_init(this, descriptor_set, field_descriptor, payload, payload_length); } - ///@copydoc mip_field_from_header_ptr() - Field(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set) { *this = C::mip_field_from_header_ptr(header, total_length, descriptor_set); } - /// Creates a %Field class from the mip_field C struct. - Field(const C::mip_field& other) { std::memcpy(static_cast(this), &other, sizeof(C::mip_field)); } - - // - // C function wrappers - // - - ///@copydoc mip_field_descriptor_set - uint8_t descriptorSet() const { return C::mip_field_descriptor_set(this); } - ///@copydoc mip_field_field_descriptor - uint8_t fieldDescriptor() const { return C::mip_field_field_descriptor(this); } - ///@brief Returns the descriptor set and field descriptor. - CompositeDescriptor descriptor() const { return {descriptorSet(), fieldDescriptor()}; } - ///@copydoc mip_field_payload_length - uint8_t payloadLength() const { return C::mip_field_payload_length(this); } - ///@copydoc mip_field_payload - const uint8_t* payload() const { return C::mip_field_payload(this); } - - ///@brief Index the payload at the given location. - ///@param index - ///@returns payload byte - uint8_t payload(unsigned int index) const { return payload()[index]; } - - uint8_t operator[](unsigned int index) const { return payload(index); } - - ///@copydoc mip_field_is_valid - bool isValid() const { return C::mip_field_is_valid(this); } - - ///@copydoc mip_field_next_after - Field nextAfter() const { return C::mip_field_next_after(this); } - ///@copydoc mip_field_next - bool next() { return C::mip_field_next(this); } - - // - // Additional functions which have no C equivalent - // - - ///@brief Deserializes the field data to specific field struct. - /// - ///@tparam FieldType Any field class from a file in the mip/definitions directory. - /// - ///@param[out] field A reference to the field struct to be filled out. Valid - /// only if the function returns true. - ///@param exact_size If true, the function fails if any bytes remain after deserialization. - /// - ///@returns True if the field was successfully deserialized, or false if the field contains - /// too few bytes (or to many if exact_size is specified). The field data is not - /// valid unless this function returns true. - template - bool extract(FieldType& field, bool exact_size=true) const { return mip::extract(field, payload(), payloadLength(), 0, exact_size); } - - - ///@brief Determines if the field holds data (and not a command, reply, or response). - bool isData() const { return isDataDescriptorSet(descriptorSet()); } - - ///@brief Determines if the field is from a command descriptor set (a command, reply, or response field). - bool isCommandSet() const { return isCommandDescriptorSet(descriptorSet()); } - - ///@brief Determines if the field holds a command. - bool isCommand() const { return isCommandSet() && isCommandFieldDescriptor(fieldDescriptor()); } - - ///@brief Determines if the field holds an ack/nack reply code. - bool isReply() const { return isCommandSet() && isReplyFieldDescriptor(fieldDescriptor()) && payloadLength()==2; } - - ///@brief Determines if the field holds command response data (not an ack/nack reply). - bool isResponse() const { return isCommandSet() && isResponseFieldDescriptor(fieldDescriptor()); } -}; - - -//////////////////////////////////////////////////////////////////////////////// -///@brief C++ class representing a MIP PacketRef. -/// -/// This is a thin wrapper around the mip_packet C structure. Like the C -/// version, it does not contain or own the data buffer. Any of the C functions -/// can be used with the C++ packet class because it inherits from the C struct. -/// -/// Fields may be iterated over using the C-style methods, with an iterator, or -/// with a range-based for loop: -///@code{.cpp} -/// for(PacketRef::Iterator iter = packet.begin(); iter != packet.end(); ++iter) { ... } -/// for(Field field : packet) { ... } -///@endcode -/// -class PacketRef : public C::mip_packet -{ -public: - class FieldIterator; - -public: - ///@copydoc mip::C::mip_packet_create - PacketRef(uint8_t* buffer, size_t bufferSize, uint8_t descriptorSet) { C::mip_packet_create(this, buffer, bufferSize, descriptorSet); } - ///@copydoc mip_packet_from_buffer - PacketRef(uint8_t* buffer, size_t length) { C::mip_packet_from_buffer(this, buffer, length); } - /// Constructs a C++ %PacketRef class from the base C object. - PacketRef(const C::mip_packet* other) { std::memcpy(static_cast(this), other, sizeof(*this)); } - /// Constructs a C++ %PacketRef class from the base C object. - PacketRef(const C::mip_packet& other) { std::memcpy(static_cast(this), &other, sizeof(*this)); } - - - // - // C function wrappers - // - - uint8_t descriptorSet() const { return C::mip_packet_descriptor_set(this); } ///<@copydoc mip::C::mip_packet_descriptor_set - uint_least16_t totalLength() const { return C::mip_packet_total_length(this); } ///<@copydoc mip::C::mip_packet_total_length - uint8_t payloadLength() const { return C::mip_packet_payload_length(this); } ///<@copydoc mip::C::mip_packet_payload_length - - bool isData() const { return C::mip_packet_is_data(this); } - - const uint8_t* pointer() const { return C::mip_packet_pointer(this); } ///<@copydoc mip::C::mip_packet_pointer - const uint8_t* payload() const { return C::mip_packet_payload(this); } ///<@copydoc mip::C::mip_packet_payload - - uint16_t checksumValue() const { return C::mip_packet_checksum_value(this); } ///<@copydoc mip::C::mip_packet_checksum_value - uint16_t computeChecksum() const { return C::mip_packet_compute_checksum(this); } ///<@copydoc mip::C::mip_packet_compute_checksum - - bool isSane() const { return C::mip_packet_is_sane(this); } ///<@copydoc mip::C::mip_packet_is_sane - bool isValid() const { return C::mip_packet_is_valid(this); } ///<@copydoc mip::C::mip_packet_is_valid - bool isEmpty() const { return C::mip_packet_is_empty(this); } ///<@copydoc mip::C::mip_packet_is_empty - - uint_least16_t bufferSize() const { return C::mip_packet_buffer_size(this); } ///<@copydoc mip::C::mip_packet_buffer_size - int remainingSpace() const { return C::mip_packet_remaining_space(this); } ///<@copydoc mip::C::mip_packet_remaining_space - - bool addField(uint8_t fieldDescriptor, const uint8_t* payload, uint8_t payloadLength) { return C::mip_packet_add_field(this, fieldDescriptor, payload, payloadLength); } ///<@copydoc mip::C::mip_packet_add_field - microstrain::Buffer createField(uint8_t fieldDescriptor, uint8_t length) { uint8_t* ptr; if(C::mip_packet_alloc_field(this, fieldDescriptor, length, &ptr) < 0) length=0; return microstrain::Buffer{ptr, length}; } - //std::tuple createField(uint8_t fieldDescriptor) { uint8_t* ptr; int max_size = C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr); return max_size >= 0 ? std::make_tuple(ptr, max_size) : std::make_tuple(nullptr, 0); } ///<@copydoc mip::C::mip_packet_alloc_field - //int finishLastField(uint8_t* payloadPtr, uint8_t newPayloadLength) { return C::mip_packet_realloc_last_field(this, payloadPtr, newPayloadLength); } ///<@copydoc mip::C::mip_packet_realloc_last_field - //int cancelLastField(uint8_t* payloadPtr) { return C::mip_packet_cancel_last_field(this, payloadPtr); } ///<@copydoc mip::C::mip_packet_cancel_last_field - - class AllocatedField : public microstrain::Buffer - { - public: - AllocatedField(mip::PacketRef& packet, uint8_t* buffer, size_t space) : Buffer(buffer, space), m_packet(packet) {} - //AllocatedField(const AllocatedField&) = delete; - AllocatedField& operator=(const AllocatedField&) = delete; - - bool commit() - { - bool ok = isOk(); - - if(ok) - C::mip_packet_realloc_last_field(&m_packet, basePointer(), length()); - else - C::mip_packet_cancel_last_field(&m_packet, basePointer()); - - return ok; - } - - private: - PacketRef& m_packet; - }; - - AllocatedField createField(uint8_t fieldDescriptor) { uint8_t* ptr; size_t max_size = std::max(0, C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr)); return {*this, ptr, max_size}; } - - void finalize() { C::mip_packet_finalize(this); } ///<@copydoc mip::C::mip_packet_finalize - - void reset(uint8_t descSet) { C::mip_packet_reset(this, descSet); } ///<@copydoc mip::C::mip_packet_reset - void reset() { reset(descriptorSet()); } ///<@brief Resets the packet using the same descriptor set. - - uint8_t operator[](unsigned int index) const { return pointer()[index]; } - - // - // Additional functions which have no C equivalent - // - - /// Returns a forward iterator to the first field in the packet. - /// - FieldIterator begin() const { return firstField(); } - - /// Returns a sentry object representing the end of fields in the packet. - /// -#if __cpp_range_based_for >= 201603 - // After 201603, for loops allow different clases for begin and end. - // Using nullptr is simpler and more efficient than creating an end iterator. - std::nullptr_t end() const { return nullptr; } -#else - FieldIterator end() const { return Field(); } -#endif - - ///@brief Returns the first field in the packet. - /// - /// Subsequent fields can be obtained via the returned Field class, - /// but iteration is best done with begin()/end() or the range-based for loop. - /// - ///@note Packets can be empty, so make sure that the returned field is - /// valid before using it. - /// - ///@returns A Field instance representing the first field (if any). - /// - Field firstField() const { return Field(C::mip_field_first_from_packet(this)); } - - ///@brief Adds a field of the given type to the packet. - /// - ///@tparam FieldType Any field class from a file in the mip/definitions directory. - /// - ///@param field Instance of the field to add to the packet. - ///@param fieldDescriptor If specified, overrides the field descriptor. - /// - ///@returns True if the field was added, false if the packet has insufficient space. - /// - template - bool addField(const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) - { - if( fieldDescriptor == INVALID_FIELD_DESCRIPTOR ) - fieldDescriptor = FieldType::FIELD_DESCRIPTOR; - - AllocatedField buffer = createField(fieldDescriptor); - buffer.insert(field); - return buffer.commit(); - } - - ///@brief Creates a new PacketRef containing a single MIP field from an instance of the field type. - /// - /// This works just like the addField() function but also initializes and finalizes the packet. - /// It is assumed that the field will fit in an empty packet; otherwise the field can't ever be used. - /// The field classes are predefined so this doesn't need runtime checking. - /// - ///@tparam FieldType Any field class from a file in the mip/definitions directory. - /// - ///@param buffer Buffer to hold the packet bytes. - ///@param bufferSize Size of buffer in bytes. - ///@param field Instance of the field to add to the packet. - ///@param fieldDescriptor If specified, overrides the field descriptor. - /// - ///@returns A PacketRef object containing the field. - /// - template - static PacketRef createFromField(uint8_t* buffer, size_t bufferSize, const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) - { - if( fieldDescriptor == INVALID_FIELD_DESCRIPTOR ) - fieldDescriptor = FieldType::FIELD_DESCRIPTOR; - PacketRef packet(buffer, bufferSize, FieldType::DESCRIPTOR_SET); - packet.addField(field, fieldDescriptor); - packet.finalize(); - return packet; - } - - - /// Iterator class for use with the range-based for loop or iterators. - /// - /// You should generally use the begin()/end() functions on the PacketRef - /// class instead of using this class directly. - /// - class FieldIterator - { - public: - /// Empty iterator, which represents the "end" iterator of a packet. - FieldIterator() {} - - /// Create an iterator given the first field to iterate in a packet. - /// Technically this can be any field, not just the first field. - FieldIterator(const Field& first) : mField(first) {} - - /// Comparison between any two iterators. - /// This works even for iterators over different packets, which will - /// never be the same (except all null/end iterators are equivalent). - bool operator==(const FieldIterator& other) const { - // Required to make invalid fields equivalent for range-based for loop - if( !mField.isValid() && !other.mField.isValid() ) - return true; - return mField.descriptorSet() == other.mField.descriptorSet() && mField.fieldDescriptor() == other.mField.fieldDescriptor() && mField.payload() == other.mField.payload(); - } - bool operator!=(const FieldIterator& other) const { return !(*this == other); } - - /// Comparison with std::nullptr is checking if the iterator points to - /// a valid field (i.e. not the end). - bool operator==(std::nullptr_t) const { return !mField.isValid(); } - bool operator!=(std::nullptr_t) const { return mField.isValid(); } - - /// Dereference the iterator as a Field instance. - const Field& operator*() const { return mField; } - - /// Advance to the next field. - FieldIterator& operator++() { mField.next(); return *this; } - - private: - Field mField; - }; - -}; - - -//////////////////////////////////////////////////////////////////////////////// -///@brief A mip packet with a self-contained buffer (useful with std::vector). -/// -template -class SizedPacketBuf : public PacketRef -{ -public: - SizedPacketBuf(uint8_t descriptorSet=INVALID_DESCRIPTOR_SET) : PacketRef(mData, sizeof(mData), descriptorSet) {} - - ///@brief Creates a PacketBuf by copying existing data. - /// - explicit SizedPacketBuf(const uint8_t* data, size_t length) : PacketRef(mData, sizeof(mData)) { copyFrom(data, length); } - explicit SizedPacketBuf(const PacketRef& packet) : PacketRef(mData, sizeof(mData)) { copyFrom(packet); } - - ///@brief Copy constructor - SizedPacketBuf(const SizedPacketBuf& other) : PacketRef(mData, sizeof(mData)) { copyFrom(other); } - - ///@brief Copy constructor (required to put packets into std::vector in some cases). - template - explicit SizedPacketBuf(const SizedPacketBuf& other) : PacketRef(mData, sizeof(mData)) { copyFrom(other); }; - - ///@brief Copy assignment operator - SizedPacketBuf& operator=(const SizedPacketBuf& other) { copyFrom(other); return *this; } - - ///@brief Assignment operator, copies data from another buffer to this one. - template - SizedPacketBuf& operator=(const SizedPacketBuf& other) { copyFrom(other); return *this; } - - ///@brief Create a packet containing just the given field. - /// - ///@tparam FieldType Type of the MIP field. This can't be explicitly specified due to being a constructor. - /// - ///@param field The field object to serialize. - ///@param fieldDescriptor If specified (not INVALID_FIELD_DESCRIPTOR), overrides the field descriptor. - /// - template - SizedPacketBuf(const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) : PacketRef(mData, sizeof(mData)) { createFromField(mData, sizeof(mData), field, fieldDescriptor); } - - - ///@brief Explicitly obtains a reference to the packet data. - /// - PacketRef ref() { return *this; } - - ///@brief Explicitly obtains a const reference to the packet data. - /// - const PacketRef& ref() const { return *this; } - - ///@brief Returns a pointer to the underlying buffer. - /// This is technically the same as PacketRef::pointer but is writable. - uint8_t* buffer() { return mData; } - - ///@brief Copies the data from the pointer to this buffer. The data is not inspected. - /// - ///@param data Pointer to the start of the packet. - ///@param length Total length of the packet. - /// - void copyFrom(const uint8_t* data, size_t length) { assert(length <= sizeof(mData)); std::memcpy(mData, data, length); } - - ///@brief Copies an existing packet. The packet is assumed to be valid (undefined behavior otherwise). - /// - ///@param packet A "sane" (isSane()) mip packet. - /// - void copyFrom(const PacketRef& packet) { assert(packet.isSane()); copyFrom(packet.pointer(), packet.totalLength()); } - - ///@brief Copies this packet to an external buffer. - /// - /// This packet must be sane (see isSane()). Undefined behavior otherwise due to lookup of totalLength(). - /// - ///@param buffer Data is copied into this location. - ///@param maxLength Maximum number of bytes to copy. - /// - ///@returns true if successful. - ///@returns false if maxLength is too short. - /// - bool copyTo(uint8_t* buffer, size_t maxLength) { assert(isSane()); size_t copyLength = this->totalLength(); if(copyLength > maxLength) return false; std::memcpy(buffer, mData, copyLength); return true; } - -private: - uint8_t mData[BufferSize]; -}; - -//////////////////////////////////////////////////////////////////////////////// -///@brief Typedef for SizedPacketBuf of max possible size. -/// -/// Generally you should use this instead of SizedPacketBuf directly, unless you -/// know the maximum size of your packet will be less than PACKET_LENGTH_MAX. -/// -typedef SizedPacketBuf PacketBuf; - - -//////////////////////////////////////////////////////////////////////////////// -///@brief C++ class representing a MIP parser. -/// -/// See @ref parsing_packets -/// -class Parser : public C::mip_parser -{ -public: - ///@copydoc mip::C::mip_parser_init - Parser(uint8_t* buffer, size_t bufferSize, C::mip_packet_callback callback, void* callbackObject, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, callback, callbackObject, timeout); } - ///@copydoc mip::C::mip_parser_init - Parser(uint8_t* buffer, size_t bufferSize, bool (*callback)(void*,const PacketRef*,Timestamp), void* callbackObject, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, (C::mip_packet_callback)callback, callbackObject, timeout); } - - Parser(uint8_t* buffer, size_t bufferSize, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, nullptr, nullptr, timeout); } - - template - void setCallback(T& object); - - ///@copydoc mip::C::mip_parser_reset - void reset() { C::mip_parser_reset(this); } - - ///@copydoc mip::C::mip_parser_parse - size_t parse(const uint8_t* inputBuffer, size_t inputCount, Timestamp timestamp, unsigned int maxPackets=0) { return C::mip_parser_parse(this, inputBuffer, inputCount, timestamp, maxPackets); } - - ///@copydoc mip::C::mip_parser_timeout - Timeout timeout() const { return C::mip_parser_timeout(this); } - ///@copydoc mip::C::mip_parser_set_timeout - void setTimeout(Timeout timeout) { return C::mip_parser_set_timeout(this, timeout); } -}; - - -///@brief Initializes the MIP Parser -/// -/// This version allows binding a member function instead of a C-style callback. -/// Example: -///@code{.cpp} -/// struct MyClass -/// { -/// void handlePacket(const PacketRef& packet, Timeout timeout); -/// }; -/// MyClass myInstance; -/// Parser parser(myInstance); -///@endcode -/// -///@tparam T Class type containing the member function to be called. -///@tparam Callback A pointer to a member function on a T to be called when a -/// packet is parsed. -/// -///@param object -/// Instance of T to call the callback. -/// -template -void Parser::setCallback(T& object) -{ - C::mip_packet_callback callback = [](void* obj, const C::mip_packet* pkt, Timestamp timestamp)->bool - { - return (static_cast(obj)->*Callback)(PacketRef(pkt), timestamp); - }; - - C::mip_parser_set_callback(this, callback, &object); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Read data from a source into the internal parsing buffer. -/// -///@tparam Function -/// A function-like object with the following signature: -/// `bool read(size_t maxCount, size_t* count_out, Timestamp* timestamp_out);` -/// The parameters are as follows: -/// @li buffer - Buffer into which to write data. -/// @li maxCount - The maximum number of bytes to read. -/// @li count_out - Updated with the number of bytes actually read. -/// @li timestamp_out - Updated with the timestamp of the data. -/// -///@param parser -/// -///@param reader -/// A callback function, lambda, or similar which will read data into the -/// buffer and capture the timestamp. It should return true if successful -/// or false otherwise. If it returns false, parsing is skipped. The read -/// function may also throw an exception instead of returning false. -/// -///@param maxPackets -/// Maximum number of packets to parse, just like for Parser::parse(). -/// -///@return Same as the return value of reader. -/// -template -bool parseMipDataFromSource(C::mip_parser& parser, Function reader, size_t maxPackets) -{ - uint8_t* ptr; - size_t maxCount = C::mip_parser_get_write_ptr(&parser, &ptr); - - size_t count; - Timestamp timestamp; - if( !reader(ptr, maxCount, &count, ×tamp) ) - return false; - - assert(count <= maxCount); - - C::mip_parser_process_written(&parser, count, timestamp, maxPackets); - - return true; -} - -///@} -//////////////////////////////////////////////////////////////////////////////// - } // namespace mip + diff --git a/src/mip/mip_all.h b/src/mip/mip_all.h index 84d5b9e5e..6f7e81262 100644 --- a/src/mip/mip_all.h +++ b/src/mip/mip_all.h @@ -8,7 +8,7 @@ #include "mip_offsets.h" #include "mip_packet.h" #include "mip_parser.h" -#include "definitions/descriptors.h" +#include "mip_descriptors.h" //MIP Utils #include "microstrain/common/serialization.h" diff --git a/src/mip/mip_all.hpp b/src/mip/mip_all.hpp index 7df181d63..7fe51b488 100644 --- a/src/mip/mip_all.hpp +++ b/src/mip/mip_all.hpp @@ -1,19 +1,17 @@ #pragma once //MIP Core -#include "mip_cmdqueue.h" -#include "mip_dispatch.h" -#include "mip_field.h" -#include "mip_interface.h" -#include "mip_offsets.h" -#include "mip_packet.h" -#include "mip_parser.h" -#include "definitions/descriptors.h" +#include "mip_cmdqueue.hpp" +#include "mip_dispatch.hpp" +#include "mip_field.hpp" +#include "mip_interface.hpp" +#include "mip_packet.hpp" +#include "mip_parser.hpp" -//MIP Utils -#include "microstrain/common/buffer.hpp" +#include "mip_descriptors.h" //MIP Commands +#include "definitions/commands_aiding.hpp" #include "definitions/commands_base.hpp" #include "definitions/commands_3dm.hpp" #include "definitions/commands_filter.hpp" @@ -28,7 +26,3 @@ #include "definitions/data_sensor.hpp" #include "definitions/data_gnss.hpp" #include "definitions/data_filter.hpp" - -//MIP Helpers -#include "mip.hpp" -#include "mip_device.hpp" diff --git a/src/mip/mip_cmdqueue.hpp b/src/mip/mip_cmdqueue.hpp new file mode 100644 index 000000000..a2eac8d64 --- /dev/null +++ b/src/mip/mip_cmdqueue.hpp @@ -0,0 +1,113 @@ +#pragma once + +#include "mip_cmdqueue.h" + + +#include +#include + + +namespace mip +{ +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief C++ wrapper around a command queue. +/// +struct CmdQueue : public C::mip_cmd_queue +{ + CmdQueue(Timeout baseReplyTimeout=1000) { C::mip_cmd_queue_init(this, baseReplyTimeout); } + ~CmdQueue() { assert(_first_pending_cmd==nullptr); } + + CmdQueue(const CmdQueue&) = delete; + CmdQueue& operator=(const CmdQueue&) = delete; + + void enqueue(C::mip_pending_cmd& cmd) { C::mip_cmd_queue_enqueue(this, &cmd); } + void dequeue(C::mip_pending_cmd& cmd) { C::mip_cmd_queue_dequeue(this, &cmd); } + + void clear() { C::mip_cmd_queue_clear(this); } + + void update(Timestamp now) { C::mip_cmd_queue_update(this, now); } + + void setBaseReplyTimeout(Timeout timeout) { C::mip_cmd_queue_set_base_reply_timeout(this, timeout); } + Timeout baseReplyTimeout() const { return C::mip_cmd_queue_base_reply_timeout(this); } + + void processPacket(const C::mip_packet& packet, Timestamp timestamp) { C::mip_cmd_queue_process_packet(this, &packet, timestamp); } +}; +static_assert(sizeof(CmdQueue) == sizeof(C::mip_cmd_queue), "CmdQueue must not have additional data members."); + + +//////////////////////////////////////////////////////////////////////////////// +///@brief C++ class representing the state of a MIP command. +/// +struct PendingCmd : public C::mip_pending_cmd +{ + ///@brief Create a null pending command in the CmdResult::NONE state. + /// + PendingCmd() { std::memset(static_cast(this), 0, sizeof(C::mip_pending_cmd)); } + + ///@brief Create a pending command for the given descriptor pair. + /// + ///@param descriptorSet MIP descriptor set for the command. + ///@param fieldDescriptor MIP field descriptor for the command. + ///@param additionalTime Optional additional time to allow for the device to process the command. Default 0. + /// + PendingCmd(uint8_t descriptorSet, uint8_t fieldDescriptor, Timeout additionalTime=0) { C::mip_pending_cmd_init_with_timeout(this, descriptorSet, fieldDescriptor, additionalTime); } + + ///@brief Create a pending command with expected response. + /// + ///@param descriptorSet MIP descriptor set for the command. + ///@param fieldDescriptor MIP field descriptor for the command. + ///@param responseDescriptor MIP field descriptor for the response. + ///@param responseBuffer A buffer used for the command response data. Must be big enough for the expected response. You can reuse the buffer used to send the command. + ///@param responseBufferSize Length of responseBuffer in bytes. + ///@param additionalTime Optional additional time to allow for the device to process the command. Default 0. + /// + PendingCmd(uint8_t descriptorSet, uint8_t fieldDescriptor, uint8_t responseDescriptor, uint8_t* responseBuffer, uint8_t responseBufferSize, Timeout additionalTime) { C::mip_pending_cmd_init_full(this, descriptorSet, fieldDescriptor, responseDescriptor, responseBuffer, responseBufferSize, additionalTime); } + + ///@brief Create a pending command given the actual command struct. + /// + ///@param cmd The C++ command struct (this must be the C++ version of the struct, the C struct will not work). It need not be fully populated; this parameter is unused except for its type information. + ///@param additionalTime Optional additional time to allow for the device to process the command. Default 0. + /// + template + PendingCmd(const Cmd& cmd, Timeout additionalTime=0) : PendingCmd(cmd.descriptorSet, cmd.fieldDescriptor, additionalTime) {} + + ///@brief Create a pending command given the actual command struct and a response buffer. + /// + ///@param cmd The C++ command struct (this must be the C++ version of the struct, the C struct will not work). It need not be fully populated; this parameter is unused except for its type information. + ///@param responseBuffer A buffer used for the command response data. Must be big enough for the expected response. You can reuse the buffer used to send the command. + ///@param responseBufferSize Length of responseBuffer in bytes. + ///@param additionalTime Optional additional time to allow for the device to process the command. Default 0. + /// + template + PendingCmd(const Cmd& cmd, uint8_t* responseBuffer, uint8_t responseBufferSize, Timeout additionalTime=0) : PendingCmd(Cmd::DESCRIPTOR_SET, Cmd::FIELD_DESCRIPTOR, Cmd::Response::FIELD_DESCRIPTOR, responseBuffer, responseBufferSize, additionalTime) {} + + ///@brief Disable copying and moving. Once queued, a pending command must remain in the same memory location. + /// + PendingCmd(const PendingCmd&) = delete; + PendingCmd& operator=(const PendingCmd&) = delete; + + ///@brief Sanity check that the PendingCmd is not deallocated while still in the queue. + /// + ~PendingCmd() { CmdResult tmp = status(); assert(tmp.isFinished() || tmp==CmdResult::STATUS_NONE); (void)tmp; } + + ///@brief Gets the status of the pending command. + /// + CmdResult status() const { return C::mip_pending_cmd_status(this); } + + ///@copydoc mip::C::mip_pending_cmd_response_descriptor + uint8_t responseDescriptor() const { return C::mip_pending_cmd_response_descriptor(this); } + + ///@copydoc mip::C::mip_pending_cmd_response + const uint8_t* response() const { return C::mip_pending_cmd_response(this); } + + ///@copydoc mip::C::mip_pending_cmd_response_length + uint8_t responseLength() const { return C::mip_pending_cmd_response_length(this); } +}; + +///@} +//////////////////////////////////////////////////////////////////////////////// +} // namespace mip diff --git a/src/mip/definitions/descriptors.c b/src/mip/mip_descriptors.c similarity index 99% rename from src/mip/definitions/descriptors.c rename to src/mip/mip_descriptors.c index 8547f195d..4a65112b9 100644 --- a/src/mip/definitions/descriptors.c +++ b/src/mip/mip_descriptors.c @@ -1,5 +1,5 @@ -#include "descriptors.h" +#include "mip_descriptors.h" #include "microstrain/common/serialization.h" diff --git a/src/mip/mip_descriptors.h b/src/mip/mip_descriptors.h new file mode 100644 index 000000000..2d5c3b264 --- /dev/null +++ b/src/mip/mip_descriptors.h @@ -0,0 +1,65 @@ +#pragma once + +#include +#include +#include +#include "microstrain/common/serialization.h" +#include "mip_result.h" + +#ifdef __cplusplus +#include "microstrain/common/buffer.hpp" + +#include +#include +#include + +namespace mip { +namespace C { +using ::microstrain::C::microstrain_serializer; +extern "C" { +#endif // __cplusplus + +enum { + MIP_INVALID_DESCRIPTOR_SET = 0x00, + MIP_DATA_DESCRIPTOR_SET_START = 0x80, + MIP_RESERVED_DESCRIPTOR_SET_START = 0xF0, + + MIP_INVALID_FIELD_DESCRIPTOR = 0x00, + MIP_REPLY_DESCRIPTOR = 0xF1, + MIP_RESERVED_DESCRIPTOR_START = 0xF0, + MIP_RESPONSE_DESCRIPTOR_START = 0x80, + + MIP_SHARED_DATA_FIELD_DESCRIPTOR_START = 0xD0, +}; + +bool mip_is_valid_descriptor_set(uint8_t descriptor_set); +bool mip_is_data_descriptor_set(uint8_t descriptor_set); +bool mip_is_cmd_descriptor_set(uint8_t descriptor_set); +bool mip_is_reserved_descriptor_set(uint8_t descriptor_set); +bool mip_is_gnss_data_descriptor_set(uint8_t descriptor_set); + +bool mip_is_valid_field_descriptor(uint8_t field_descriptor); +bool mip_is_cmd_field_descriptor(uint8_t field_descriptor); +bool mip_is_reply_field_descriptor(uint8_t field_descriptor); +bool mip_is_response_field_descriptor(uint8_t field_descriptor); +bool mip_is_reserved_cmd_field_descriptor(uint8_t field_descriptor); +bool mip_is_shared_data_field_descriptor(uint8_t field_descriptor); + +enum mip_function_selector +{ + MIP_FUNCTION_WRITE = 0x01, + MIP_FUNCTION_READ = 0x02, + MIP_FUNCTION_SAVE = 0x03, + MIP_FUNCTION_LOAD = 0x04, + MIP_FUNCTION_RESET = 0x05, +}; +typedef enum mip_function_selector mip_function_selector; +void insert_mip_function_selector(microstrain_serializer* serializer, enum mip_function_selector self); +void extract_mip_function_selector(microstrain_serializer* serializer, enum mip_function_selector* self); + + +#ifdef __cplusplus +} // extern "C" +} // namespace "C" +} // namespace mip +#endif // __cplusplus diff --git a/src/mip/definitions/descriptors.h b/src/mip/mip_descriptors.hpp similarity index 68% rename from src/mip/definitions/descriptors.h rename to src/mip/mip_descriptors.hpp index abf4cff34..c17e9f72e 100644 --- a/src/mip/definitions/descriptors.h +++ b/src/mip/mip_descriptors.hpp @@ -1,68 +1,21 @@ #pragma once -#include -#include -#include -#include "microstrain/common/serialization.h" -#include "../mip_result.h" +#include "mip_descriptors.h" + +#include "mip_result.hpp" -#ifdef __cplusplus #include "microstrain/common/buffer.hpp" #include #include #include -namespace mip { -namespace C { -using ::microstrain::C::microstrain_serializer; -extern "C" { -#endif // __cplusplus - -enum { - MIP_INVALID_DESCRIPTOR_SET = 0x00, - MIP_DATA_DESCRIPTOR_SET_START = 0x80, - MIP_RESERVED_DESCRIPTOR_SET_START = 0xF0, - - MIP_INVALID_FIELD_DESCRIPTOR = 0x00, - MIP_REPLY_DESCRIPTOR = 0xF1, - MIP_RESERVED_DESCRIPTOR_START = 0xF0, - MIP_RESPONSE_DESCRIPTOR_START = 0x80, - - MIP_SHARED_DATA_FIELD_DESCRIPTOR_START = 0xD0, -}; - -bool mip_is_valid_descriptor_set(uint8_t descriptor_set); -bool mip_is_data_descriptor_set(uint8_t descriptor_set); -bool mip_is_cmd_descriptor_set(uint8_t descriptor_set); -bool mip_is_reserved_descriptor_set(uint8_t descriptor_set); -bool mip_is_gnss_data_descriptor_set(uint8_t descriptor_set); - -bool mip_is_valid_field_descriptor(uint8_t field_descriptor); -bool mip_is_cmd_field_descriptor(uint8_t field_descriptor); -bool mip_is_reply_field_descriptor(uint8_t field_descriptor); -bool mip_is_response_field_descriptor(uint8_t field_descriptor); -bool mip_is_reserved_cmd_field_descriptor(uint8_t field_descriptor); -bool mip_is_shared_data_field_descriptor(uint8_t field_descriptor); -enum mip_function_selector +namespace mip { - MIP_FUNCTION_WRITE = 0x01, - MIP_FUNCTION_READ = 0x02, - MIP_FUNCTION_SAVE = 0x03, - MIP_FUNCTION_LOAD = 0x04, - MIP_FUNCTION_RESET = 0x05, -}; -typedef enum mip_function_selector mip_function_selector; -void insert_mip_function_selector(microstrain_serializer* serializer, enum mip_function_selector self); -void extract_mip_function_selector(microstrain_serializer* serializer, enum mip_function_selector* self); - - -#ifdef __cplusplus - -} // extern "C" -} // namespace "C" - +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ //////////////////////////////////////////////////////////////////////////////// ///@brief Convenience struct holding both descriptor set and field descriptor. @@ -143,6 +96,7 @@ struct TypedResult : public CmdResult constexpr CompositeDescriptor descriptor() const { return DESCRIPTOR; } }; +///@} +//////////////////////////////////////////////////////////////////////////////// } // namespace mip -#endif // __cplusplus diff --git a/src/mip/mip_dispatch.h b/src/mip/mip_dispatch.h index 59b02dbbf..9e60ae6cb 100644 --- a/src/mip/mip_dispatch.h +++ b/src/mip/mip_dispatch.h @@ -3,7 +3,7 @@ #include "mip_types.h" #include "mip_field.h" #include "mip_packet.h" -#include "definitions/descriptors.h" +#include "mip_descriptors.h" #include @@ -11,6 +11,7 @@ #ifdef __cplusplus namespace mip { namespace C { +extern "C" { #endif @@ -35,7 +36,7 @@ namespace C { ///@param packet The MIP packet triggering this callback. ///@param timestamp The approximate parse time of the packet. /// -typedef void (*mip_dispatch_packet_callback)(void* context, const mip_packet* packet, mip_timestamp timestamp); +typedef void (*mip_dispatch_packet_callback)(void *context, const mip_packet *packet, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// ///@brief Signature for field-level callbacks. @@ -44,7 +45,7 @@ typedef void (*mip_dispatch_packet_callback)(void* context, const mip_packet* pa ///@param field The MIP field triggering this callback. ///@param timestamp The approximate parse time of the packet. /// -typedef void (*mip_dispatch_field_callback )(void* context, const mip_field* field, mip_timestamp timestamp); +typedef void (*mip_dispatch_field_callback )(void *context, const mip_field *field, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// ///@brief Signature for extraction callbacks. @@ -52,7 +53,7 @@ typedef void (*mip_dispatch_field_callback )(void* context, const mip_field* fie ///@param field A valid mip_field. ///@param ptr A pointer to the destination field structure. /// -typedef bool (*mip_dispatch_extractor)(const mip_field* field, void* ptr); +typedef bool (*mip_dispatch_extractor)(const mip_field *field, void *ptr); enum { @@ -86,14 +87,14 @@ enum { /// typedef struct mip_dispatch_handler { - struct mip_dispatch_handler* _next; ///<@private Pointer to the next handler in the list. + struct mip_dispatch_handler *_next; ///<@private Pointer to the next handler in the list. union { - mip_dispatch_packet_callback _packet_callback; ///<@private User function for packets. Valid if _type is MIP_DISPATCH_TYPE_PACKET_*. - mip_dispatch_field_callback _field_callback; ///<@private User callback for data fields. Valid if _type is MIP_DISPATCH_TYPE_FIELD. - mip_dispatch_extractor _extract_callback; ///<@private User callback for data fields. Valid if _type is MIP_DISPATCH_TYPE_EXTRACT. + mip_dispatch_packet_callback _packet_callback; ///<@private User function for packets. Valid if _type is MIP_DISPATCH_TYPE_PACKET_*. + mip_dispatch_field_callback _field_callback; ///<@private User callback for data fields. Valid if _type is MIP_DISPATCH_TYPE_FIELD. + mip_dispatch_extractor _extract_callback; ///<@private User callback for data fields. Valid if _type is MIP_DISPATCH_TYPE_EXTRACT. }; - void* _user_data; ///<@private User-provided pointer which is passed directly to the callback. + void *_user_data; ///<@private User-provided pointer which is passed directly to the callback. uint8_t _type; ///<@private Type of the callback. (Using u8 for better struct packing.) @see mip_dispatch_type uint8_t _descriptor_set; ///<@private MIP descriptor set for this callback. uint8_t _field_descriptor; ///<@private MIP field descriptor for this callback. If 0x00, the callback is a packet callback. @@ -101,12 +102,12 @@ typedef struct mip_dispatch_handler } mip_dispatch_handler; -void mip_dispatch_handler_init_packet_handler(mip_dispatch_handler* handler, uint8_t descriptor_set, bool after_fields, mip_dispatch_packet_callback callback, void* context); -void mip_dispatch_handler_init_field_handler(mip_dispatch_handler* handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_field_callback callback, void* context); -void mip_dispatch_handler_init_extractor(mip_dispatch_handler* handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_extractor extractor, void* field_ptr); +void mip_dispatch_handler_init_packet_handler(mip_dispatch_handler *handler, uint8_t descriptor_set, bool after_fields, mip_dispatch_packet_callback callback, void *context); +void mip_dispatch_handler_init_field_handler(mip_dispatch_handler *handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_field_callback callback, void *context); +void mip_dispatch_handler_init_extractor(mip_dispatch_handler *handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_extractor extractor, void *field_ptr); -void mip_dispatch_handler_set_enabled(mip_dispatch_handler* handler, bool enable); -bool mip_dispatch_handler_is_enabled(mip_dispatch_handler* handler); +void mip_dispatch_handler_set_enabled(mip_dispatch_handler *handler, bool enable); +bool mip_dispatch_handler_is_enabled(mip_dispatch_handler *handler); ///@} @@ -120,16 +121,16 @@ bool mip_dispatch_handler_is_enabled(mip_dispatch_handler* handler); /// typedef struct mip_dispatcher { - mip_dispatch_handler* _first_handler; ///<@private Pointer to the first dispatch handler. May be NULL. + mip_dispatch_handler *_first_handler; ///<@private Pointer to the first dispatch handler. May be NULL. } mip_dispatcher; -void mip_dispatcher_init(mip_dispatcher* self); -void mip_dispatcher_add_handler(mip_dispatcher* self, mip_dispatch_handler* handler); -void mip_dispatcher_remove_handler(mip_dispatcher* self, mip_dispatch_handler* handler); -void mip_dispatcher_remove_all_handlers(mip_dispatcher* self); +void mip_dispatcher_init(mip_dispatcher *self); +void mip_dispatcher_add_handler(mip_dispatcher *self, mip_dispatch_handler *handler); +void mip_dispatcher_remove_handler(mip_dispatcher *self, mip_dispatch_handler *handler); +void mip_dispatcher_remove_all_handlers(mip_dispatcher *self); -void mip_dispatcher_dispatch_packet(mip_dispatcher* self, const mip_packet* packet, mip_timestamp timestamp); +void mip_dispatcher_dispatch_packet(mip_dispatcher *self, const mip_packet *packet, mip_timestamp timestamp); ///@} ///@} @@ -138,6 +139,7 @@ void mip_dispatcher_dispatch_packet(mip_dispatcher* self, const mip_packet* pack #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip #endif diff --git a/src/mip/mip_field.c b/src/mip/mip_field.c index 16a58bc93..cbc6b2d25 100644 --- a/src/mip/mip_field.c +++ b/src/mip/mip_field.c @@ -3,7 +3,7 @@ #include "mip_packet.h" #include "mip_offsets.h" -#include "definitions/descriptors.h" +#include "mip_descriptors.h" #include diff --git a/src/mip/mip_field.hpp b/src/mip/mip_field.hpp new file mode 100644 index 000000000..66c438b96 --- /dev/null +++ b/src/mip/mip_field.hpp @@ -0,0 +1,103 @@ +#pragma once + +#include "mip_field.h" +#include "mip_offsets.h" +#include "mip_descriptors.hpp" + +#include + + +namespace mip +{ +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief C++ class representing a MIP field. +/// +/// This is a thin wrapper around the C mip_field struct. +/// +class Field : public C::mip_field +{ +public: + static constexpr size_t MAX_PAYLOAD_LENGTH = C::MIP_FIELD_PAYLOAD_LENGTH_MAX; + + /// Construct an empty MIP field. + Field() { C::mip_field::_payload=nullptr; C::mip_field::_payload_length=0; C::mip_field::_field_descriptor=0x00; C::mip_field::_descriptor_set=0x00; C::mip_field::_remaining_length=0; } + ///@copydoc mip_field_init() + Field(uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) { C::mip_field_init(this, descriptor_set, field_descriptor, payload, payload_length); } + ///@copydoc mip_field_from_header_ptr() + Field(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set) { *this = C::mip_field_from_header_ptr(header, total_length, descriptor_set); } + /// Creates a %Field class from the mip_field C struct. + Field(const C::mip_field& other) { std::memcpy(static_cast(this), &other, sizeof(C::mip_field)); } + + // + // C function wrappers + // + + ///@copydoc mip_field_descriptor_set + uint8_t descriptorSet() const { return C::mip_field_descriptor_set(this); } + ///@copydoc mip_field_field_descriptor + uint8_t fieldDescriptor() const { return C::mip_field_field_descriptor(this); } + ///@brief Returns the descriptor set and field descriptor. + CompositeDescriptor descriptor() const { return {descriptorSet(), fieldDescriptor()}; } + ///@copydoc mip_field_payload_length + uint8_t payloadLength() const { return C::mip_field_payload_length(this); } + ///@copydoc mip_field_payload + const uint8_t* payload() const { return C::mip_field_payload(this); } + + ///@brief Index the payload at the given location. + ///@param index + ///@returns payload byte + uint8_t payload(unsigned int index) const { return payload()[index]; } + + uint8_t operator[](unsigned int index) const { return payload(index); } + + ///@copydoc mip_field_is_valid + bool isValid() const { return C::mip_field_is_valid(this); } + + ///@copydoc mip_field_next_after + Field nextAfter() const { return C::mip_field_next_after(this); } + ///@copydoc mip_field_next + bool next() { return C::mip_field_next(this); } + + // + // Additional functions which have no C equivalent + // + + ///@brief Deserializes the field data to specific field struct. + /// + ///@tparam FieldType Any field class from a file in the mip/definitions directory. + /// + ///@param[out] field A reference to the field struct to be filled out. Valid + /// only if the function returns true. + ///@param exact_size If true, the function fails if any bytes remain after deserialization. + /// + ///@returns True if the field was successfully deserialized, or false if the field contains + /// too few bytes (or to many if exact_size is specified). The field data is not + /// valid unless this function returns true. + template + bool extract(FieldType& field, bool exact_size=true) const { return mip::extract(field, payload(), payloadLength(), 0, exact_size); } + + + ///@brief Determines if the field holds data (and not a command, reply, or response). + bool isData() const { return isDataDescriptorSet(descriptorSet()); } + + ///@brief Determines if the field is from a command descriptor set (a command, reply, or response field). + bool isCommandSet() const { return isCommandDescriptorSet(descriptorSet()); } + + ///@brief Determines if the field holds a command. + bool isCommand() const { return isCommandSet() && isCommandFieldDescriptor(fieldDescriptor()); } + + ///@brief Determines if the field holds an ack/nack reply code. + bool isReply() const { return isCommandSet() && isReplyFieldDescriptor(fieldDescriptor()) && payloadLength()==2; } + + ///@brief Determines if the field holds command response data (not an ack/nack reply). + bool isResponse() const { return isCommandSet() && isResponseFieldDescriptor(fieldDescriptor()); } +}; + + +///@} +//////////////////////////////////////////////////////////////////////////////// +} // namespace mip diff --git a/src/mip/mip_interface.c b/src/mip/mip_interface.c index 586b7689a..5b4876308 100644 --- a/src/mip/mip_interface.c +++ b/src/mip/mip_interface.c @@ -3,7 +3,7 @@ #include "mip_field.h" -#include "definitions/descriptors.h" +#include "mip_descriptors.h" #include diff --git a/src/mip/mip_device.cpp b/src/mip/mip_interface.cpp similarity index 98% rename from src/mip/mip_device.cpp rename to src/mip/mip_interface.cpp index ecc6ef7dd..3c9792334 100644 --- a/src/mip/mip_device.cpp +++ b/src/mip/mip_interface.cpp @@ -1,5 +1,5 @@ -#include "mip_device.hpp" +#include "mip_interface.hpp" #include diff --git a/src/mip/mip_device.hpp b/src/mip/mip_interface.hpp similarity index 85% rename from src/mip/mip_device.hpp rename to src/mip/mip_interface.hpp index e0d4496a4..d410eaeac 100644 --- a/src/mip/mip_device.hpp +++ b/src/mip/mip_interface.hpp @@ -1,12 +1,16 @@ #pragma once -#include "mip.hpp" +#include "mip_parser.hpp" +#include "mip_cmdqueue.hpp" + #include "mip_interface.h" -#include "definitions/descriptors.h" +#include "mip_descriptors.h" +#include #include + namespace microstrain { class Connection; @@ -14,6 +18,9 @@ namespace microstrain namespace mip { +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ class DeviceInterface; @@ -21,11 +28,6 @@ void connect_interface(mip::DeviceInterface& dev, microstrain::Connection& conn) - -//////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_cpp -///@{ - using DispatchHandler = C::mip_dispatch_handler; struct Dispatcher : public C::mip_dispatcher @@ -42,103 +44,6 @@ struct Dispatcher : public C::mip_dispatcher }; -//////////////////////////////////////////////////////////////////////////////// -///@brief C++ wrapper around a command queue. -/// -struct CmdQueue : public C::mip_cmd_queue -{ - CmdQueue(Timeout baseReplyTimeout=1000) { C::mip_cmd_queue_init(this, baseReplyTimeout); } - ~CmdQueue() { assert(_first_pending_cmd==nullptr); } - - CmdQueue(const CmdQueue&) = delete; - CmdQueue& operator=(const CmdQueue&) = delete; - - void enqueue(C::mip_pending_cmd& cmd) { C::mip_cmd_queue_enqueue(this, &cmd); } - void dequeue(C::mip_pending_cmd& cmd) { C::mip_cmd_queue_dequeue(this, &cmd); } - - void clear() { C::mip_cmd_queue_clear(this); } - - void update(Timestamp now) { C::mip_cmd_queue_update(this, now); } - - void setBaseReplyTimeout(Timeout timeout) { C::mip_cmd_queue_set_base_reply_timeout(this, timeout); } - Timeout baseReplyTimeout() const { return C::mip_cmd_queue_base_reply_timeout(this); } - - void processPacket(const C::mip_packet& packet, Timestamp timestamp) { C::mip_cmd_queue_process_packet(this, &packet, timestamp); } -}; -static_assert(sizeof(CmdQueue) == sizeof(C::mip_cmd_queue), "CmdQueue must not have additional data members."); - - -//////////////////////////////////////////////////////////////////////////////// -///@brief C++ class representing the state of a MIP command. -/// -struct PendingCmd : public C::mip_pending_cmd -{ - ///@brief Create a null pending command in the CmdResult::NONE state. - /// - PendingCmd() { std::memset(static_cast(this), 0, sizeof(C::mip_pending_cmd)); } - - ///@brief Create a pending command for the given descriptor pair. - /// - ///@param descriptorSet MIP descriptor set for the command. - ///@param fieldDescriptor MIP field descriptor for the command. - ///@param additionalTime Optional additional time to allow for the device to process the command. Default 0. - /// - PendingCmd(uint8_t descriptorSet, uint8_t fieldDescriptor, Timeout additionalTime=0) { C::mip_pending_cmd_init_with_timeout(this, descriptorSet, fieldDescriptor, additionalTime); } - - ///@brief Create a pending command with expected response. - /// - ///@param descriptorSet MIP descriptor set for the command. - ///@param fieldDescriptor MIP field descriptor for the command. - ///@param responseDescriptor MIP field descriptor for the response. - ///@param responseBuffer A buffer used for the command response data. Must be big enough for the expected response. You can reuse the buffer used to send the command. - ///@param responseBufferSize Length of responseBuffer in bytes. - ///@param additionalTime Optional additional time to allow for the device to process the command. Default 0. - /// - PendingCmd(uint8_t descriptorSet, uint8_t fieldDescriptor, uint8_t responseDescriptor, uint8_t* responseBuffer, uint8_t responseBufferSize, Timeout additionalTime) { C::mip_pending_cmd_init_full(this, descriptorSet, fieldDescriptor, responseDescriptor, responseBuffer, responseBufferSize, additionalTime); } - - ///@brief Create a pending command given the actual command struct. - /// - ///@param cmd The C++ command struct (this must be the C++ version of the struct, the C struct will not work). It need not be fully populated; this parameter is unused except for its type information. - ///@param additionalTime Optional additional time to allow for the device to process the command. Default 0. - /// - template - PendingCmd(const Cmd& cmd, Timeout additionalTime=0) : PendingCmd(cmd.descriptorSet, cmd.fieldDescriptor, additionalTime) {} - - ///@brief Create a pending command given the actual command struct and a response buffer. - /// - ///@param cmd The C++ command struct (this must be the C++ version of the struct, the C struct will not work). It need not be fully populated; this parameter is unused except for its type information. - ///@param responseBuffer A buffer used for the command response data. Must be big enough for the expected response. You can reuse the buffer used to send the command. - ///@param responseBufferSize Length of responseBuffer in bytes. - ///@param additionalTime Optional additional time to allow for the device to process the command. Default 0. - /// - template - PendingCmd(const Cmd& cmd, uint8_t* responseBuffer, uint8_t responseBufferSize, Timeout additionalTime=0) : PendingCmd(Cmd::DESCRIPTOR_SET, Cmd::FIELD_DESCRIPTOR, Cmd::Response::FIELD_DESCRIPTOR, responseBuffer, responseBufferSize, additionalTime) {} - - ///@brief Disable copying and moving. Once queued, a pending command must remain in the same memory location. - /// - PendingCmd(const PendingCmd&) = delete; - PendingCmd& operator=(const PendingCmd&) = delete; - - ///@brief Sanity check that the PendingCmd is not deallocated while still in the queue. - /// - ~PendingCmd() { CmdResult tmp = status(); assert(tmp.isFinished() || tmp==CmdResult::STATUS_NONE); (void)tmp; } - - ///@brief Gets the status of the pending command. - /// - CmdResult status() const { return C::mip_pending_cmd_status(this); } - - ///@copydoc mip::C::mip_pending_cmd_response_descriptor - uint8_t responseDescriptor() const { return C::mip_pending_cmd_response_descriptor(this); } - - ///@copydoc mip::C::mip_pending_cmd_response - const uint8_t* response() const { return C::mip_pending_cmd_response(this); } - - ///@copydoc mip::C::mip_pending_cmd_response_length - uint8_t responseLength() const { return C::mip_pending_cmd_response_length(this); } -}; - - - template CmdResult runCommand(C::mip_interface& device, const Cmd& cmd, Timeout additionalTime=0); template CmdResult runCommand(C::mip_interface& device, const Cmd& cmd, typename Cmd::Response& response, Timeout additionalTime=0); template CmdResult runCommand(C::mip_interface& device, const Args&&... args, Timeout additionalTime); @@ -985,5 +890,4 @@ bool startCommand(C::mip_interface& device, C::mip_pending_cmd& pending, const C ///@} //////////////////////////////////////////////////////////////////////////////// - } // namespace mip diff --git a/src/mip/mip_packet.c b/src/mip/mip_packet.c index 59927bf10..631065a71 100644 --- a/src/mip/mip_packet.c +++ b/src/mip/mip_packet.c @@ -2,7 +2,7 @@ #include "mip_packet.h" #include "mip_offsets.h" -#include "definitions/descriptors.h" +#include "mip_descriptors.h" #include diff --git a/src/mip/mip_packet.hpp b/src/mip/mip_packet.hpp new file mode 100644 index 000000000..6bc663665 --- /dev/null +++ b/src/mip/mip_packet.hpp @@ -0,0 +1,329 @@ +#pragma once + +#include "mip_field.hpp" + +#include "mip_packet.h" +#include "mip_offsets.h" + +#include + +#include +#include + + +namespace mip +{ +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ + + +//////////////////////////////////////////////////////////////////////////////// +///@brief C++ class representing a MIP PacketRef. +/// +/// This is a thin wrapper around the mip_packet C structure. Like the C +/// version, it does not contain or own the data buffer. Any of the C functions +/// can be used with the C++ packet class because it inherits from the C struct. +/// +/// Fields may be iterated over using the C-style methods, with an iterator, or +/// with a range-based for loop: +///@code{.cpp} +/// for(PacketRef::Iterator iter = packet.begin(); iter != packet.end(); ++iter) { ... } +/// for(Field field : packet) { ... } +///@endcode +/// +class PacketRef : public C::mip_packet +{ +public: + static constexpr size_t PAYLOAD_LENGTH_MAX = C::MIP_PACKET_PAYLOAD_LENGTH_MAX; + static constexpr size_t PACKET_SIZE_MIN = C::MIP_PACKET_LENGTH_MIN; + static constexpr size_t PACKET_SIZE_MAX = C::MIP_PACKET_LENGTH_MAX; + + class FieldIterator; + +public: + ///@copydoc mip::C::mip_packet_create + PacketRef(uint8_t* buffer, size_t bufferSize, uint8_t descriptorSet) { C::mip_packet_create(this, buffer, bufferSize, descriptorSet); } + ///@copydoc mip_packet_from_buffer + PacketRef(uint8_t* buffer, size_t length) { C::mip_packet_from_buffer(this, buffer, length); } + /// Constructs a C++ %PacketRef class from the base C object. + PacketRef(const C::mip_packet* other) { std::memcpy(static_cast(this), other, sizeof(*this)); } + /// Constructs a C++ %PacketRef class from the base C object. + PacketRef(const C::mip_packet& other) { std::memcpy(static_cast(this), &other, sizeof(*this)); } + + + // + // C function wrappers + // + + uint8_t descriptorSet() const { return C::mip_packet_descriptor_set(this); } ///<@copydoc mip::C::mip_packet_descriptor_set + uint_least16_t totalLength() const { return C::mip_packet_total_length(this); } ///<@copydoc mip::C::mip_packet_total_length + uint8_t payloadLength() const { return C::mip_packet_payload_length(this); } ///<@copydoc mip::C::mip_packet_payload_length + + bool isData() const { return C::mip_packet_is_data(this); } + + const uint8_t* pointer() const { return C::mip_packet_pointer(this); } ///<@copydoc mip::C::mip_packet_pointer + const uint8_t* payload() const { return C::mip_packet_payload(this); } ///<@copydoc mip::C::mip_packet_payload + + uint16_t checksumValue() const { return C::mip_packet_checksum_value(this); } ///<@copydoc mip::C::mip_packet_checksum_value + uint16_t computeChecksum() const { return C::mip_packet_compute_checksum(this); } ///<@copydoc mip::C::mip_packet_compute_checksum + + bool isSane() const { return C::mip_packet_is_sane(this); } ///<@copydoc mip::C::mip_packet_is_sane + bool isValid() const { return C::mip_packet_is_valid(this); } ///<@copydoc mip::C::mip_packet_is_valid + bool isEmpty() const { return C::mip_packet_is_empty(this); } ///<@copydoc mip::C::mip_packet_is_empty + + uint_least16_t bufferSize() const { return C::mip_packet_buffer_size(this); } ///<@copydoc mip::C::mip_packet_buffer_size + int remainingSpace() const { return C::mip_packet_remaining_space(this); } ///<@copydoc mip::C::mip_packet_remaining_space + + bool addField(uint8_t fieldDescriptor, const uint8_t* payload, uint8_t payloadLength) { return C::mip_packet_add_field(this, fieldDescriptor, payload, payloadLength); } ///<@copydoc mip::C::mip_packet_add_field + microstrain::Buffer createField(uint8_t fieldDescriptor, uint8_t length) { uint8_t* ptr; if(C::mip_packet_alloc_field(this, fieldDescriptor, length, &ptr) < 0) length=0; return microstrain::Buffer{ptr, length}; } + //std::tuple createField(uint8_t fieldDescriptor) { uint8_t* ptr; int max_size = C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr); return max_size >= 0 ? std::make_tuple(ptr, max_size) : std::make_tuple(nullptr, 0); } ///<@copydoc mip::C::mip_packet_alloc_field + //int finishLastField(uint8_t* payloadPtr, uint8_t newPayloadLength) { return C::mip_packet_realloc_last_field(this, payloadPtr, newPayloadLength); } ///<@copydoc mip::C::mip_packet_realloc_last_field + //int cancelLastField(uint8_t* payloadPtr) { return C::mip_packet_cancel_last_field(this, payloadPtr); } ///<@copydoc mip::C::mip_packet_cancel_last_field + + class AllocatedField : public microstrain::Buffer + { + public: + AllocatedField(mip::PacketRef& packet, uint8_t* buffer, size_t space) : Buffer(buffer, space), m_packet(packet) {} + //AllocatedField(const AllocatedField&) = delete; + AllocatedField& operator=(const AllocatedField&) = delete; + + bool commit() + { + bool ok = isOk(); + + if(ok) + C::mip_packet_realloc_last_field(&m_packet, basePointer(), length()); + else + C::mip_packet_cancel_last_field(&m_packet, basePointer()); + + return ok; + } + + private: + PacketRef& m_packet; + }; + + AllocatedField createField(uint8_t fieldDescriptor) { uint8_t* ptr; size_t max_size = std::max(0, C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr)); return {*this, ptr, max_size}; } + + void finalize() { C::mip_packet_finalize(this); } ///<@copydoc mip::C::mip_packet_finalize + + void reset(uint8_t descSet) { C::mip_packet_reset(this, descSet); } ///<@copydoc mip::C::mip_packet_reset + void reset() { reset(descriptorSet()); } ///<@brief Resets the packet using the same descriptor set. + + uint8_t operator[](unsigned int index) const { return pointer()[index]; } + + // + // Additional functions which have no C equivalent + // + + /// Returns a forward iterator to the first field in the packet. + /// + FieldIterator begin() const { return firstField(); } + + /// Returns a sentry object representing the end of fields in the packet. + /// +#if __cpp_range_based_for >= 201603 + // After 201603, for loops allow different clases for begin and end. + // Using nullptr is simpler and more efficient than creating an end iterator. + std::nullptr_t end() const { return nullptr; } +#else + FieldIterator end() const { return Field(); } +#endif + + ///@brief Returns the first field in the packet. + /// + /// Subsequent fields can be obtained via the returned Field class, + /// but iteration is best done with begin()/end() or the range-based for loop. + /// + ///@note Packets can be empty, so make sure that the returned field is + /// valid before using it. + /// + ///@returns A Field instance representing the first field (if any). + /// + Field firstField() const { return Field(C::mip_field_first_from_packet(this)); } + + ///@brief Adds a field of the given type to the packet. + /// + ///@tparam FieldType Any field class from a file in the mip/definitions directory. + /// + ///@param field Instance of the field to add to the packet. + ///@param fieldDescriptor If specified, overrides the field descriptor. + /// + ///@returns True if the field was added, false if the packet has insufficient space. + /// + template + bool addField(const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) + { + if( fieldDescriptor == INVALID_FIELD_DESCRIPTOR ) + fieldDescriptor = FieldType::FIELD_DESCRIPTOR; + + AllocatedField buffer = createField(fieldDescriptor); + buffer.insert(field); + return buffer.commit(); + } + + ///@brief Creates a new PacketRef containing a single MIP field from an instance of the field type. + /// + /// This works just like the addField() function but also initializes and finalizes the packet. + /// It is assumed that the field will fit in an empty packet; otherwise the field can't ever be used. + /// The field classes are predefined so this doesn't need runtime checking. + /// + ///@tparam FieldType Any field class from a file in the mip/definitions directory. + /// + ///@param buffer Buffer to hold the packet bytes. + ///@param bufferSize Size of buffer in bytes. + ///@param field Instance of the field to add to the packet. + ///@param fieldDescriptor If specified, overrides the field descriptor. + /// + ///@returns A PacketRef object containing the field. + /// + template + static PacketRef createFromField(uint8_t* buffer, size_t bufferSize, const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) + { + if( fieldDescriptor == INVALID_FIELD_DESCRIPTOR ) + fieldDescriptor = FieldType::FIELD_DESCRIPTOR; + PacketRef packet(buffer, bufferSize, FieldType::DESCRIPTOR_SET); + packet.addField(field, fieldDescriptor); + packet.finalize(); + return packet; + } + + + /// Iterator class for use with the range-based for loop or iterators. + /// + /// You should generally use the begin()/end() functions on the PacketRef + /// class instead of using this class directly. + /// + class FieldIterator + { + public: + /// Empty iterator, which represents the "end" iterator of a packet. + FieldIterator() {} + + /// Create an iterator given the first field to iterate in a packet. + /// Technically this can be any field, not just the first field. + FieldIterator(const Field& first) : mField(first) {} + + /// Comparison between any two iterators. + /// This works even for iterators over different packets, which will + /// never be the same (except all null/end iterators are equivalent). + bool operator==(const FieldIterator& other) const { + // Required to make invalid fields equivalent for range-based for loop + if( !mField.isValid() && !other.mField.isValid() ) + return true; + return mField.descriptorSet() == other.mField.descriptorSet() && mField.fieldDescriptor() == other.mField.fieldDescriptor() && mField.payload() == other.mField.payload(); + } + bool operator!=(const FieldIterator& other) const { return !(*this == other); } + + /// Comparison with std::nullptr is checking if the iterator points to + /// a valid field (i.e. not the end). + bool operator==(std::nullptr_t) const { return !mField.isValid(); } + bool operator!=(std::nullptr_t) const { return mField.isValid(); } + + /// Dereference the iterator as a Field instance. + const Field& operator*() const { return mField; } + + /// Advance to the next field. + FieldIterator& operator++() { mField.next(); return *this; } + + private: + Field mField; + }; + +}; + + +//////////////////////////////////////////////////////////////////////////////// +///@brief A mip packet with a self-contained buffer (useful with std::vector). +/// +template +class SizedPacketBuf : public PacketRef +{ +public: + SizedPacketBuf(uint8_t descriptorSet=INVALID_DESCRIPTOR_SET) : PacketRef(mData, sizeof(mData), descriptorSet) {} + + ///@brief Creates a PacketBuf by copying existing data. + /// + explicit SizedPacketBuf(const uint8_t* data, size_t length) : PacketRef(mData, sizeof(mData)) { copyFrom(data, length); } + explicit SizedPacketBuf(const PacketRef& packet) : PacketRef(mData, sizeof(mData)) { copyFrom(packet); } + + ///@brief Copy constructor + SizedPacketBuf(const SizedPacketBuf& other) : PacketRef(mData, sizeof(mData)) { copyFrom(other); } + + ///@brief Copy constructor (required to put packets into std::vector in some cases). + template + explicit SizedPacketBuf(const SizedPacketBuf& other) : PacketRef(mData, sizeof(mData)) { copyFrom(other); }; + + ///@brief Copy assignment operator + SizedPacketBuf& operator=(const SizedPacketBuf& other) { copyFrom(other); return *this; } + + ///@brief Assignment operator, copies data from another buffer to this one. + template + SizedPacketBuf& operator=(const SizedPacketBuf& other) { copyFrom(other); return *this; } + + ///@brief Create a packet containing just the given field. + /// + ///@tparam FieldType Type of the MIP field. This can't be explicitly specified due to being a constructor. + /// + ///@param field The field object to serialize. + ///@param fieldDescriptor If specified (not INVALID_FIELD_DESCRIPTOR), overrides the field descriptor. + /// + template + SizedPacketBuf(const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) : PacketRef(mData, sizeof(mData)) { createFromField(mData, sizeof(mData), field, fieldDescriptor); } + + + ///@brief Explicitly obtains a reference to the packet data. + /// + PacketRef ref() { return *this; } + + ///@brief Explicitly obtains a const reference to the packet data. + /// + const PacketRef& ref() const { return *this; } + + ///@brief Returns a pointer to the underlying buffer. + /// This is technically the same as PacketRef::pointer but is writable. + uint8_t* buffer() { return mData; } + + ///@brief Copies the data from the pointer to this buffer. The data is not inspected. + /// + ///@param data Pointer to the start of the packet. + ///@param length Total length of the packet. + /// + void copyFrom(const uint8_t* data, size_t length) { assert(length <= sizeof(mData)); std::memcpy(mData, data, length); } + + ///@brief Copies an existing packet. The packet is assumed to be valid (undefined behavior otherwise). + /// + ///@param packet A "sane" (isSane()) mip packet. + /// + void copyFrom(const PacketRef& packet) { assert(packet.isSane()); copyFrom(packet.pointer(), packet.totalLength()); } + + ///@brief Copies this packet to an external buffer. + /// + /// This packet must be sane (see isSane()). Undefined behavior otherwise due to lookup of totalLength(). + /// + ///@param buffer Data is copied into this location. + ///@param maxLength Maximum number of bytes to copy. + /// + ///@returns true if successful. + ///@returns false if maxLength is too short. + /// + bool copyTo(uint8_t* buffer, size_t maxLength) { assert(isSane()); size_t copyLength = this->totalLength(); if(copyLength > maxLength) return false; std::memcpy(buffer, mData, copyLength); return true; } + +private: + uint8_t mData[BufferSize]; +}; + +//////////////////////////////////////////////////////////////////////////////// +///@brief Typedef for SizedPacketBuf of max possible size. +/// +/// Generally you should use this instead of SizedPacketBuf directly, unless you +/// know the maximum size of your packet will be less than PACKET_LENGTH_MAX. +/// +typedef SizedPacketBuf PacketBuf; + + + +///@} +//////////////////////////////////////////////////////////////////////////////// +} // namespace mip diff --git a/src/mip/mip_parser.hpp b/src/mip/mip_parser.hpp new file mode 100644 index 000000000..a2656b117 --- /dev/null +++ b/src/mip/mip_parser.hpp @@ -0,0 +1,122 @@ +#pragma once + +#include "mip_packet.hpp" + +#include "mip_parser.h" + + +namespace mip +{ +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief C++ class representing a MIP parser. +/// +/// See @ref parsing_packets +/// +class Parser : public C::mip_parser +{ +public: + ///@copydoc mip::C::mip_parser_init + Parser(uint8_t* buffer, size_t bufferSize, C::mip_packet_callback callback, void* callbackObject, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, callback, callbackObject, timeout); } + ///@copydoc mip::C::mip_parser_init + Parser(uint8_t* buffer, size_t bufferSize, bool (*callback)(void*,const PacketRef*,Timestamp), void* callbackObject, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, (C::mip_packet_callback)callback, callbackObject, timeout); } + + Parser(uint8_t* buffer, size_t bufferSize, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, nullptr, nullptr, timeout); } + + template + void setCallback(T& object); + + ///@copydoc mip::C::mip_parser_reset + void reset() { C::mip_parser_reset(this); } + + ///@copydoc mip::C::mip_parser_parse + size_t parse(const uint8_t* inputBuffer, size_t inputCount, Timestamp timestamp, unsigned int maxPackets=0) { return C::mip_parser_parse(this, inputBuffer, inputCount, timestamp, maxPackets); } + + ///@copydoc mip::C::mip_parser_timeout + Timeout timeout() const { return C::mip_parser_timeout(this); } + ///@copydoc mip::C::mip_parser_set_timeout + void setTimeout(Timeout timeout) { return C::mip_parser_set_timeout(this, timeout); } +}; + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Initializes the MIP Parser +/// +/// This version allows binding a member function instead of a C-style callback. +/// Example: +///@code{.cpp} +/// struct MyClass +/// { +/// void handlePacket(const PacketRef& packet, Timeout timeout); +/// }; +/// MyClass myInstance; +/// Parser parser(myInstance); +///@endcode +/// +///@tparam T Class type containing the member function to be called. +///@tparam Callback A pointer to a member function on a T to be called when a +/// packet is parsed. +/// +///@param object +/// Instance of T to call the callback. +/// +template +void Parser::setCallback(T& object) +{ + C::mip_packet_callback callback = [](void* obj, const C::mip_packet* pkt, Timestamp timestamp)->bool + { + return (static_cast(obj)->*Callback)(PacketRef(pkt), timestamp); + }; + + C::mip_parser_set_callback(this, callback, &object); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Read data from a source into the internal parsing buffer. +/// +///@tparam Function +/// A function-like object with the following signature: +/// `bool read(size_t maxCount, size_t* count_out, Timestamp* timestamp_out);` +/// The parameters are as follows: +/// @li buffer - Buffer into which to write data. +/// @li maxCount - The maximum number of bytes to read. +/// @li count_out - Updated with the number of bytes actually read. +/// @li timestamp_out - Updated with the timestamp of the data. +/// +///@param parser +/// +///@param reader +/// A callback function, lambda, or similar which will read data into the +/// buffer and capture the timestamp. It should return true if successful +/// or false otherwise. If it returns false, parsing is skipped. The read +/// function may also throw an exception instead of returning false. +/// +///@param maxPackets +/// Maximum number of packets to parse, just like for Parser::parse(). +/// +///@return Same as the return value of reader. +/// +template +bool parseMipDataFromSource(C::mip_parser& parser, Function reader, size_t maxPackets) +{ + uint8_t* ptr; + size_t maxCount = C::mip_parser_get_write_ptr(&parser, &ptr); + + size_t count; + Timestamp timestamp; + if( !reader(ptr, maxCount, &count, ×tamp) ) + return false; + + assert(count <= maxCount); + + C::mip_parser_process_written(&parser, count, timestamp, maxPackets); + + return true; +} + +///@} +//////////////////////////////////////////////////////////////////////////////// +} // namespace mip diff --git a/src/mip/mip_result.h b/src/mip/mip_result.h index 590c7bff3..0cfb8b153 100644 --- a/src/mip/mip_result.h +++ b/src/mip/mip_result.h @@ -27,12 +27,12 @@ typedef enum mip_cmd_result MIP_STATUS_USER_START = -10, ///< Values defined by user code must be less than or equal to this value. // Status codes < 0 - MIP_STATUS_ERROR = -6, ///< Command could not be executed (error sending/receiving) - MIP_STATUS_CANCELLED = -5, ///< Command was canceled in software. - MIP_STATUS_TIMEDOUT = -4, ///< Reply was not received before timeout expired. - MIP_STATUS_WAITING = -3, ///< Waiting for command reply (timeout timer has started). - MIP_STATUS_PENDING = -2, ///< Command has been queued but the I/O update hasn't run yet. - MIP_STATUS_NONE = -1, ///< Command has been initialized but not queued yet. + MIP_STATUS_ERROR = -6, ///< Command could not be executed (error sending/receiving) + MIP_STATUS_CANCELLED = -5, ///< Command was canceled in software. + MIP_STATUS_TIMEDOUT = -4, ///< Reply was not received before timeout expired. + MIP_STATUS_WAITING = -3, ///< Waiting for command reply (timeout timer has started). + MIP_STATUS_PENDING = -2, ///< Command has been queued but the I/O update hasn't run yet. + MIP_STATUS_NONE = -1, ///< Command has been initialized but not queued yet. // Device replies >= 0 MIP_ACK_OK = 0x00, ///< Command completed successfully. @@ -43,7 +43,7 @@ typedef enum mip_cmd_result MIP_NACK_COMMAND_TIMEOUT = 0x05, ///< Internal device timeout. Use MIP_STATUS_TIMEDOUT for command timeouts. } mip_cmd_result; -const char* mip_cmd_result_to_string(enum mip_cmd_result result); +const char *mip_cmd_result_to_string(enum mip_cmd_result result); bool mip_cmd_result_is_finished(enum mip_cmd_result result); @@ -59,77 +59,5 @@ bool mip_cmd_result_is_ack(enum mip_cmd_result result); #ifdef __cplusplus } // extern "C" } // namespace C - -//////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_cpp -///@{ - -//////////////////////////////////////////////////////////////////////////////// -///@brief Represents the status of a MIP command. -/// -/// This is the same as the mip_cmd_result enum, but with some convenient -// member functions and some operator overloads. -/// -/// CmdResult is convertible to bool, allowing code like the following: -///@code{.cpp} -/// if( !mip::commands_base::ping(device) ) -/// fprintf(stderr, "Couldn't ping the device!\n"); -///@endcode -/// -struct CmdResult -{ - static constexpr C::mip_cmd_result STATUS_USER = C::MIP_STATUS_USER_START; ///<@copydoc mip::C::MIP_STATUS_USER_START - static constexpr C::mip_cmd_result STATUS_ERROR = C::MIP_STATUS_ERROR; ///<@copydoc mip::C::MIP_STATUS_ERROR - static constexpr C::mip_cmd_result STATUS_CANCELLED = C::MIP_STATUS_CANCELLED; ///<@copydoc mip::C::MIP_STATUS_CANCELLED - static constexpr C::mip_cmd_result STATUS_TIMEDOUT = C::MIP_STATUS_TIMEDOUT; ///<@copydoc mip::C::MIP_STATUS_TIMEDOUT - static constexpr C::mip_cmd_result STATUS_WAITING = C::MIP_STATUS_WAITING; ///<@copydoc mip::C::MIP_STATUS_WAITING - static constexpr C::mip_cmd_result STATUS_QUEUED = C::MIP_STATUS_PENDING; ///<@copydoc mip::C::MIP_STATUS_PENDING - static constexpr C::mip_cmd_result STATUS_NONE = C::MIP_STATUS_NONE; ///<@copydoc mip::C::MIP_STATUS_NONE - - static constexpr C::mip_cmd_result ACK_OK = C::MIP_ACK_OK; ///<@copydoc C::MIP_ACK_OK - static constexpr C::mip_cmd_result NACK_COMMAND_UNKNOWN = C::MIP_NACK_COMMAND_UNKNOWN; ///<@copydoc C::MIP_NACK_COMMAND_UNKNOWN - static constexpr C::mip_cmd_result NACK_INVALID_CHECKSUM = C::MIP_NACK_INVALID_CHECKSUM; ///<@copydoc C::MIP_NACK_INVALID_CHECKSUM - static constexpr C::mip_cmd_result NACK_INVALID_PARAM = C::MIP_NACK_INVALID_PARAM; ///<@copydoc C::MIP_NACK_INVALID_PARAM - static constexpr C::mip_cmd_result NACK_COMMAND_FAILED = C::MIP_NACK_COMMAND_FAILED; ///<@copydoc C::MIP_NACK_COMMAND_FAILED - static constexpr C::mip_cmd_result NACK_COMMAND_TIMEOUT = C::MIP_NACK_COMMAND_TIMEOUT; ///<@copydoc C::MIP_NACK_COMMAND_TIMEOUT - -#ifndef _WIN32 // Avoid name conflict with windows.h - static constexpr C::mip_cmd_result STATUS_PENDING = STATUS_QUEUED; -#endif - - C::mip_cmd_result value = C::MIP_STATUS_NONE; - - constexpr CmdResult() : value(C::MIP_ACK_OK) {} - constexpr CmdResult(C::mip_cmd_result result) : value(result) {} - ~CmdResult() = default; - - CmdResult& operator=(const CmdResult& other) = default; - CmdResult& operator=(C::mip_cmd_result other) { value = other; return *this; } - - static constexpr CmdResult userResult(uint8_t n) { return CmdResult(static_cast(STATUS_USER - int8_t(n))); } - static constexpr CmdResult fromAckNack(uint8_t code) { return CmdResult(static_cast(code)); } - - operator const void*() const { return isAck() ? this : nullptr; } - bool operator!() const { return !isAck(); } - - constexpr bool operator==(CmdResult other) const { return value == other.value; } - constexpr bool operator!=(CmdResult other) const { return value != other.value; } - - constexpr bool operator==(C::mip_cmd_result other) const { return value == other; } - constexpr bool operator!=(C::mip_cmd_result other) const { return value != other; } - - const char* name() const { return C::mip_cmd_result_to_string(value); } - - bool isReplyCode() const { return C::mip_cmd_result_is_reply(value); } - bool isStatusCode() const { return C::mip_cmd_result_is_status(value); } - bool isFinished() const { return C::mip_cmd_result_is_finished(value); } - bool isAck() const { return C::mip_cmd_result_is_ack(value); } -}; - -// using Ack = C::mip_ack; - -///@} -//////////////////////////////////////////////////////////////////////////////// - } // namespace mip #endif // __cplusplus diff --git a/src/mip/mip_result.hpp b/src/mip/mip_result.hpp new file mode 100644 index 000000000..c9ca9d1b3 --- /dev/null +++ b/src/mip/mip_result.hpp @@ -0,0 +1,76 @@ +#pragma once + +#include "mip_result.h" + + +namespace mip +{ +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ + +//////////////////////////////////////////////////////////////////////////////// +///@brief Represents the status of a MIP command. +/// +/// This is the same as the mip_cmd_result enum, but with some convenient +// member functions and some operator overloads. +/// +/// CmdResult is convertible to bool, allowing code like the following: +///@code{.cpp} +/// if( !mip::commands_base::ping(device) ) +/// fprintf(stderr, "Couldn't ping the device!\n"); +///@endcode +/// +struct CmdResult +{ + static constexpr C::mip_cmd_result STATUS_USER = C::MIP_STATUS_USER_START; ///<@copydoc mip::C::MIP_STATUS_USER_START + static constexpr C::mip_cmd_result STATUS_ERROR = C::MIP_STATUS_ERROR; ///<@copydoc mip::C::MIP_STATUS_ERROR + static constexpr C::mip_cmd_result STATUS_CANCELLED = C::MIP_STATUS_CANCELLED; ///<@copydoc mip::C::MIP_STATUS_CANCELLED + static constexpr C::mip_cmd_result STATUS_TIMEDOUT = C::MIP_STATUS_TIMEDOUT; ///<@copydoc mip::C::MIP_STATUS_TIMEDOUT + static constexpr C::mip_cmd_result STATUS_WAITING = C::MIP_STATUS_WAITING; ///<@copydoc mip::C::MIP_STATUS_WAITING + static constexpr C::mip_cmd_result STATUS_QUEUED = C::MIP_STATUS_PENDING; ///<@copydoc mip::C::MIP_STATUS_PENDING + static constexpr C::mip_cmd_result STATUS_NONE = C::MIP_STATUS_NONE; ///<@copydoc mip::C::MIP_STATUS_NONE + + static constexpr C::mip_cmd_result ACK_OK = C::MIP_ACK_OK; ///<@copydoc C::MIP_ACK_OK + static constexpr C::mip_cmd_result NACK_COMMAND_UNKNOWN = C::MIP_NACK_COMMAND_UNKNOWN; ///<@copydoc C::MIP_NACK_COMMAND_UNKNOWN + static constexpr C::mip_cmd_result NACK_INVALID_CHECKSUM = C::MIP_NACK_INVALID_CHECKSUM; ///<@copydoc C::MIP_NACK_INVALID_CHECKSUM + static constexpr C::mip_cmd_result NACK_INVALID_PARAM = C::MIP_NACK_INVALID_PARAM; ///<@copydoc C::MIP_NACK_INVALID_PARAM + static constexpr C::mip_cmd_result NACK_COMMAND_FAILED = C::MIP_NACK_COMMAND_FAILED; ///<@copydoc C::MIP_NACK_COMMAND_FAILED + static constexpr C::mip_cmd_result NACK_COMMAND_TIMEOUT = C::MIP_NACK_COMMAND_TIMEOUT; ///<@copydoc C::MIP_NACK_COMMAND_TIMEOUT + +#ifndef _WIN32 // Avoid name conflict with windows.h + static constexpr C::mip_cmd_result STATUS_PENDING = STATUS_QUEUED; +#endif + + C::mip_cmd_result value = C::MIP_STATUS_NONE; + + constexpr CmdResult() : value(C::MIP_ACK_OK) {} + constexpr CmdResult(C::mip_cmd_result result) : value(result) {} + ~CmdResult() = default; + + CmdResult& operator=(const CmdResult& other) = default; + CmdResult& operator=(C::mip_cmd_result other) { value = other; return *this; } + + static constexpr CmdResult userResult(uint8_t n) { return CmdResult(static_cast(STATUS_USER - int8_t(n))); } + static constexpr CmdResult fromAckNack(uint8_t code) { return CmdResult(static_cast(code)); } + + operator const void*() const { return isAck() ? this : nullptr; } + bool operator!() const { return !isAck(); } + + constexpr bool operator==(CmdResult other) const { return value == other.value; } + constexpr bool operator!=(CmdResult other) const { return value != other.value; } + + constexpr bool operator==(C::mip_cmd_result other) const { return value == other; } + constexpr bool operator!=(C::mip_cmd_result other) const { return value != other; } + + const char* name() const { return C::mip_cmd_result_to_string(value); } + + bool isReplyCode() const { return C::mip_cmd_result_is_reply(value); } + bool isStatusCode() const { return C::mip_cmd_result_is_status(value); } + bool isFinished() const { return C::mip_cmd_result_is_finished(value); } + bool isAck() const { return C::mip_cmd_result_is_ack(value); } +}; + +///@} +//////////////////////////////////////////////////////////////////////////////// +} // namespace mip From 62a71d3425fce0ffab3d54ef6c7363d48eaf360a Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 29 May 2024 14:29:04 -0400 Subject: [PATCH 015/147] Fix warnings and possible endless recursion in Buffer.hpp. --- src/microstrain/common/buffer.hpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/microstrain/common/buffer.hpp b/src/microstrain/common/buffer.hpp index b9838361a..ef0c2a959 100644 --- a/src/microstrain/common/buffer.hpp +++ b/src/microstrain/common/buffer.hpp @@ -115,7 +115,7 @@ class Buffer size_t capacity() const { return m_size; } size_t length() const { return m_size; } size_t offset() const { return m_offset; } - int remaining() const { return m_size - m_offset; } + int remaining() const { return int(m_size - m_offset); } bool noRemaining() const { return m_offset == m_size; } bool isOverrun() const { return m_offset > m_size; } @@ -130,7 +130,7 @@ class Buffer uint8_t* getPtrAndAdvance(size_t size) { uint8_t* ptr = hasRemaining(size) ? (m_ptr+m_offset) : nullptr; m_offset += size; return ptr; } - void invalidate() { m_offset = -1U; } + void invalidate() { m_offset = size_t(-1); } template bool insert(const Ts&... values); @@ -198,7 +198,8 @@ typename std::enable_if::value, size_t>::type #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template -size_t insert(Buffer& buffer, Ts... values) +typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type +/*size_t*/ insert(Buffer& buffer, Ts... values) { if constexpr( (std::is_arithmetic::value && ...) ) { @@ -279,7 +280,8 @@ typename std::enable_if::value, size_t>::type #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template -size_t extract(Buffer& buffer, Ts&... values) +typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type +/*size_t*/ extract(Buffer& buffer, Ts&... values) { if constexpr( (std::is_arithmetic::value && ...) ) { From 9f2d694b5f79074b1eafe3d0a2f4febb5b9ccf87 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 29 May 2024 14:30:02 -0400 Subject: [PATCH 016/147] Remove c++ includes from mip_descriptors.c --- src/mip/mip_descriptors.h | 6 ------ 1 file changed, 6 deletions(-) diff --git a/src/mip/mip_descriptors.h b/src/mip/mip_descriptors.h index 2d5c3b264..468c8cf56 100644 --- a/src/mip/mip_descriptors.h +++ b/src/mip/mip_descriptors.h @@ -7,12 +7,6 @@ #include "mip_result.h" #ifdef __cplusplus -#include "microstrain/common/buffer.hpp" - -#include -#include -#include - namespace mip { namespace C { using ::microstrain::C::microstrain_serializer; From 3ba6d4c2e41f06987cc3708319e75ba14b162d0a Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 29 May 2024 14:30:25 -0400 Subject: [PATCH 017/147] Fix warnings and add some more checks to AllocatedField::commit(). --- src/mip/mip_packet.hpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/mip/mip_packet.hpp b/src/mip/mip_packet.hpp index 6bc663665..1529e3f5e 100644 --- a/src/mip/mip_packet.hpp +++ b/src/mip/mip_packet.hpp @@ -90,11 +90,14 @@ class PacketRef : public C::mip_packet bool commit() { + assert(capacity() <= FIELD_PAYLOAD_LENGTH_MAX); + bool ok = isOk(); if(ok) - C::mip_packet_realloc_last_field(&m_packet, basePointer(), length()); - else + ok &= C::mip_packet_realloc_last_field(&m_packet, basePointer(), (uint8_t)length()) >= 0; + + if(!ok) C::mip_packet_cancel_last_field(&m_packet, basePointer()); return ok; From 891fe21142601d904a78dda4099a06b8aa9b6d1e Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 31 May 2024 17:57:54 -0400 Subject: [PATCH 018/147] Rename Buffer to Serializer. --- examples/watch_imu.cpp | 2 +- src/microstrain/common/CMakeLists.txt | 2 +- .../common/{buffer.hpp => serialization.hpp} | 51 +- src/mip/definitions/commands_3dm.cpp | 1100 +++++++------- src/mip/definitions/commands_3dm.hpp | 390 ++--- src/mip/definitions/commands_aiding.cpp | 138 +- src/mip/definitions/commands_aiding.hpp | 56 +- src/mip/definitions/commands_base.cpp | 112 +- src/mip/definitions/commands_base.hpp | 74 +- src/mip/definitions/commands_filter.cpp | 1340 ++++++++--------- src/mip/definitions/commands_filter.hpp | 380 ++--- src/mip/definitions/commands_gnss.cpp | 76 +- src/mip/definitions/commands_gnss.hpp | 28 +- src/mip/definitions/commands_rtk.cpp | 136 +- src/mip/definitions/commands_rtk.hpp | 84 +- src/mip/definitions/commands_system.cpp | 24 +- src/mip/definitions/commands_system.hpp | 8 +- src/mip/definitions/common.hpp | 10 +- src/mip/definitions/data_filter.cpp | 230 +-- src/mip/definitions/data_filter.hpp | 228 +-- src/mip/definitions/data_gnss.cpp | 110 +- src/mip/definitions/data_gnss.hpp | 108 +- src/mip/definitions/data_sensor.cpp | 94 +- src/mip/definitions/data_sensor.hpp | 92 +- src/mip/definitions/data_shared.cpp | 38 +- src/mip/definitions/data_shared.hpp | 36 +- src/mip/definitions/data_system.cpp | 18 +- src/mip/definitions/data_system.hpp | 16 +- src/mip/mip_descriptors.hpp | 6 +- src/mip/mip_packet.h | 2 +- src/mip/mip_packet.hpp | 8 +- 31 files changed, 2496 insertions(+), 2501 deletions(-) rename src/microstrain/common/{buffer.hpp => serialization.hpp} (84%) diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index e5b6692c3..76c116643 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -3,7 +3,7 @@ #include #include -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include #include diff --git a/src/microstrain/common/CMakeLists.txt b/src/microstrain/common/CMakeLists.txt index e582a5082..c90dca4b1 100644 --- a/src/microstrain/common/CMakeLists.txt +++ b/src/microstrain/common/CMakeLists.txt @@ -4,7 +4,7 @@ set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max set(SOURCES - buffer.hpp + serialization.hpp connection.hpp descriptor_id.hpp index.hpp diff --git a/src/microstrain/common/buffer.hpp b/src/microstrain/common/serialization.hpp similarity index 84% rename from src/microstrain/common/buffer.hpp rename to src/microstrain/common/serialization.hpp index ef0c2a959..4fb5645b2 100644 --- a/src/microstrain/common/buffer.hpp +++ b/src/microstrain/common/serialization.hpp @@ -4,6 +4,7 @@ #include #include +#include namespace microstrain @@ -105,12 +106,12 @@ typename std::enable_if::value && sizeof(T)==8, size_t>::t } -class Buffer +class Serializer { public: - Buffer() = default; - Buffer(uint8_t* ptr, size_t capacity, size_t offset=0) : m_ptr(ptr), m_size(capacity), m_offset(offset) {} - Buffer(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} + Serializer() = default; + Serializer(uint8_t* ptr, size_t capacity, size_t offset=0) : m_ptr(ptr), m_size(capacity), m_offset(offset) {} + Serializer(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} size_t capacity() const { return m_size; } size_t length() const { return m_size; } @@ -167,7 +168,7 @@ class Buffer // Built-in types (bool, int, float, ...) template typename std::enable_if::value, size_t>::type -/*size_t*/ insert(Buffer& buffer, T value) +/*size_t*/ insert(Serializer& buffer, T value) { if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) write(ptr, value); @@ -178,7 +179,7 @@ typename std::enable_if::value, size_t>::type // Enums template typename std::enable_if::value, size_t>::type -/*size_t*/ insert(Buffer& buffer, T value) +/*size_t*/ insert(Serializer& buffer, T value) { using BaseType = typename std::underlying_type::type; @@ -188,18 +189,10 @@ typename std::enable_if::value, size_t>::type return sizeof(BaseType); } -//// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. -//template -//typename std::enable_if::value, size_t>::type -///*size_t*/ insert(Buffer& buffer, const T& value) -//{ -// return value.serialize(buffer); -//} - #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type -/*size_t*/ insert(Buffer& buffer, Ts... values) +/*size_t*/ insert(Serializer& buffer, Ts... values) { if constexpr( (std::is_arithmetic::value && ...) ) { @@ -245,7 +238,7 @@ size_t insert(Buffer& buffer, T0 value0, Ts... values) // Built-in types (bool, int, float, ...) template typename std::enable_if::value, size_t>::type -/*size_t*/ extract(Buffer& buffer, T& value) +/*size_t*/ extract(Serializer& buffer, T& value) { if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) read(ptr, value); @@ -256,7 +249,7 @@ typename std::enable_if::value, size_t>::type // Enums template typename std::enable_if::value, size_t>::type -/*size_t*/ extract(Buffer& buffer, T& value) +/*size_t*/ extract(Serializer& buffer, T& value) { using BaseType = typename std::underlying_type::type; @@ -270,18 +263,18 @@ typename std::enable_if::value, size_t>::type return sizeof(BaseType); } -//// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. -//template -//typename std::enable_if::value, size_t>::type -///*size_t*/ extract(Buffer& buffer, T& value) -//{ -// return value.deserialize(buffer); -//} +// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. +template +typename std::enable_if::value, size_t>::type +/*size_t*/ extract(Serializer& buffer, T& value) +{ + return value.deserialize(buffer); +} #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type -/*size_t*/ extract(Buffer& buffer, Ts&... values) +/*size_t*/ extract(Serializer& buffer, Ts&... values) { if constexpr( (std::is_arithmetic::value && ...) ) { @@ -321,7 +314,7 @@ size_t extract(Buffer& buffer, T0 value0, Ts... values) //} template -size_t extract_count(Buffer& buffer, T& count, size_t max_count) +size_t extract_count(Serializer& buffer, T& count, size_t max_count) { T tmp; size_t size = extract(buffer, tmp); @@ -334,15 +327,15 @@ size_t extract_count(Buffer& buffer, T& count, size_t max_count) return size; } template -size_t extract_count(Buffer& buffer, T* count, size_t max_count) { return extract_count(buffer, *count, max_count); } +size_t extract_count(Serializer& buffer, T* count, size_t max_count) { return extract_count(buffer, *count, max_count); } template -bool Buffer::insert(const Ts&... values) { return microstrain::insert(*this, values...); } +bool Serializer::insert(const Ts&... values) { return microstrain::insert(*this, values...); } template -bool Buffer::extract(Ts&... values) { return microstrain::extract(*this, values...); } +bool Serializer::extract(Ts&... values) { return microstrain::extract(*this, values...); } } // namespace microstrain diff --git a/src/mip/definitions/commands_3dm.cpp b/src/mip/definitions/commands_3dm.cpp index 2a705af6e..9ccc8d28c 100644 --- a/src/mip/definitions/commands_3dm.cpp +++ b/src/mip/definitions/commands_3dm.cpp @@ -1,7 +1,7 @@ #include "commands_3dm.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -21,7 +21,7 @@ using ::microstrain::extract; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const NmeaMessage& self) +void insert(::microstrain::Serializer& serializer, const NmeaMessage& self) { insert(serializer, self.message_id); @@ -32,7 +32,7 @@ void insert(::microstrain::Buffer& serializer, const NmeaMessage& self) insert(serializer, self.decimation); } -void extract(::microstrain::Buffer& serializer, NmeaMessage& self) +void extract(::microstrain::Serializer& serializer, NmeaMessage& self) { extract(serializer, self.message_id); @@ -49,7 +49,7 @@ void extract(::microstrain::Buffer& serializer, NmeaMessage& self) // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const PollImuMessage& self) +void insert(::microstrain::Serializer& serializer, const PollImuMessage& self) { insert(serializer, self.suppress_ack); @@ -59,7 +59,7 @@ void insert(::microstrain::Buffer& serializer, const PollImuMessage& self) insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, PollImuMessage& self) +void extract(::microstrain::Serializer& serializer, PollImuMessage& self) { extract(serializer, self.suppress_ack); @@ -71,8 +71,8 @@ void extract(::microstrain::Buffer& serializer, PollImuMessage& self) TypedResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -86,7 +86,7 @@ TypedResult pollImuMessage(C::mip_interface& device, bool suppre return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_IMU_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const PollGnssMessage& self) +void insert(::microstrain::Serializer& serializer, const PollGnssMessage& self) { insert(serializer, self.suppress_ack); @@ -96,7 +96,7 @@ void insert(::microstrain::Buffer& serializer, const PollGnssMessage& self) insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, PollGnssMessage& self) +void extract(::microstrain::Serializer& serializer, PollGnssMessage& self) { extract(serializer, self.suppress_ack); @@ -108,8 +108,8 @@ void extract(::microstrain::Buffer& serializer, PollGnssMessage& self) TypedResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -123,7 +123,7 @@ TypedResult pollGnssMessage(C::mip_interface& device, bool supp return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_GNSS_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const PollFilterMessage& self) +void insert(::microstrain::Serializer& serializer, const PollFilterMessage& self) { insert(serializer, self.suppress_ack); @@ -133,7 +133,7 @@ void insert(::microstrain::Buffer& serializer, const PollFilterMessage& self) insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, PollFilterMessage& self) +void extract(::microstrain::Serializer& serializer, PollFilterMessage& self) { extract(serializer, self.suppress_ack); @@ -145,8 +145,8 @@ void extract(::microstrain::Buffer& serializer, PollFilterMessage& self) TypedResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -160,7 +160,7 @@ TypedResult pollFilterMessage(C::mip_interface& device, bool return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_FILTER_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ImuMessageFormat& self) +void insert(::microstrain::Serializer& serializer, const ImuMessageFormat& self) { insert(serializer, self.function); @@ -173,7 +173,7 @@ void insert(::microstrain::Buffer& serializer, const ImuMessageFormat& self) } } -void extract(::microstrain::Buffer& serializer, ImuMessageFormat& self) +void extract(::microstrain::Serializer& serializer, ImuMessageFormat& self) { extract(serializer, self.function); @@ -186,7 +186,7 @@ void extract(::microstrain::Buffer& serializer, ImuMessageFormat& self) } } -void insert(::microstrain::Buffer& serializer, const ImuMessageFormat::Response& self) +void insert(::microstrain::Serializer& serializer, const ImuMessageFormat::Response& self) { insert(serializer, self.num_descriptors); @@ -194,7 +194,7 @@ void insert(::microstrain::Buffer& serializer, const ImuMessageFormat::Response& insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, ImuMessageFormat::Response& self) +void extract(::microstrain::Serializer& serializer, ImuMessageFormat::Response& self) { extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) @@ -204,8 +204,8 @@ void extract(::microstrain::Buffer& serializer, ImuMessageFormat::Response& self TypedResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, numDescriptors); @@ -220,8 +220,8 @@ TypedResult writeImuMessageFormat(C::mip_interface& device, ui } TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -231,7 +231,7 @@ TypedResult readImuMessageFormat(C::mip_interface& device, uin if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); @@ -245,8 +245,8 @@ TypedResult readImuMessageFormat(C::mip_interface& device, uin } TypedResult saveImuMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -255,8 +255,8 @@ TypedResult saveImuMessageFormat(C::mip_interface& device) } TypedResult loadImuMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -265,15 +265,15 @@ TypedResult loadImuMessageFormat(C::mip_interface& device) } TypedResult defaultImuMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GpsMessageFormat& self) +void insert(::microstrain::Serializer& serializer, const GpsMessageFormat& self) { insert(serializer, self.function); @@ -286,7 +286,7 @@ void insert(::microstrain::Buffer& serializer, const GpsMessageFormat& self) } } -void extract(::microstrain::Buffer& serializer, GpsMessageFormat& self) +void extract(::microstrain::Serializer& serializer, GpsMessageFormat& self) { extract(serializer, self.function); @@ -299,7 +299,7 @@ void extract(::microstrain::Buffer& serializer, GpsMessageFormat& self) } } -void insert(::microstrain::Buffer& serializer, const GpsMessageFormat::Response& self) +void insert(::microstrain::Serializer& serializer, const GpsMessageFormat::Response& self) { insert(serializer, self.num_descriptors); @@ -307,7 +307,7 @@ void insert(::microstrain::Buffer& serializer, const GpsMessageFormat::Response& insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, GpsMessageFormat::Response& self) +void extract(::microstrain::Serializer& serializer, GpsMessageFormat::Response& self) { extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) @@ -317,8 +317,8 @@ void extract(::microstrain::Buffer& serializer, GpsMessageFormat::Response& self TypedResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, numDescriptors); @@ -333,8 +333,8 @@ TypedResult writeGpsMessageFormat(C::mip_interface& device, ui } TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -344,7 +344,7 @@ TypedResult readGpsMessageFormat(C::mip_interface& device, uin if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); @@ -358,8 +358,8 @@ TypedResult readGpsMessageFormat(C::mip_interface& device, uin } TypedResult saveGpsMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -368,8 +368,8 @@ TypedResult saveGpsMessageFormat(C::mip_interface& device) } TypedResult loadGpsMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -378,15 +378,15 @@ TypedResult loadGpsMessageFormat(C::mip_interface& device) } TypedResult defaultGpsMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const FilterMessageFormat& self) +void insert(::microstrain::Serializer& serializer, const FilterMessageFormat& self) { insert(serializer, self.function); @@ -399,7 +399,7 @@ void insert(::microstrain::Buffer& serializer, const FilterMessageFormat& self) } } -void extract(::microstrain::Buffer& serializer, FilterMessageFormat& self) +void extract(::microstrain::Serializer& serializer, FilterMessageFormat& self) { extract(serializer, self.function); @@ -412,7 +412,7 @@ void extract(::microstrain::Buffer& serializer, FilterMessageFormat& self) } } -void insert(::microstrain::Buffer& serializer, const FilterMessageFormat::Response& self) +void insert(::microstrain::Serializer& serializer, const FilterMessageFormat::Response& self) { insert(serializer, self.num_descriptors); @@ -420,7 +420,7 @@ void insert(::microstrain::Buffer& serializer, const FilterMessageFormat::Respon insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, FilterMessageFormat::Response& self) +void extract(::microstrain::Serializer& serializer, FilterMessageFormat::Response& self) { extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); for(unsigned int i=0; i < self.num_descriptors; i++) @@ -430,8 +430,8 @@ void extract(::microstrain::Buffer& serializer, FilterMessageFormat::Response& s TypedResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, numDescriptors); @@ -446,8 +446,8 @@ TypedResult writeFilterMessageFormat(C::mip_interface& devi } TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -457,7 +457,7 @@ TypedResult readFilterMessageFormat(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); @@ -471,8 +471,8 @@ TypedResult readFilterMessageFormat(C::mip_interface& devic } TypedResult saveFilterMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -481,8 +481,8 @@ TypedResult saveFilterMessageFormat(C::mip_interface& devic } TypedResult loadFilterMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -491,31 +491,31 @@ TypedResult loadFilterMessageFormat(C::mip_interface& devic } TypedResult defaultFilterMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ImuGetBaseRate& self) +void insert(::microstrain::Serializer& serializer, const ImuGetBaseRate& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, ImuGetBaseRate& self) +void extract(::microstrain::Serializer& serializer, ImuGetBaseRate& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const ImuGetBaseRate::Response& self) +void insert(::microstrain::Serializer& serializer, const ImuGetBaseRate::Response& self) { insert(serializer, self.rate); } -void extract(::microstrain::Buffer& serializer, ImuGetBaseRate::Response& self) +void extract(::microstrain::Serializer& serializer, ImuGetBaseRate::Response& self) { extract(serializer, self.rate); @@ -530,7 +530,7 @@ TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* r if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(rateOut); extract(deserializer, *rateOut); @@ -540,23 +540,23 @@ TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* r } return result; } -void insert(::microstrain::Buffer& serializer, const GpsGetBaseRate& self) +void insert(::microstrain::Serializer& serializer, const GpsGetBaseRate& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GpsGetBaseRate& self) +void extract(::microstrain::Serializer& serializer, GpsGetBaseRate& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GpsGetBaseRate::Response& self) +void insert(::microstrain::Serializer& serializer, const GpsGetBaseRate::Response& self) { insert(serializer, self.rate); } -void extract(::microstrain::Buffer& serializer, GpsGetBaseRate::Response& self) +void extract(::microstrain::Serializer& serializer, GpsGetBaseRate::Response& self) { extract(serializer, self.rate); @@ -571,7 +571,7 @@ TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* r if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(rateOut); extract(deserializer, *rateOut); @@ -581,23 +581,23 @@ TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* r } return result; } -void insert(::microstrain::Buffer& serializer, const FilterGetBaseRate& self) +void insert(::microstrain::Serializer& serializer, const FilterGetBaseRate& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, FilterGetBaseRate& self) +void extract(::microstrain::Serializer& serializer, FilterGetBaseRate& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const FilterGetBaseRate::Response& self) +void insert(::microstrain::Serializer& serializer, const FilterGetBaseRate::Response& self) { insert(serializer, self.rate); } -void extract(::microstrain::Buffer& serializer, FilterGetBaseRate::Response& self) +void extract(::microstrain::Serializer& serializer, FilterGetBaseRate::Response& self) { extract(serializer, self.rate); @@ -612,7 +612,7 @@ TypedResult filterGetBaseRate(C::mip_interface& device, uint1 if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(rateOut); extract(deserializer, *rateOut); @@ -622,7 +622,7 @@ TypedResult filterGetBaseRate(C::mip_interface& device, uint1 } return result; } -void insert(::microstrain::Buffer& serializer, const PollData& self) +void insert(::microstrain::Serializer& serializer, const PollData& self) { insert(serializer, self.desc_set); @@ -634,7 +634,7 @@ void insert(::microstrain::Buffer& serializer, const PollData& self) insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, PollData& self) +void extract(::microstrain::Serializer& serializer, PollData& self) { extract(serializer, self.desc_set); @@ -648,8 +648,8 @@ void extract(::microstrain::Buffer& serializer, PollData& self) TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, descSet); @@ -665,25 +665,25 @@ TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool s return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_DATA, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GetBaseRate& self) +void insert(::microstrain::Serializer& serializer, const GetBaseRate& self) { insert(serializer, self.desc_set); } -void extract(::microstrain::Buffer& serializer, GetBaseRate& self) +void extract(::microstrain::Serializer& serializer, GetBaseRate& self) { extract(serializer, self.desc_set); } -void insert(::microstrain::Buffer& serializer, const GetBaseRate::Response& self) +void insert(::microstrain::Serializer& serializer, const GetBaseRate::Response& self) { insert(serializer, self.desc_set); insert(serializer, self.rate); } -void extract(::microstrain::Buffer& serializer, GetBaseRate::Response& self) +void extract(::microstrain::Serializer& serializer, GetBaseRate::Response& self) { extract(serializer, self.desc_set); @@ -693,8 +693,8 @@ void extract(::microstrain::Buffer& serializer, GetBaseRate::Response& self) TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, descSet); @@ -705,7 +705,7 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -717,7 +717,7 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, } return result; } -void insert(::microstrain::Buffer& serializer, const MessageFormat& self) +void insert(::microstrain::Serializer& serializer, const MessageFormat& self) { insert(serializer, self.function); @@ -732,7 +732,7 @@ void insert(::microstrain::Buffer& serializer, const MessageFormat& self) } } -void extract(::microstrain::Buffer& serializer, MessageFormat& self) +void extract(::microstrain::Serializer& serializer, MessageFormat& self) { extract(serializer, self.function); @@ -747,7 +747,7 @@ void extract(::microstrain::Buffer& serializer, MessageFormat& self) } } -void insert(::microstrain::Buffer& serializer, const MessageFormat::Response& self) +void insert(::microstrain::Serializer& serializer, const MessageFormat::Response& self) { insert(serializer, self.desc_set); @@ -757,7 +757,7 @@ void insert(::microstrain::Buffer& serializer, const MessageFormat::Response& se insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, MessageFormat::Response& self) +void extract(::microstrain::Serializer& serializer, MessageFormat::Response& self) { extract(serializer, self.desc_set); @@ -769,8 +769,8 @@ void extract(::microstrain::Buffer& serializer, MessageFormat::Response& self) TypedResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, descSet); @@ -787,8 +787,8 @@ TypedResult writeMessageFormat(C::mip_interface& device, uint8_t } TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, descSet); @@ -800,7 +800,7 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -816,8 +816,8 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d } TypedResult saveMessageFormat(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, descSet); @@ -828,8 +828,8 @@ TypedResult saveMessageFormat(C::mip_interface& device, uint8_t d } TypedResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, descSet); @@ -840,8 +840,8 @@ TypedResult loadMessageFormat(C::mip_interface& device, uint8_t d } TypedResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, descSet); @@ -850,7 +850,7 @@ TypedResult defaultMessageFormat(C::mip_interface& device, uint8_ return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const NmeaPollData& self) +void insert(::microstrain::Serializer& serializer, const NmeaPollData& self) { insert(serializer, self.suppress_ack); @@ -860,7 +860,7 @@ void insert(::microstrain::Buffer& serializer, const NmeaPollData& self) insert(serializer, self.format_entries[i]); } -void extract(::microstrain::Buffer& serializer, NmeaPollData& self) +void extract(::microstrain::Serializer& serializer, NmeaPollData& self) { extract(serializer, self.suppress_ack); @@ -872,8 +872,8 @@ void extract(::microstrain::Buffer& serializer, NmeaPollData& self) TypedResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, suppressAck); @@ -887,7 +887,7 @@ TypedResult nmeaPollData(C::mip_interface& device, bool suppressAc return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_NMEA_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat& self) +void insert(::microstrain::Serializer& serializer, const NmeaMessageFormat& self) { insert(serializer, self.function); @@ -900,7 +900,7 @@ void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat& self) } } -void extract(::microstrain::Buffer& serializer, NmeaMessageFormat& self) +void extract(::microstrain::Serializer& serializer, NmeaMessageFormat& self) { extract(serializer, self.function); @@ -913,7 +913,7 @@ void extract(::microstrain::Buffer& serializer, NmeaMessageFormat& self) } } -void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat::Response& self) +void insert(::microstrain::Serializer& serializer, const NmeaMessageFormat::Response& self) { insert(serializer, self.count); @@ -921,7 +921,7 @@ void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat::Response insert(serializer, self.format_entries[i]); } -void extract(::microstrain::Buffer& serializer, NmeaMessageFormat::Response& self) +void extract(::microstrain::Serializer& serializer, NmeaMessageFormat::Response& self) { extract_count(serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); for(unsigned int i=0; i < self.count; i++) @@ -931,8 +931,8 @@ void extract(::microstrain::Buffer& serializer, NmeaMessageFormat::Response& sel TypedResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, count); @@ -947,8 +947,8 @@ TypedResult writeNmeaMessageFormat(C::mip_interface& device, } TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -958,7 +958,7 @@ TypedResult readNmeaMessageFormat(C::mip_interface& device, u if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract_count(deserializer, countOut, countOutMax); assert(formatEntriesOut || (countOut == 0)); @@ -972,8 +972,8 @@ TypedResult readNmeaMessageFormat(C::mip_interface& device, u } TypedResult saveNmeaMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -982,8 +982,8 @@ TypedResult saveNmeaMessageFormat(C::mip_interface& device) } TypedResult loadNmeaMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -992,20 +992,20 @@ TypedResult loadNmeaMessageFormat(C::mip_interface& device) } TypedResult defaultNmeaMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const DeviceSettings& self) +void insert(::microstrain::Serializer& serializer, const DeviceSettings& self) { insert(serializer, self.function); } -void extract(::microstrain::Buffer& serializer, DeviceSettings& self) +void extract(::microstrain::Serializer& serializer, DeviceSettings& self) { extract(serializer, self.function); @@ -1013,8 +1013,8 @@ void extract(::microstrain::Buffer& serializer, DeviceSettings& self) TypedResult saveDeviceSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1023,8 +1023,8 @@ TypedResult saveDeviceSettings(C::mip_interface& device) } TypedResult loadDeviceSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1033,15 +1033,15 @@ TypedResult loadDeviceSettings(C::mip_interface& device) } TypedResult defaultDeviceSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const UartBaudrate& self) +void insert(::microstrain::Serializer& serializer, const UartBaudrate& self) { insert(serializer, self.function); @@ -1051,7 +1051,7 @@ void insert(::microstrain::Buffer& serializer, const UartBaudrate& self) } } -void extract(::microstrain::Buffer& serializer, UartBaudrate& self) +void extract(::microstrain::Serializer& serializer, UartBaudrate& self) { extract(serializer, self.function); @@ -1062,12 +1062,12 @@ void extract(::microstrain::Buffer& serializer, UartBaudrate& self) } } -void insert(::microstrain::Buffer& serializer, const UartBaudrate::Response& self) +void insert(::microstrain::Serializer& serializer, const UartBaudrate::Response& self) { insert(serializer, self.baud); } -void extract(::microstrain::Buffer& serializer, UartBaudrate::Response& self) +void extract(::microstrain::Serializer& serializer, UartBaudrate::Response& self) { extract(serializer, self.baud); @@ -1075,8 +1075,8 @@ void extract(::microstrain::Buffer& serializer, UartBaudrate::Response& self) TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, baud); @@ -1087,8 +1087,8 @@ TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t b } TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1098,7 +1098,7 @@ TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* b if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(baudOut); extract(deserializer, *baudOut); @@ -1110,8 +1110,8 @@ TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* b } TypedResult saveUartBaudrate(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1120,8 +1120,8 @@ TypedResult saveUartBaudrate(C::mip_interface& device) } TypedResult loadUartBaudrate(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1130,22 +1130,22 @@ TypedResult loadUartBaudrate(C::mip_interface& device) } TypedResult defaultUartBaudrate(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const FactoryStreaming& self) +void insert(::microstrain::Serializer& serializer, const FactoryStreaming& self) { insert(serializer, self.action); insert(serializer, self.reserved); } -void extract(::microstrain::Buffer& serializer, FactoryStreaming& self) +void extract(::microstrain::Serializer& serializer, FactoryStreaming& self) { extract(serializer, self.action); @@ -1155,8 +1155,8 @@ void extract(::microstrain::Buffer& serializer, FactoryStreaming& self) TypedResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, action); @@ -1166,7 +1166,7 @@ TypedResult factoryStreaming(C::mip_interface& device, Factory return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const DatastreamControl& self) +void insert(::microstrain::Serializer& serializer, const DatastreamControl& self) { insert(serializer, self.function); @@ -1178,7 +1178,7 @@ void insert(::microstrain::Buffer& serializer, const DatastreamControl& self) } } -void extract(::microstrain::Buffer& serializer, DatastreamControl& self) +void extract(::microstrain::Serializer& serializer, DatastreamControl& self) { extract(serializer, self.function); @@ -1191,14 +1191,14 @@ void extract(::microstrain::Buffer& serializer, DatastreamControl& self) } } -void insert(::microstrain::Buffer& serializer, const DatastreamControl::Response& self) +void insert(::microstrain::Serializer& serializer, const DatastreamControl::Response& self) { insert(serializer, self.desc_set); insert(serializer, self.enabled); } -void extract(::microstrain::Buffer& serializer, DatastreamControl::Response& self) +void extract(::microstrain::Serializer& serializer, DatastreamControl::Response& self) { extract(serializer, self.desc_set); @@ -1208,8 +1208,8 @@ void extract(::microstrain::Buffer& serializer, DatastreamControl::Response& sel TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, descSet); @@ -1222,8 +1222,8 @@ TypedResult writeDatastreamControl(C::mip_interface& device, } TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, descSet); @@ -1235,7 +1235,7 @@ TypedResult readDatastreamControl(C::mip_interface& device, u if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -1249,8 +1249,8 @@ TypedResult readDatastreamControl(C::mip_interface& device, u } TypedResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, descSet); @@ -1261,8 +1261,8 @@ TypedResult saveDatastreamControl(C::mip_interface& device, u } TypedResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, descSet); @@ -1273,8 +1273,8 @@ TypedResult loadDatastreamControl(C::mip_interface& device, u } TypedResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, descSet); @@ -1283,7 +1283,7 @@ TypedResult defaultDatastreamControl(C::mip_interface& device return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ConstellationSettings& self) +void insert(::microstrain::Serializer& serializer, const ConstellationSettings& self) { insert(serializer, self.function); @@ -1298,7 +1298,7 @@ void insert(::microstrain::Buffer& serializer, const ConstellationSettings& self } } -void extract(::microstrain::Buffer& serializer, ConstellationSettings& self) +void extract(::microstrain::Serializer& serializer, ConstellationSettings& self) { extract(serializer, self.function); @@ -1313,7 +1313,7 @@ void extract(::microstrain::Buffer& serializer, ConstellationSettings& self) } } -void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Response& self) +void insert(::microstrain::Serializer& serializer, const ConstellationSettings::Response& self) { insert(serializer, self.max_channels_available); @@ -1325,7 +1325,7 @@ void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Resp insert(serializer, self.settings[i]); } -void extract(::microstrain::Buffer& serializer, ConstellationSettings::Response& self) +void extract(::microstrain::Serializer& serializer, ConstellationSettings::Response& self) { extract(serializer, self.max_channels_available); @@ -1337,7 +1337,7 @@ void extract(::microstrain::Buffer& serializer, ConstellationSettings::Response& } -void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Settings& self) +void insert(::microstrain::Serializer& serializer, const ConstellationSettings::Settings& self) { insert(serializer, self.constellation_id); @@ -1350,7 +1350,7 @@ void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Sett insert(serializer, self.option_flags); } -void extract(::microstrain::Buffer& serializer, ConstellationSettings::Settings& self) +void extract(::microstrain::Serializer& serializer, ConstellationSettings::Settings& self) { extract(serializer, self.constellation_id); @@ -1366,8 +1366,8 @@ void extract(::microstrain::Buffer& serializer, ConstellationSettings::Settings& TypedResult writeConstellationSettings(C::mip_interface& device, uint16_t maxChannels, uint8_t configCount, const ConstellationSettings::Settings* settings) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, maxChannels); @@ -1384,8 +1384,8 @@ TypedResult writeConstellationSettings(C::mip_interface& } TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1395,7 +1395,7 @@ TypedResult readConstellationSettings(C::mip_interface& d if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(maxChannelsAvailableOut); extract(deserializer, *maxChannelsAvailableOut); @@ -1415,8 +1415,8 @@ TypedResult readConstellationSettings(C::mip_interface& d } TypedResult saveConstellationSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1425,8 +1425,8 @@ TypedResult saveConstellationSettings(C::mip_interface& d } TypedResult loadConstellationSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1435,15 +1435,15 @@ TypedResult loadConstellationSettings(C::mip_interface& d } TypedResult defaultConstellationSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GnssSbasSettings& self) +void insert(::microstrain::Serializer& serializer, const GnssSbasSettings& self) { insert(serializer, self.function); @@ -1460,7 +1460,7 @@ void insert(::microstrain::Buffer& serializer, const GnssSbasSettings& self) } } -void extract(::microstrain::Buffer& serializer, GnssSbasSettings& self) +void extract(::microstrain::Serializer& serializer, GnssSbasSettings& self) { extract(serializer, self.function); @@ -1477,7 +1477,7 @@ void extract(::microstrain::Buffer& serializer, GnssSbasSettings& self) } } -void insert(::microstrain::Buffer& serializer, const GnssSbasSettings::Response& self) +void insert(::microstrain::Serializer& serializer, const GnssSbasSettings::Response& self) { insert(serializer, self.enable_sbas); @@ -1489,7 +1489,7 @@ void insert(::microstrain::Buffer& serializer, const GnssSbasSettings::Response& insert(serializer, self.included_prns[i]); } -void extract(::microstrain::Buffer& serializer, GnssSbasSettings::Response& self) +void extract(::microstrain::Serializer& serializer, GnssSbasSettings::Response& self) { extract(serializer, self.enable_sbas); @@ -1503,8 +1503,8 @@ void extract(::microstrain::Buffer& serializer, GnssSbasSettings::Response& self TypedResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enableSbas); @@ -1523,8 +1523,8 @@ TypedResult writeGnssSbasSettings(C::mip_interface& device, ui } TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1534,7 +1534,7 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableSbasOut); extract(deserializer, *enableSbasOut); @@ -1554,8 +1554,8 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin } TypedResult saveGnssSbasSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1564,8 +1564,8 @@ TypedResult saveGnssSbasSettings(C::mip_interface& device) } TypedResult loadGnssSbasSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1574,15 +1574,15 @@ TypedResult loadGnssSbasSettings(C::mip_interface& device) } TypedResult defaultGnssSbasSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GnssAssistedFix& self) +void insert(::microstrain::Serializer& serializer, const GnssAssistedFix& self) { insert(serializer, self.function); @@ -1594,7 +1594,7 @@ void insert(::microstrain::Buffer& serializer, const GnssAssistedFix& self) } } -void extract(::microstrain::Buffer& serializer, GnssAssistedFix& self) +void extract(::microstrain::Serializer& serializer, GnssAssistedFix& self) { extract(serializer, self.function); @@ -1607,14 +1607,14 @@ void extract(::microstrain::Buffer& serializer, GnssAssistedFix& self) } } -void insert(::microstrain::Buffer& serializer, const GnssAssistedFix::Response& self) +void insert(::microstrain::Serializer& serializer, const GnssAssistedFix::Response& self) { insert(serializer, self.option); insert(serializer, self.flags); } -void extract(::microstrain::Buffer& serializer, GnssAssistedFix::Response& self) +void extract(::microstrain::Serializer& serializer, GnssAssistedFix::Response& self) { extract(serializer, self.option); @@ -1624,8 +1624,8 @@ void extract(::microstrain::Buffer& serializer, GnssAssistedFix::Response& self) TypedResult writeGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption option, uint8_t flags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, option); @@ -1638,8 +1638,8 @@ TypedResult writeGnssAssistedFix(C::mip_interface& device, Gnss } TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1649,7 +1649,7 @@ TypedResult readGnssAssistedFix(C::mip_interface& device, GnssA if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(optionOut); extract(deserializer, *optionOut); @@ -1664,8 +1664,8 @@ TypedResult readGnssAssistedFix(C::mip_interface& device, GnssA } TypedResult saveGnssAssistedFix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1674,8 +1674,8 @@ TypedResult saveGnssAssistedFix(C::mip_interface& device) } TypedResult loadGnssAssistedFix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1684,15 +1684,15 @@ TypedResult loadGnssAssistedFix(C::mip_interface& device) } TypedResult defaultGnssAssistedFix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance& self) +void insert(::microstrain::Serializer& serializer, const GnssTimeAssistance& self) { insert(serializer, self.function); @@ -1706,7 +1706,7 @@ void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance& self) } } -void extract(::microstrain::Buffer& serializer, GnssTimeAssistance& self) +void extract(::microstrain::Serializer& serializer, GnssTimeAssistance& self) { extract(serializer, self.function); @@ -1721,7 +1721,7 @@ void extract(::microstrain::Buffer& serializer, GnssTimeAssistance& self) } } -void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance::Response& self) +void insert(::microstrain::Serializer& serializer, const GnssTimeAssistance::Response& self) { insert(serializer, self.tow); @@ -1730,7 +1730,7 @@ void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance::Respons insert(serializer, self.accuracy); } -void extract(::microstrain::Buffer& serializer, GnssTimeAssistance::Response& self) +void extract(::microstrain::Serializer& serializer, GnssTimeAssistance::Response& self) { extract(serializer, self.tow); @@ -1742,8 +1742,8 @@ void extract(::microstrain::Buffer& serializer, GnssTimeAssistance::Response& se TypedResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, tow); @@ -1758,8 +1758,8 @@ TypedResult writeGnssTimeAssistance(C::mip_interface& device } TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1769,7 +1769,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(towOut); extract(deserializer, *towOut); @@ -1785,7 +1785,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, } return result; } -void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter& self) +void insert(::microstrain::Serializer& serializer, const ImuLowpassFilter& self) { insert(serializer, self.function); @@ -1803,7 +1803,7 @@ void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter& self) } } -void extract(::microstrain::Buffer& serializer, ImuLowpassFilter& self) +void extract(::microstrain::Serializer& serializer, ImuLowpassFilter& self) { extract(serializer, self.function); @@ -1822,7 +1822,7 @@ void extract(::microstrain::Buffer& serializer, ImuLowpassFilter& self) } } -void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter::Response& self) +void insert(::microstrain::Serializer& serializer, const ImuLowpassFilter::Response& self) { insert(serializer, self.target_descriptor); @@ -1835,7 +1835,7 @@ void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter::Response& insert(serializer, self.reserved); } -void extract(::microstrain::Buffer& serializer, ImuLowpassFilter::Response& self) +void extract(::microstrain::Serializer& serializer, ImuLowpassFilter::Response& self) { extract(serializer, self.target_descriptor); @@ -1851,8 +1851,8 @@ void extract(::microstrain::Buffer& serializer, ImuLowpassFilter::Response& self TypedResult writeImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, targetDescriptor); @@ -1871,8 +1871,8 @@ TypedResult writeImuLowpassFilter(C::mip_interface& device, ui } TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, targetDescriptor); @@ -1884,7 +1884,7 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, targetDescriptor); @@ -1907,8 +1907,8 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin } TypedResult saveImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, targetDescriptor); @@ -1919,8 +1919,8 @@ TypedResult saveImuLowpassFilter(C::mip_interface& device, uin } TypedResult loadImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, targetDescriptor); @@ -1931,8 +1931,8 @@ TypedResult loadImuLowpassFilter(C::mip_interface& device, uin } TypedResult defaultImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, targetDescriptor); @@ -1941,7 +1941,7 @@ TypedResult defaultImuLowpassFilter(C::mip_interface& device, return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const PpsSource& self) +void insert(::microstrain::Serializer& serializer, const PpsSource& self) { insert(serializer, self.function); @@ -1951,7 +1951,7 @@ void insert(::microstrain::Buffer& serializer, const PpsSource& self) } } -void extract(::microstrain::Buffer& serializer, PpsSource& self) +void extract(::microstrain::Serializer& serializer, PpsSource& self) { extract(serializer, self.function); @@ -1962,12 +1962,12 @@ void extract(::microstrain::Buffer& serializer, PpsSource& self) } } -void insert(::microstrain::Buffer& serializer, const PpsSource::Response& self) +void insert(::microstrain::Serializer& serializer, const PpsSource::Response& self) { insert(serializer, self.source); } -void extract(::microstrain::Buffer& serializer, PpsSource::Response& self) +void extract(::microstrain::Serializer& serializer, PpsSource::Response& self) { extract(serializer, self.source); @@ -1975,8 +1975,8 @@ void extract(::microstrain::Buffer& serializer, PpsSource::Response& self) TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -1987,8 +1987,8 @@ TypedResult writePpsSource(C::mip_interface& device, PpsSource::Sourc } TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1998,7 +1998,7 @@ TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -2010,8 +2010,8 @@ TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source } TypedResult savePpsSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2020,8 +2020,8 @@ TypedResult savePpsSource(C::mip_interface& device) } TypedResult loadPpsSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2030,15 +2030,15 @@ TypedResult loadPpsSource(C::mip_interface& device) } TypedResult defaultPpsSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GpioConfig& self) +void insert(::microstrain::Serializer& serializer, const GpioConfig& self) { insert(serializer, self.function); @@ -2054,7 +2054,7 @@ void insert(::microstrain::Buffer& serializer, const GpioConfig& self) } } -void extract(::microstrain::Buffer& serializer, GpioConfig& self) +void extract(::microstrain::Serializer& serializer, GpioConfig& self) { extract(serializer, self.function); @@ -2071,7 +2071,7 @@ void extract(::microstrain::Buffer& serializer, GpioConfig& self) } } -void insert(::microstrain::Buffer& serializer, const GpioConfig::Response& self) +void insert(::microstrain::Serializer& serializer, const GpioConfig::Response& self) { insert(serializer, self.pin); @@ -2082,7 +2082,7 @@ void insert(::microstrain::Buffer& serializer, const GpioConfig::Response& self) insert(serializer, self.pin_mode); } -void extract(::microstrain::Buffer& serializer, GpioConfig::Response& self) +void extract(::microstrain::Serializer& serializer, GpioConfig::Response& self) { extract(serializer, self.pin); @@ -2096,8 +2096,8 @@ void extract(::microstrain::Buffer& serializer, GpioConfig::Response& self) TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, pin); @@ -2114,8 +2114,8 @@ TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, G } TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, pin); @@ -2127,7 +2127,7 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, pin); @@ -2147,8 +2147,8 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp } TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, pin); @@ -2159,8 +2159,8 @@ TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) } TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, pin); @@ -2171,8 +2171,8 @@ TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) } TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, pin); @@ -2181,7 +2181,7 @@ TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GpioState& self) +void insert(::microstrain::Serializer& serializer, const GpioState& self) { insert(serializer, self.function); @@ -2196,7 +2196,7 @@ void insert(::microstrain::Buffer& serializer, const GpioState& self) } } -void extract(::microstrain::Buffer& serializer, GpioState& self) +void extract(::microstrain::Serializer& serializer, GpioState& self) { extract(serializer, self.function); @@ -2212,14 +2212,14 @@ void extract(::microstrain::Buffer& serializer, GpioState& self) } } -void insert(::microstrain::Buffer& serializer, const GpioState::Response& self) +void insert(::microstrain::Serializer& serializer, const GpioState::Response& self) { insert(serializer, self.pin); insert(serializer, self.state); } -void extract(::microstrain::Buffer& serializer, GpioState::Response& self) +void extract(::microstrain::Serializer& serializer, GpioState::Response& self) { extract(serializer, self.pin); @@ -2229,8 +2229,8 @@ void extract(::microstrain::Buffer& serializer, GpioState::Response& self) TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, pin); @@ -2243,8 +2243,8 @@ TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, boo } TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, pin); @@ -2256,7 +2256,7 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, pin); @@ -2268,7 +2268,7 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool } return result; } -void insert(::microstrain::Buffer& serializer, const Odometer& self) +void insert(::microstrain::Serializer& serializer, const Odometer& self) { insert(serializer, self.function); @@ -2282,7 +2282,7 @@ void insert(::microstrain::Buffer& serializer, const Odometer& self) } } -void extract(::microstrain::Buffer& serializer, Odometer& self) +void extract(::microstrain::Serializer& serializer, Odometer& self) { extract(serializer, self.function); @@ -2297,7 +2297,7 @@ void extract(::microstrain::Buffer& serializer, Odometer& self) } } -void insert(::microstrain::Buffer& serializer, const Odometer::Response& self) +void insert(::microstrain::Serializer& serializer, const Odometer::Response& self) { insert(serializer, self.mode); @@ -2306,7 +2306,7 @@ void insert(::microstrain::Buffer& serializer, const Odometer::Response& self) insert(serializer, self.uncertainty); } -void extract(::microstrain::Buffer& serializer, Odometer::Response& self) +void extract(::microstrain::Serializer& serializer, Odometer::Response& self) { extract(serializer, self.mode); @@ -2318,8 +2318,8 @@ void extract(::microstrain::Buffer& serializer, Odometer::Response& self) TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); @@ -2334,8 +2334,8 @@ TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mod } TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2345,7 +2345,7 @@ TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* mod if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -2363,8 +2363,8 @@ TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* mod } TypedResult saveOdometer(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2373,8 +2373,8 @@ TypedResult saveOdometer(C::mip_interface& device) } TypedResult loadOdometer(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2383,26 +2383,26 @@ TypedResult loadOdometer(C::mip_interface& device) } TypedResult defaultOdometer(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GetEventSupport& self) +void insert(::microstrain::Serializer& serializer, const GetEventSupport& self) { insert(serializer, self.query); } -void extract(::microstrain::Buffer& serializer, GetEventSupport& self) +void extract(::microstrain::Serializer& serializer, GetEventSupport& self) { extract(serializer, self.query); } -void insert(::microstrain::Buffer& serializer, const GetEventSupport::Response& self) +void insert(::microstrain::Serializer& serializer, const GetEventSupport::Response& self) { insert(serializer, self.query); @@ -2414,7 +2414,7 @@ void insert(::microstrain::Buffer& serializer, const GetEventSupport::Response& insert(serializer, self.entries[i]); } -void extract(::microstrain::Buffer& serializer, GetEventSupport::Response& self) +void extract(::microstrain::Serializer& serializer, GetEventSupport::Response& self) { extract(serializer, self.query); @@ -2426,14 +2426,14 @@ void extract(::microstrain::Buffer& serializer, GetEventSupport::Response& self) } -void insert(::microstrain::Buffer& serializer, const GetEventSupport::Info& self) +void insert(::microstrain::Serializer& serializer, const GetEventSupport::Info& self) { insert(serializer, self.type); insert(serializer, self.count); } -void extract(::microstrain::Buffer& serializer, GetEventSupport::Info& self) +void extract(::microstrain::Serializer& serializer, GetEventSupport::Info& self) { extract(serializer, self.type); @@ -2443,8 +2443,8 @@ void extract(::microstrain::Buffer& serializer, GetEventSupport::Info& self) TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, query); @@ -2455,7 +2455,7 @@ TypedResult getEventSupport(C::mip_interface& device, GetEventS if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, query); @@ -2472,7 +2472,7 @@ TypedResult getEventSupport(C::mip_interface& device, GetEventS } return result; } -void insert(::microstrain::Buffer& serializer, const EventControl& self) +void insert(::microstrain::Serializer& serializer, const EventControl& self) { insert(serializer, self.function); @@ -2484,7 +2484,7 @@ void insert(::microstrain::Buffer& serializer, const EventControl& self) } } -void extract(::microstrain::Buffer& serializer, EventControl& self) +void extract(::microstrain::Serializer& serializer, EventControl& self) { extract(serializer, self.function); @@ -2497,14 +2497,14 @@ void extract(::microstrain::Buffer& serializer, EventControl& self) } } -void insert(::microstrain::Buffer& serializer, const EventControl::Response& self) +void insert(::microstrain::Serializer& serializer, const EventControl::Response& self) { insert(serializer, self.instance); insert(serializer, self.mode); } -void extract(::microstrain::Buffer& serializer, EventControl::Response& self) +void extract(::microstrain::Serializer& serializer, EventControl::Response& self) { extract(serializer, self.instance); @@ -2514,8 +2514,8 @@ void extract(::microstrain::Buffer& serializer, EventControl::Response& self) TypedResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, instance); @@ -2528,8 +2528,8 @@ TypedResult writeEventControl(C::mip_interface& device, uint8_t in } TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, instance); @@ -2541,7 +2541,7 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, instance); @@ -2555,8 +2555,8 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins } TypedResult saveEventControl(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, instance); @@ -2567,8 +2567,8 @@ TypedResult saveEventControl(C::mip_interface& device, uint8_t ins } TypedResult loadEventControl(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, instance); @@ -2579,8 +2579,8 @@ TypedResult loadEventControl(C::mip_interface& device, uint8_t ins } TypedResult defaultEventControl(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, instance); @@ -2589,7 +2589,7 @@ TypedResult defaultEventControl(C::mip_interface& device, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus& self) +void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus& self) { insert(serializer, self.requested_count); @@ -2597,7 +2597,7 @@ void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus& self insert(serializer, self.requested_instances[i]); } -void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus& self) +void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus& self) { extract_count(serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); for(unsigned int i=0; i < self.requested_count; i++) @@ -2605,7 +2605,7 @@ void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus& self) } -void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Response& self) +void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus::Response& self) { insert(serializer, self.count); @@ -2613,7 +2613,7 @@ void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Resp insert(serializer, self.triggers[i]); } -void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Response& self) +void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus::Response& self) { extract_count(serializer, &self.count, sizeof(self.triggers)/sizeof(self.triggers[0])); for(unsigned int i=0; i < self.count; i++) @@ -2621,14 +2621,14 @@ void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Response& } -void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Entry& self) +void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus::Entry& self) { insert(serializer, self.type); insert(serializer, self.status); } -void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Entry& self) +void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus::Entry& self) { extract(serializer, self.type); @@ -2638,8 +2638,8 @@ void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Entry& se TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, requestedCount); @@ -2654,7 +2654,7 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract_count(deserializer, countOut, countOutMax); assert(triggersOut || (countOut == 0)); @@ -2666,7 +2666,7 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic } return result; } -void insert(::microstrain::Buffer& serializer, const GetEventActionStatus& self) +void insert(::microstrain::Serializer& serializer, const GetEventActionStatus& self) { insert(serializer, self.requested_count); @@ -2674,7 +2674,7 @@ void insert(::microstrain::Buffer& serializer, const GetEventActionStatus& self) insert(serializer, self.requested_instances[i]); } -void extract(::microstrain::Buffer& serializer, GetEventActionStatus& self) +void extract(::microstrain::Serializer& serializer, GetEventActionStatus& self) { extract_count(serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); for(unsigned int i=0; i < self.requested_count; i++) @@ -2682,7 +2682,7 @@ void extract(::microstrain::Buffer& serializer, GetEventActionStatus& self) } -void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Response& self) +void insert(::microstrain::Serializer& serializer, const GetEventActionStatus::Response& self) { insert(serializer, self.count); @@ -2690,7 +2690,7 @@ void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Respo insert(serializer, self.actions[i]); } -void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Response& self) +void extract(::microstrain::Serializer& serializer, GetEventActionStatus::Response& self) { extract_count(serializer, &self.count, sizeof(self.actions)/sizeof(self.actions[0])); for(unsigned int i=0; i < self.count; i++) @@ -2698,14 +2698,14 @@ void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Response& } -void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Entry& self) +void insert(::microstrain::Serializer& serializer, const GetEventActionStatus::Entry& self) { insert(serializer, self.action_type); insert(serializer, self.trigger_id); } -void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Entry& self) +void extract(::microstrain::Serializer& serializer, GetEventActionStatus::Entry& self) { extract(serializer, self.action_type); @@ -2715,8 +2715,8 @@ void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Entry& sel TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, requestedCount); @@ -2731,7 +2731,7 @@ TypedResult getEventActionStatus(C::mip_interface& device, if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract_count(deserializer, countOut, countOutMax); assert(actionsOut || (countOut == 0)); @@ -2743,7 +2743,7 @@ TypedResult getEventActionStatus(C::mip_interface& device, } return result; } -void insert(::microstrain::Buffer& serializer, const EventTrigger& self) +void insert(::microstrain::Serializer& serializer, const EventTrigger& self) { insert(serializer, self.function); @@ -2770,7 +2770,7 @@ void insert(::microstrain::Buffer& serializer, const EventTrigger& self) } } } -void extract(::microstrain::Buffer& serializer, EventTrigger& self) +void extract(::microstrain::Serializer& serializer, EventTrigger& self) { extract(serializer, self.function); @@ -2798,7 +2798,7 @@ void extract(::microstrain::Buffer& serializer, EventTrigger& self) } } -void insert(::microstrain::Buffer& serializer, const EventTrigger::Response& self) +void insert(::microstrain::Serializer& serializer, const EventTrigger::Response& self) { insert(serializer, self.instance); @@ -2820,7 +2820,7 @@ void insert(::microstrain::Buffer& serializer, const EventTrigger::Response& sel } } -void extract(::microstrain::Buffer& serializer, EventTrigger::Response& self) +void extract(::microstrain::Serializer& serializer, EventTrigger::Response& self) { extract(serializer, self.instance); @@ -2843,14 +2843,14 @@ void extract(::microstrain::Buffer& serializer, EventTrigger::Response& self) } } -void insert(::microstrain::Buffer& serializer, const EventTrigger::GpioParams& self) +void insert(::microstrain::Serializer& serializer, const EventTrigger::GpioParams& self) { insert(serializer, self.pin); insert(serializer, self.mode); } -void extract(::microstrain::Buffer& serializer, EventTrigger::GpioParams& self) +void extract(::microstrain::Serializer& serializer, EventTrigger::GpioParams& self) { extract(serializer, self.pin); @@ -2858,7 +2858,7 @@ void extract(::microstrain::Buffer& serializer, EventTrigger::GpioParams& self) } -void insert(::microstrain::Buffer& serializer, const EventTrigger::ThresholdParams& self) +void insert(::microstrain::Serializer& serializer, const EventTrigger::ThresholdParams& self) { insert(serializer, self.desc_set); @@ -2889,7 +2889,7 @@ void insert(::microstrain::Buffer& serializer, const EventTrigger::ThresholdPara } } -void extract(::microstrain::Buffer& serializer, EventTrigger::ThresholdParams& self) +void extract(::microstrain::Serializer& serializer, EventTrigger::ThresholdParams& self) { extract(serializer, self.desc_set); @@ -2921,7 +2921,7 @@ void extract(::microstrain::Buffer& serializer, EventTrigger::ThresholdParams& s } } -void insert(::microstrain::Buffer& serializer, const EventTrigger::CombinationParams& self) +void insert(::microstrain::Serializer& serializer, const EventTrigger::CombinationParams& self) { insert(serializer, self.logic_table); @@ -2929,7 +2929,7 @@ void insert(::microstrain::Buffer& serializer, const EventTrigger::CombinationPa insert(serializer, self.input_triggers[i]); } -void extract(::microstrain::Buffer& serializer, EventTrigger::CombinationParams& self) +void extract(::microstrain::Serializer& serializer, EventTrigger::CombinationParams& self) { extract(serializer, self.logic_table); @@ -2940,8 +2940,8 @@ void extract(::microstrain::Buffer& serializer, EventTrigger::CombinationParams& TypedResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, instance); @@ -2969,8 +2969,8 @@ TypedResult writeEventTrigger(C::mip_interface& device, uint8_t in } TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, instance); @@ -2982,7 +2982,7 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, instance); @@ -3011,8 +3011,8 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins } TypedResult saveEventTrigger(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, instance); @@ -3023,8 +3023,8 @@ TypedResult saveEventTrigger(C::mip_interface& device, uint8_t ins } TypedResult loadEventTrigger(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, instance); @@ -3035,8 +3035,8 @@ TypedResult loadEventTrigger(C::mip_interface& device, uint8_t ins } TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, instance); @@ -3045,7 +3045,7 @@ TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const EventAction& self) +void insert(::microstrain::Serializer& serializer, const EventAction& self) { insert(serializer, self.function); @@ -3069,7 +3069,7 @@ void insert(::microstrain::Buffer& serializer, const EventAction& self) } } } -void extract(::microstrain::Buffer& serializer, EventAction& self) +void extract(::microstrain::Serializer& serializer, EventAction& self) { extract(serializer, self.function); @@ -3094,7 +3094,7 @@ void extract(::microstrain::Buffer& serializer, EventAction& self) } } -void insert(::microstrain::Buffer& serializer, const EventAction::Response& self) +void insert(::microstrain::Serializer& serializer, const EventAction::Response& self) { insert(serializer, self.instance); @@ -3113,7 +3113,7 @@ void insert(::microstrain::Buffer& serializer, const EventAction::Response& self } } -void extract(::microstrain::Buffer& serializer, EventAction::Response& self) +void extract(::microstrain::Serializer& serializer, EventAction::Response& self) { extract(serializer, self.instance); @@ -3133,14 +3133,14 @@ void extract(::microstrain::Buffer& serializer, EventAction::Response& self) } } -void insert(::microstrain::Buffer& serializer, const EventAction::GpioParams& self) +void insert(::microstrain::Serializer& serializer, const EventAction::GpioParams& self) { insert(serializer, self.pin); insert(serializer, self.mode); } -void extract(::microstrain::Buffer& serializer, EventAction::GpioParams& self) +void extract(::microstrain::Serializer& serializer, EventAction::GpioParams& self) { extract(serializer, self.pin); @@ -3148,7 +3148,7 @@ void extract(::microstrain::Buffer& serializer, EventAction::GpioParams& self) } -void insert(::microstrain::Buffer& serializer, const EventAction::MessageParams& self) +void insert(::microstrain::Serializer& serializer, const EventAction::MessageParams& self) { insert(serializer, self.desc_set); @@ -3160,7 +3160,7 @@ void insert(::microstrain::Buffer& serializer, const EventAction::MessageParams& insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, EventAction::MessageParams& self) +void extract(::microstrain::Serializer& serializer, EventAction::MessageParams& self) { extract(serializer, self.desc_set); @@ -3174,8 +3174,8 @@ void extract(::microstrain::Buffer& serializer, EventAction::MessageParams& self TypedResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, instance); @@ -3200,8 +3200,8 @@ TypedResult writeEventAction(C::mip_interface& device, uint8_t inst } TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, instance); @@ -3213,7 +3213,7 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, instance); @@ -3240,8 +3240,8 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta } TypedResult saveEventAction(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, instance); @@ -3252,8 +3252,8 @@ TypedResult saveEventAction(C::mip_interface& device, uint8_t insta } TypedResult loadEventAction(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, instance); @@ -3264,8 +3264,8 @@ TypedResult loadEventAction(C::mip_interface& device, uint8_t insta } TypedResult defaultEventAction(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, instance); @@ -3274,7 +3274,7 @@ TypedResult defaultEventAction(C::mip_interface& device, uint8_t in return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AccelBias& self) +void insert(::microstrain::Serializer& serializer, const AccelBias& self) { insert(serializer, self.function); @@ -3285,7 +3285,7 @@ void insert(::microstrain::Buffer& serializer, const AccelBias& self) } } -void extract(::microstrain::Buffer& serializer, AccelBias& self) +void extract(::microstrain::Serializer& serializer, AccelBias& self) { extract(serializer, self.function); @@ -3297,13 +3297,13 @@ void extract(::microstrain::Buffer& serializer, AccelBias& self) } } -void insert(::microstrain::Buffer& serializer, const AccelBias::Response& self) +void insert(::microstrain::Serializer& serializer, const AccelBias::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); } -void extract(::microstrain::Buffer& serializer, AccelBias::Response& self) +void extract(::microstrain::Serializer& serializer, AccelBias::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -3312,8 +3312,8 @@ void extract(::microstrain::Buffer& serializer, AccelBias::Response& self) TypedResult writeAccelBias(C::mip_interface& device, const float* bias) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(bias || (3 == 0)); @@ -3326,8 +3326,8 @@ TypedResult writeAccelBias(C::mip_interface& device, const float* bia } TypedResult readAccelBias(C::mip_interface& device, float* biasOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3337,7 +3337,7 @@ TypedResult readAccelBias(C::mip_interface& device, float* biasOut) if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(biasOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3350,8 +3350,8 @@ TypedResult readAccelBias(C::mip_interface& device, float* biasOut) } TypedResult saveAccelBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3360,8 +3360,8 @@ TypedResult saveAccelBias(C::mip_interface& device) } TypedResult loadAccelBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3370,15 +3370,15 @@ TypedResult loadAccelBias(C::mip_interface& device) } TypedResult defaultAccelBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GyroBias& self) +void insert(::microstrain::Serializer& serializer, const GyroBias& self) { insert(serializer, self.function); @@ -3389,7 +3389,7 @@ void insert(::microstrain::Buffer& serializer, const GyroBias& self) } } -void extract(::microstrain::Buffer& serializer, GyroBias& self) +void extract(::microstrain::Serializer& serializer, GyroBias& self) { extract(serializer, self.function); @@ -3401,13 +3401,13 @@ void extract(::microstrain::Buffer& serializer, GyroBias& self) } } -void insert(::microstrain::Buffer& serializer, const GyroBias::Response& self) +void insert(::microstrain::Serializer& serializer, const GyroBias::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); } -void extract(::microstrain::Buffer& serializer, GyroBias::Response& self) +void extract(::microstrain::Serializer& serializer, GyroBias::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -3416,8 +3416,8 @@ void extract(::microstrain::Buffer& serializer, GyroBias::Response& self) TypedResult writeGyroBias(C::mip_interface& device, const float* bias) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(bias || (3 == 0)); @@ -3430,8 +3430,8 @@ TypedResult writeGyroBias(C::mip_interface& device, const float* bias) } TypedResult readGyroBias(C::mip_interface& device, float* biasOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3441,7 +3441,7 @@ TypedResult readGyroBias(C::mip_interface& device, float* biasOut) if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(biasOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3454,8 +3454,8 @@ TypedResult readGyroBias(C::mip_interface& device, float* biasOut) } TypedResult saveGyroBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3464,8 +3464,8 @@ TypedResult saveGyroBias(C::mip_interface& device) } TypedResult loadGyroBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3474,32 +3474,32 @@ TypedResult loadGyroBias(C::mip_interface& device) } TypedResult defaultGyroBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const CaptureGyroBias& self) +void insert(::microstrain::Serializer& serializer, const CaptureGyroBias& self) { insert(serializer, self.averaging_time_ms); } -void extract(::microstrain::Buffer& serializer, CaptureGyroBias& self) +void extract(::microstrain::Serializer& serializer, CaptureGyroBias& self) { extract(serializer, self.averaging_time_ms); } -void insert(::microstrain::Buffer& serializer, const CaptureGyroBias::Response& self) +void insert(::microstrain::Serializer& serializer, const CaptureGyroBias::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); } -void extract(::microstrain::Buffer& serializer, CaptureGyroBias::Response& self) +void extract(::microstrain::Serializer& serializer, CaptureGyroBias::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -3508,8 +3508,8 @@ void extract(::microstrain::Buffer& serializer, CaptureGyroBias::Response& self) TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, averagingTimeMs); @@ -3520,7 +3520,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(biasOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3531,7 +3531,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t } return result; } -void insert(::microstrain::Buffer& serializer, const MagHardIronOffset& self) +void insert(::microstrain::Serializer& serializer, const MagHardIronOffset& self) { insert(serializer, self.function); @@ -3542,7 +3542,7 @@ void insert(::microstrain::Buffer& serializer, const MagHardIronOffset& self) } } -void extract(::microstrain::Buffer& serializer, MagHardIronOffset& self) +void extract(::microstrain::Serializer& serializer, MagHardIronOffset& self) { extract(serializer, self.function); @@ -3554,13 +3554,13 @@ void extract(::microstrain::Buffer& serializer, MagHardIronOffset& self) } } -void insert(::microstrain::Buffer& serializer, const MagHardIronOffset::Response& self) +void insert(::microstrain::Serializer& serializer, const MagHardIronOffset::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset[i]); } -void extract(::microstrain::Buffer& serializer, MagHardIronOffset::Response& self) +void extract(::microstrain::Serializer& serializer, MagHardIronOffset::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset[i]); @@ -3569,8 +3569,8 @@ void extract(::microstrain::Buffer& serializer, MagHardIronOffset::Response& sel TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (3 == 0)); @@ -3583,8 +3583,8 @@ TypedResult writeMagHardIronOffset(C::mip_interface& device, } TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3594,7 +3594,7 @@ TypedResult readMagHardIronOffset(C::mip_interface& device, f if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(offsetOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -3607,8 +3607,8 @@ TypedResult readMagHardIronOffset(C::mip_interface& device, f } TypedResult saveMagHardIronOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3617,8 +3617,8 @@ TypedResult saveMagHardIronOffset(C::mip_interface& device) } TypedResult loadMagHardIronOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3627,15 +3627,15 @@ TypedResult loadMagHardIronOffset(C::mip_interface& device) } TypedResult defaultMagHardIronOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const MagSoftIronMatrix& self) +void insert(::microstrain::Serializer& serializer, const MagSoftIronMatrix& self) { insert(serializer, self.function); @@ -3646,7 +3646,7 @@ void insert(::microstrain::Buffer& serializer, const MagSoftIronMatrix& self) } } -void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix& self) +void extract(::microstrain::Serializer& serializer, MagSoftIronMatrix& self) { extract(serializer, self.function); @@ -3658,13 +3658,13 @@ void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix& self) } } -void insert(::microstrain::Buffer& serializer, const MagSoftIronMatrix::Response& self) +void insert(::microstrain::Serializer& serializer, const MagSoftIronMatrix::Response& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.offset[i]); } -void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix::Response& self) +void extract(::microstrain::Serializer& serializer, MagSoftIronMatrix::Response& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.offset[i]); @@ -3673,8 +3673,8 @@ void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix::Response& sel TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (9 == 0)); @@ -3687,8 +3687,8 @@ TypedResult writeMagSoftIronMatrix(C::mip_interface& device, } TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3698,7 +3698,7 @@ TypedResult readMagSoftIronMatrix(C::mip_interface& device, f if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(offsetOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -3711,8 +3711,8 @@ TypedResult readMagSoftIronMatrix(C::mip_interface& device, f } TypedResult saveMagSoftIronMatrix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3721,8 +3721,8 @@ TypedResult saveMagSoftIronMatrix(C::mip_interface& device) } TypedResult loadMagSoftIronMatrix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3731,15 +3731,15 @@ TypedResult loadMagSoftIronMatrix(C::mip_interface& device) } TypedResult defaultMagSoftIronMatrix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ConingScullingEnable& self) +void insert(::microstrain::Serializer& serializer, const ConingScullingEnable& self) { insert(serializer, self.function); @@ -3749,7 +3749,7 @@ void insert(::microstrain::Buffer& serializer, const ConingScullingEnable& self) } } -void extract(::microstrain::Buffer& serializer, ConingScullingEnable& self) +void extract(::microstrain::Serializer& serializer, ConingScullingEnable& self) { extract(serializer, self.function); @@ -3760,12 +3760,12 @@ void extract(::microstrain::Buffer& serializer, ConingScullingEnable& self) } } -void insert(::microstrain::Buffer& serializer, const ConingScullingEnable::Response& self) +void insert(::microstrain::Serializer& serializer, const ConingScullingEnable::Response& self) { insert(serializer, self.enable); } -void extract(::microstrain::Buffer& serializer, ConingScullingEnable::Response& self) +void extract(::microstrain::Serializer& serializer, ConingScullingEnable::Response& self) { extract(serializer, self.enable); @@ -3773,8 +3773,8 @@ void extract(::microstrain::Buffer& serializer, ConingScullingEnable::Response& TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -3785,8 +3785,8 @@ TypedResult writeConingScullingEnable(C::mip_interface& de } TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3796,7 +3796,7 @@ TypedResult readConingScullingEnable(C::mip_interface& dev if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -3808,8 +3808,8 @@ TypedResult readConingScullingEnable(C::mip_interface& dev } TypedResult saveConingScullingEnable(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3818,8 +3818,8 @@ TypedResult saveConingScullingEnable(C::mip_interface& dev } TypedResult loadConingScullingEnable(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3828,15 +3828,15 @@ TypedResult loadConingScullingEnable(C::mip_interface& dev } TypedResult defaultConingScullingEnable(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEuler& self) +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformEuler& self) { insert(serializer, self.function); @@ -3850,7 +3850,7 @@ void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEule } } -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler& self) +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformEuler& self) { extract(serializer, self.function); @@ -3865,7 +3865,7 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler& se } } -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEuler::Response& self) +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformEuler::Response& self) { insert(serializer, self.roll); @@ -3874,7 +3874,7 @@ void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEule insert(serializer, self.yaw); } -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler::Response& self) +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformEuler::Response& self) { extract(serializer, self.roll); @@ -3886,8 +3886,8 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler::Re TypedResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, roll); @@ -3902,8 +3902,8 @@ TypedResult writeSensor2VehicleTransformEuler(C::m } TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3913,7 +3913,7 @@ TypedResult readSensor2VehicleTransformEuler(C::mi if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(rollOut); extract(deserializer, *rollOut); @@ -3931,8 +3931,8 @@ TypedResult readSensor2VehicleTransformEuler(C::mi } TypedResult saveSensor2VehicleTransformEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3941,8 +3941,8 @@ TypedResult saveSensor2VehicleTransformEuler(C::mi } TypedResult loadSensor2VehicleTransformEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3951,15 +3951,15 @@ TypedResult loadSensor2VehicleTransformEuler(C::mi } TypedResult defaultSensor2VehicleTransformEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformQuaternion& self) +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformQuaternion& self) { insert(serializer, self.function); @@ -3970,7 +3970,7 @@ void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformQuat } } -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternion& self) +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformQuaternion& self) { extract(serializer, self.function); @@ -3982,13 +3982,13 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternio } } -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformQuaternion::Response& self) +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformQuaternion::Response& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.q[i]); } -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternion::Response& self) +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformQuaternion::Response& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.q[i]); @@ -3997,8 +3997,8 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternio TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(q || (4 == 0)); @@ -4011,8 +4011,8 @@ TypedResult writeSensor2VehicleTransformQuate } TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4022,7 +4022,7 @@ TypedResult readSensor2VehicleTransformQuater if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(qOut || (4 == 0)); for(unsigned int i=0; i < 4; i++) @@ -4035,8 +4035,8 @@ TypedResult readSensor2VehicleTransformQuater } TypedResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4045,8 +4045,8 @@ TypedResult saveSensor2VehicleTransformQuater } TypedResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4055,15 +4055,15 @@ TypedResult loadSensor2VehicleTransformQuater } TypedResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformDcm& self) +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformDcm& self) { insert(serializer, self.function); @@ -4074,7 +4074,7 @@ void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformDcm& } } -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm& self) +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformDcm& self) { extract(serializer, self.function); @@ -4086,13 +4086,13 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm& self } } -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformDcm::Response& self) +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformDcm::Response& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.dcm[i]); } -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm::Response& self) +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformDcm::Response& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.dcm[i]); @@ -4101,8 +4101,8 @@ void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm::Resp TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(dcm || (9 == 0)); @@ -4115,8 +4115,8 @@ TypedResult writeSensor2VehicleTransformDcm(C::mip_i } TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4126,7 +4126,7 @@ TypedResult readSensor2VehicleTransformDcm(C::mip_in if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(dcmOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -4139,8 +4139,8 @@ TypedResult readSensor2VehicleTransformDcm(C::mip_in } TypedResult saveSensor2VehicleTransformDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4149,8 +4149,8 @@ TypedResult saveSensor2VehicleTransformDcm(C::mip_in } TypedResult loadSensor2VehicleTransformDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4159,15 +4159,15 @@ TypedResult loadSensor2VehicleTransformDcm(C::mip_in } TypedResult defaultSensor2VehicleTransformDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ComplementaryFilter& self) +void insert(::microstrain::Serializer& serializer, const ComplementaryFilter& self) { insert(serializer, self.function); @@ -4183,7 +4183,7 @@ void insert(::microstrain::Buffer& serializer, const ComplementaryFilter& self) } } -void extract(::microstrain::Buffer& serializer, ComplementaryFilter& self) +void extract(::microstrain::Serializer& serializer, ComplementaryFilter& self) { extract(serializer, self.function); @@ -4200,7 +4200,7 @@ void extract(::microstrain::Buffer& serializer, ComplementaryFilter& self) } } -void insert(::microstrain::Buffer& serializer, const ComplementaryFilter::Response& self) +void insert(::microstrain::Serializer& serializer, const ComplementaryFilter::Response& self) { insert(serializer, self.pitch_roll_enable); @@ -4211,7 +4211,7 @@ void insert(::microstrain::Buffer& serializer, const ComplementaryFilter::Respon insert(serializer, self.heading_time_constant); } -void extract(::microstrain::Buffer& serializer, ComplementaryFilter::Response& self) +void extract(::microstrain::Serializer& serializer, ComplementaryFilter::Response& self) { extract(serializer, self.pitch_roll_enable); @@ -4225,8 +4225,8 @@ void extract(::microstrain::Buffer& serializer, ComplementaryFilter::Response& s TypedResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, pitchRollEnable); @@ -4243,8 +4243,8 @@ TypedResult writeComplementaryFilter(C::mip_interface& devi } TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4254,7 +4254,7 @@ TypedResult readComplementaryFilter(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(pitchRollEnableOut); extract(deserializer, *pitchRollEnableOut); @@ -4275,8 +4275,8 @@ TypedResult readComplementaryFilter(C::mip_interface& devic } TypedResult saveComplementaryFilter(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4285,8 +4285,8 @@ TypedResult saveComplementaryFilter(C::mip_interface& devic } TypedResult loadComplementaryFilter(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4295,15 +4295,15 @@ TypedResult loadComplementaryFilter(C::mip_interface& devic } TypedResult defaultComplementaryFilter(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SensorRange& self) +void insert(::microstrain::Serializer& serializer, const SensorRange& self) { insert(serializer, self.function); @@ -4315,7 +4315,7 @@ void insert(::microstrain::Buffer& serializer, const SensorRange& self) } } -void extract(::microstrain::Buffer& serializer, SensorRange& self) +void extract(::microstrain::Serializer& serializer, SensorRange& self) { extract(serializer, self.function); @@ -4328,14 +4328,14 @@ void extract(::microstrain::Buffer& serializer, SensorRange& self) } } -void insert(::microstrain::Buffer& serializer, const SensorRange::Response& self) +void insert(::microstrain::Serializer& serializer, const SensorRange::Response& self) { insert(serializer, self.sensor); insert(serializer, self.setting); } -void extract(::microstrain::Buffer& serializer, SensorRange::Response& self) +void extract(::microstrain::Serializer& serializer, SensorRange::Response& self) { extract(serializer, self.sensor); @@ -4345,8 +4345,8 @@ void extract(::microstrain::Buffer& serializer, SensorRange::Response& self) TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, sensor); @@ -4359,8 +4359,8 @@ TypedResult writeSensorRange(C::mip_interface& device, SensorRangeT } TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, sensor); @@ -4372,7 +4372,7 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, sensor); @@ -4386,8 +4386,8 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy } TypedResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, sensor); @@ -4398,8 +4398,8 @@ TypedResult saveSensorRange(C::mip_interface& device, SensorRangeTy } TypedResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, sensor); @@ -4410,8 +4410,8 @@ TypedResult loadSensorRange(C::mip_interface& device, SensorRangeTy } TypedResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, sensor); @@ -4420,18 +4420,18 @@ TypedResult defaultSensorRange(C::mip_interface& device, SensorRang return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges& self) +void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges& self) { insert(serializer, self.sensor); } -void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges& self) +void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges& self) { extract(serializer, self.sensor); } -void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges::Response& self) +void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges::Response& self) { insert(serializer, self.sensor); @@ -4441,7 +4441,7 @@ void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges::Res insert(serializer, self.ranges[i]); } -void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Response& self) +void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges::Response& self) { extract(serializer, self.sensor); @@ -4451,14 +4451,14 @@ void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Response } -void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges::Entry& self) +void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges::Entry& self) { insert(serializer, self.setting); insert(serializer, self.range); } -void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Entry& self) +void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges::Entry& self) { extract(serializer, self.setting); @@ -4468,8 +4468,8 @@ void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Entry& s TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, sensor); @@ -4480,7 +4480,7 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, sensor); @@ -4494,7 +4494,7 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev } return result; } -void insert(::microstrain::Buffer& serializer, const LowpassFilter& self) +void insert(::microstrain::Serializer& serializer, const LowpassFilter& self) { insert(serializer, self.function); @@ -4512,7 +4512,7 @@ void insert(::microstrain::Buffer& serializer, const LowpassFilter& self) } } -void extract(::microstrain::Buffer& serializer, LowpassFilter& self) +void extract(::microstrain::Serializer& serializer, LowpassFilter& self) { extract(serializer, self.function); @@ -4531,7 +4531,7 @@ void extract(::microstrain::Buffer& serializer, LowpassFilter& self) } } -void insert(::microstrain::Buffer& serializer, const LowpassFilter::Response& self) +void insert(::microstrain::Serializer& serializer, const LowpassFilter::Response& self) { insert(serializer, self.desc_set); @@ -4544,7 +4544,7 @@ void insert(::microstrain::Buffer& serializer, const LowpassFilter::Response& se insert(serializer, self.frequency); } -void extract(::microstrain::Buffer& serializer, LowpassFilter::Response& self) +void extract(::microstrain::Serializer& serializer, LowpassFilter::Response& self) { extract(serializer, self.desc_set); @@ -4560,8 +4560,8 @@ void extract(::microstrain::Buffer& serializer, LowpassFilter::Response& self) TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool enable, bool manual, float frequency) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, descSet); @@ -4580,8 +4580,8 @@ TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t } TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, descSet); @@ -4595,7 +4595,7 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, descSet); @@ -4617,8 +4617,8 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d } TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, descSet); @@ -4631,8 +4631,8 @@ TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t d } TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, descSet); @@ -4645,8 +4645,8 @@ TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t d } TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, descSet); diff --git a/src/mip/definitions/commands_3dm.hpp b/src/mip/definitions/commands_3dm.hpp index 5fe7aae89..8210f4395 100644 --- a/src/mip/definitions/commands_3dm.hpp +++ b/src/mip/definitions/commands_3dm.hpp @@ -172,8 +172,8 @@ struct NmeaMessage uint16_t decimation = 0; ///< Decimation from the base rate for source_desc_set. Frequency is limited to 10 Hz or the base rate, whichever is lower. Must be 0 when polling. }; -void insert(::microstrain::Buffer& serializer, const NmeaMessage& self); -void extract(::microstrain::Buffer& serializer, NmeaMessage& self); +void insert(::microstrain::Serializer& serializer, const NmeaMessage& self); +void extract(::microstrain::Serializer& serializer, NmeaMessage& self); enum class SensorRangeType : uint8_t { @@ -228,8 +228,8 @@ struct PollImuMessage } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const PollImuMessage& self); -void extract(::microstrain::Buffer& serializer, PollImuMessage& self); +void insert(::microstrain::Serializer& serializer, const PollImuMessage& self); +void extract(::microstrain::Serializer& serializer, PollImuMessage& self); TypedResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); @@ -274,8 +274,8 @@ struct PollGnssMessage } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const PollGnssMessage& self); -void extract(::microstrain::Buffer& serializer, PollGnssMessage& self); +void insert(::microstrain::Serializer& serializer, const PollGnssMessage& self); +void extract(::microstrain::Serializer& serializer, PollGnssMessage& self); TypedResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); @@ -320,8 +320,8 @@ struct PollFilterMessage } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const PollFilterMessage& self); -void extract(::microstrain::Buffer& serializer, PollFilterMessage& self); +void insert(::microstrain::Serializer& serializer, const PollFilterMessage& self); +void extract(::microstrain::Serializer& serializer, PollFilterMessage& self); TypedResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); @@ -393,11 +393,11 @@ struct ImuMessageFormat } }; }; -void insert(::microstrain::Buffer& serializer, const ImuMessageFormat& self); -void extract(::microstrain::Buffer& serializer, ImuMessageFormat& self); +void insert(::microstrain::Serializer& serializer, const ImuMessageFormat& self); +void extract(::microstrain::Serializer& serializer, ImuMessageFormat& self); -void insert(::microstrain::Buffer& serializer, const ImuMessageFormat::Response& self); -void extract(::microstrain::Buffer& serializer, ImuMessageFormat::Response& self); +void insert(::microstrain::Serializer& serializer, const ImuMessageFormat::Response& self); +void extract(::microstrain::Serializer& serializer, ImuMessageFormat::Response& self); TypedResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); @@ -473,11 +473,11 @@ struct GpsMessageFormat } }; }; -void insert(::microstrain::Buffer& serializer, const GpsMessageFormat& self); -void extract(::microstrain::Buffer& serializer, GpsMessageFormat& self); +void insert(::microstrain::Serializer& serializer, const GpsMessageFormat& self); +void extract(::microstrain::Serializer& serializer, GpsMessageFormat& self); -void insert(::microstrain::Buffer& serializer, const GpsMessageFormat::Response& self); -void extract(::microstrain::Buffer& serializer, GpsMessageFormat::Response& self); +void insert(::microstrain::Serializer& serializer, const GpsMessageFormat::Response& self); +void extract(::microstrain::Serializer& serializer, GpsMessageFormat::Response& self); TypedResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); @@ -518,7 +518,7 @@ struct FilterMessageFormat auto as_tuple() const { - return std::make_tuple(num_descriptors,descriptors); + return std::make_tuple(Counter(num_descriptors,descriptors),Array(descriptors,num_descriptors)); } auto as_tuple() @@ -545,7 +545,9 @@ struct FilterMessageFormat static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; uint8_t num_descriptors = 0; ///< Number of descriptors (limited by payload size) DescriptorRate descriptors[82]; - + //Counter num_descriptors = 0; + //Array descriptors; + auto as_tuple() { @@ -553,11 +555,11 @@ struct FilterMessageFormat } }; }; -void insert(::microstrain::Buffer& serializer, const FilterMessageFormat& self); -void extract(::microstrain::Buffer& serializer, FilterMessageFormat& self); +void insert(::microstrain::Serializer& serializer, const FilterMessageFormat& self); +void extract(::microstrain::Serializer& serializer, FilterMessageFormat& self); -void insert(::microstrain::Buffer& serializer, const FilterMessageFormat::Response& self); -void extract(::microstrain::Buffer& serializer, FilterMessageFormat::Response& self); +void insert(::microstrain::Serializer& serializer, const FilterMessageFormat::Response& self); +void extract(::microstrain::Serializer& serializer, FilterMessageFormat::Response& self); TypedResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); @@ -617,11 +619,11 @@ struct ImuGetBaseRate } }; }; -void insert(::microstrain::Buffer& serializer, const ImuGetBaseRate& self); -void extract(::microstrain::Buffer& serializer, ImuGetBaseRate& self); +void insert(::microstrain::Serializer& serializer, const ImuGetBaseRate& self); +void extract(::microstrain::Serializer& serializer, ImuGetBaseRate& self); -void insert(::microstrain::Buffer& serializer, const ImuGetBaseRate::Response& self); -void extract(::microstrain::Buffer& serializer, ImuGetBaseRate::Response& self); +void insert(::microstrain::Serializer& serializer, const ImuGetBaseRate::Response& self); +void extract(::microstrain::Serializer& serializer, ImuGetBaseRate::Response& self); TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut); @@ -677,11 +679,11 @@ struct GpsGetBaseRate } }; }; -void insert(::microstrain::Buffer& serializer, const GpsGetBaseRate& self); -void extract(::microstrain::Buffer& serializer, GpsGetBaseRate& self); +void insert(::microstrain::Serializer& serializer, const GpsGetBaseRate& self); +void extract(::microstrain::Serializer& serializer, GpsGetBaseRate& self); -void insert(::microstrain::Buffer& serializer, const GpsGetBaseRate::Response& self); -void extract(::microstrain::Buffer& serializer, GpsGetBaseRate::Response& self); +void insert(::microstrain::Serializer& serializer, const GpsGetBaseRate::Response& self); +void extract(::microstrain::Serializer& serializer, GpsGetBaseRate::Response& self); TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut); @@ -737,11 +739,11 @@ struct FilterGetBaseRate } }; }; -void insert(::microstrain::Buffer& serializer, const FilterGetBaseRate& self); -void extract(::microstrain::Buffer& serializer, FilterGetBaseRate& self); +void insert(::microstrain::Serializer& serializer, const FilterGetBaseRate& self); +void extract(::microstrain::Serializer& serializer, FilterGetBaseRate& self); -void insert(::microstrain::Buffer& serializer, const FilterGetBaseRate::Response& self); -void extract(::microstrain::Buffer& serializer, FilterGetBaseRate::Response& self); +void insert(::microstrain::Serializer& serializer, const FilterGetBaseRate::Response& self); +void extract(::microstrain::Serializer& serializer, FilterGetBaseRate::Response& self); TypedResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut); @@ -787,8 +789,8 @@ struct PollData } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const PollData& self); -void extract(::microstrain::Buffer& serializer, PollData& self); +void insert(::microstrain::Serializer& serializer, const PollData& self); +void extract(::microstrain::Serializer& serializer, PollData& self); TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors); @@ -843,11 +845,11 @@ struct GetBaseRate } }; }; -void insert(::microstrain::Buffer& serializer, const GetBaseRate& self); -void extract(::microstrain::Buffer& serializer, GetBaseRate& self); +void insert(::microstrain::Serializer& serializer, const GetBaseRate& self); +void extract(::microstrain::Serializer& serializer, GetBaseRate& self); -void insert(::microstrain::Buffer& serializer, const GetBaseRate::Response& self); -void extract(::microstrain::Buffer& serializer, GetBaseRate::Response& self); +void insert(::microstrain::Serializer& serializer, const GetBaseRate::Response& self); +void extract(::microstrain::Serializer& serializer, GetBaseRate::Response& self); TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut); @@ -922,11 +924,11 @@ struct MessageFormat } }; }; -void insert(::microstrain::Buffer& serializer, const MessageFormat& self); -void extract(::microstrain::Buffer& serializer, MessageFormat& self); +void insert(::microstrain::Serializer& serializer, const MessageFormat& self); +void extract(::microstrain::Serializer& serializer, MessageFormat& self); -void insert(::microstrain::Buffer& serializer, const MessageFormat::Response& self); -void extract(::microstrain::Buffer& serializer, MessageFormat::Response& self); +void insert(::microstrain::Serializer& serializer, const MessageFormat::Response& self); +void extract(::microstrain::Serializer& serializer, MessageFormat::Response& self); TypedResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); @@ -974,8 +976,8 @@ struct NmeaPollData } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const NmeaPollData& self); -void extract(::microstrain::Buffer& serializer, NmeaPollData& self); +void insert(::microstrain::Serializer& serializer, const NmeaPollData& self); +void extract(::microstrain::Serializer& serializer, NmeaPollData& self); TypedResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries); @@ -1045,11 +1047,11 @@ struct NmeaMessageFormat } }; }; -void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat& self); -void extract(::microstrain::Buffer& serializer, NmeaMessageFormat& self); +void insert(::microstrain::Serializer& serializer, const NmeaMessageFormat& self); +void extract(::microstrain::Serializer& serializer, NmeaMessageFormat& self); -void insert(::microstrain::Buffer& serializer, const NmeaMessageFormat::Response& self); -void extract(::microstrain::Buffer& serializer, NmeaMessageFormat::Response& self); +void insert(::microstrain::Serializer& serializer, const NmeaMessageFormat::Response& self); +void extract(::microstrain::Serializer& serializer, NmeaMessageFormat::Response& self); TypedResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries); TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut); @@ -1106,8 +1108,8 @@ struct DeviceSettings typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const DeviceSettings& self); -void extract(::microstrain::Buffer& serializer, DeviceSettings& self); +void insert(::microstrain::Serializer& serializer, const DeviceSettings& self); +void extract(::microstrain::Serializer& serializer, DeviceSettings& self); TypedResult saveDeviceSettings(C::mip_interface& device); TypedResult loadDeviceSettings(C::mip_interface& device); @@ -1191,11 +1193,11 @@ struct UartBaudrate } }; }; -void insert(::microstrain::Buffer& serializer, const UartBaudrate& self); -void extract(::microstrain::Buffer& serializer, UartBaudrate& self); +void insert(::microstrain::Serializer& serializer, const UartBaudrate& self); +void extract(::microstrain::Serializer& serializer, UartBaudrate& self); -void insert(::microstrain::Buffer& serializer, const UartBaudrate::Response& self); -void extract(::microstrain::Buffer& serializer, UartBaudrate::Response& self); +void insert(::microstrain::Serializer& serializer, const UartBaudrate::Response& self); +void extract(::microstrain::Serializer& serializer, UartBaudrate::Response& self); TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud); TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut); @@ -1246,8 +1248,8 @@ struct FactoryStreaming } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const FactoryStreaming& self); -void extract(::microstrain::Buffer& serializer, FactoryStreaming& self); +void insert(::microstrain::Serializer& serializer, const FactoryStreaming& self); +void extract(::microstrain::Serializer& serializer, FactoryStreaming& self); TypedResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved); @@ -1327,11 +1329,11 @@ struct DatastreamControl } }; }; -void insert(::microstrain::Buffer& serializer, const DatastreamControl& self); -void extract(::microstrain::Buffer& serializer, DatastreamControl& self); +void insert(::microstrain::Serializer& serializer, const DatastreamControl& self); +void extract(::microstrain::Serializer& serializer, DatastreamControl& self); -void insert(::microstrain::Buffer& serializer, const DatastreamControl::Response& self); -void extract(::microstrain::Buffer& serializer, DatastreamControl::Response& self); +void insert(::microstrain::Serializer& serializer, const DatastreamControl::Response& self); +void extract(::microstrain::Serializer& serializer, DatastreamControl::Response& self); TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable); TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut); @@ -1469,14 +1471,14 @@ struct ConstellationSettings } }; }; -void insert(::microstrain::Buffer& serializer, const ConstellationSettings& self); -void extract(::microstrain::Buffer& serializer, ConstellationSettings& self); +void insert(::microstrain::Serializer& serializer, const ConstellationSettings& self); +void extract(::microstrain::Serializer& serializer, ConstellationSettings& self); -void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Settings& self); -void extract(::microstrain::Buffer& serializer, ConstellationSettings::Settings& self); +void insert(::microstrain::Serializer& serializer, const ConstellationSettings::Settings& self); +void extract(::microstrain::Serializer& serializer, ConstellationSettings::Settings& self); -void insert(::microstrain::Buffer& serializer, const ConstellationSettings::Response& self); -void extract(::microstrain::Buffer& serializer, ConstellationSettings::Response& self); +void insert(::microstrain::Serializer& serializer, const ConstellationSettings::Response& self); +void extract(::microstrain::Serializer& serializer, ConstellationSettings::Response& self); TypedResult writeConstellationSettings(C::mip_interface& device, uint16_t maxChannels, uint8_t configCount, const ConstellationSettings::Settings* settings); TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut); @@ -1588,11 +1590,11 @@ struct GnssSbasSettings } }; }; -void insert(::microstrain::Buffer& serializer, const GnssSbasSettings& self); -void extract(::microstrain::Buffer& serializer, GnssSbasSettings& self); +void insert(::microstrain::Serializer& serializer, const GnssSbasSettings& self); +void extract(::microstrain::Serializer& serializer, GnssSbasSettings& self); -void insert(::microstrain::Buffer& serializer, const GnssSbasSettings::Response& self); -void extract(::microstrain::Buffer& serializer, GnssSbasSettings::Response& self); +void insert(::microstrain::Serializer& serializer, const GnssSbasSettings::Response& self); +void extract(::microstrain::Serializer& serializer, GnssSbasSettings::Response& self); TypedResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns); TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut); @@ -1682,11 +1684,11 @@ struct GnssAssistedFix } }; }; -void insert(::microstrain::Buffer& serializer, const GnssAssistedFix& self); -void extract(::microstrain::Buffer& serializer, GnssAssistedFix& self); +void insert(::microstrain::Serializer& serializer, const GnssAssistedFix& self); +void extract(::microstrain::Serializer& serializer, GnssAssistedFix& self); -void insert(::microstrain::Buffer& serializer, const GnssAssistedFix::Response& self); -void extract(::microstrain::Buffer& serializer, GnssAssistedFix::Response& self); +void insert(::microstrain::Serializer& serializer, const GnssAssistedFix::Response& self); +void extract(::microstrain::Serializer& serializer, GnssAssistedFix::Response& self); TypedResult writeGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption option, uint8_t flags); TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut); @@ -1765,11 +1767,11 @@ struct GnssTimeAssistance } }; }; -void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance& self); -void extract(::microstrain::Buffer& serializer, GnssTimeAssistance& self); +void insert(::microstrain::Serializer& serializer, const GnssTimeAssistance& self); +void extract(::microstrain::Serializer& serializer, GnssTimeAssistance& self); -void insert(::microstrain::Buffer& serializer, const GnssTimeAssistance::Response& self); -void extract(::microstrain::Buffer& serializer, GnssTimeAssistance::Response& self); +void insert(::microstrain::Serializer& serializer, const GnssTimeAssistance::Response& self); +void extract(::microstrain::Serializer& serializer, GnssTimeAssistance::Response& self); TypedResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy); TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut); @@ -1862,11 +1864,11 @@ struct ImuLowpassFilter } }; }; -void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter& self); -void extract(::microstrain::Buffer& serializer, ImuLowpassFilter& self); +void insert(::microstrain::Serializer& serializer, const ImuLowpassFilter& self); +void extract(::microstrain::Serializer& serializer, ImuLowpassFilter& self); -void insert(::microstrain::Buffer& serializer, const ImuLowpassFilter::Response& self); -void extract(::microstrain::Buffer& serializer, ImuLowpassFilter::Response& self); +void insert(::microstrain::Serializer& serializer, const ImuLowpassFilter::Response& self); +void extract(::microstrain::Serializer& serializer, ImuLowpassFilter::Response& self); TypedResult writeImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved); TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut); @@ -1947,11 +1949,11 @@ struct PpsSource } }; }; -void insert(::microstrain::Buffer& serializer, const PpsSource& self); -void extract(::microstrain::Buffer& serializer, PpsSource& self); +void insert(::microstrain::Serializer& serializer, const PpsSource& self); +void extract(::microstrain::Serializer& serializer, PpsSource& self); -void insert(::microstrain::Buffer& serializer, const PpsSource::Response& self); -void extract(::microstrain::Buffer& serializer, PpsSource::Response& self); +void insert(::microstrain::Serializer& serializer, const PpsSource::Response& self); +void extract(::microstrain::Serializer& serializer, PpsSource::Response& self); TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source); TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut); @@ -2106,11 +2108,11 @@ struct GpioConfig } }; }; -void insert(::microstrain::Buffer& serializer, const GpioConfig& self); -void extract(::microstrain::Buffer& serializer, GpioConfig& self); +void insert(::microstrain::Serializer& serializer, const GpioConfig& self); +void extract(::microstrain::Serializer& serializer, GpioConfig& self); -void insert(::microstrain::Buffer& serializer, const GpioConfig::Response& self); -void extract(::microstrain::Buffer& serializer, GpioConfig::Response& self); +void insert(::microstrain::Serializer& serializer, const GpioConfig::Response& self); +void extract(::microstrain::Serializer& serializer, GpioConfig::Response& self); TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode); TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut); @@ -2199,11 +2201,11 @@ struct GpioState } }; }; -void insert(::microstrain::Buffer& serializer, const GpioState& self); -void extract(::microstrain::Buffer& serializer, GpioState& self); +void insert(::microstrain::Serializer& serializer, const GpioState& self); +void extract(::microstrain::Serializer& serializer, GpioState& self); -void insert(::microstrain::Buffer& serializer, const GpioState::Response& self); -void extract(::microstrain::Buffer& serializer, GpioState::Response& self); +void insert(::microstrain::Serializer& serializer, const GpioState::Response& self); +void extract(::microstrain::Serializer& serializer, GpioState::Response& self); TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state); TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut); @@ -2283,11 +2285,11 @@ struct Odometer } }; }; -void insert(::microstrain::Buffer& serializer, const Odometer& self); -void extract(::microstrain::Buffer& serializer, Odometer& self); +void insert(::microstrain::Serializer& serializer, const Odometer& self); +void extract(::microstrain::Serializer& serializer, Odometer& self); -void insert(::microstrain::Buffer& serializer, const Odometer::Response& self); -void extract(::microstrain::Buffer& serializer, Odometer::Response& self); +void insert(::microstrain::Serializer& serializer, const Odometer::Response& self); +void extract(::microstrain::Serializer& serializer, Odometer::Response& self); TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty); TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut); @@ -2376,14 +2378,14 @@ struct GetEventSupport } }; }; -void insert(::microstrain::Buffer& serializer, const GetEventSupport& self); -void extract(::microstrain::Buffer& serializer, GetEventSupport& self); +void insert(::microstrain::Serializer& serializer, const GetEventSupport& self); +void extract(::microstrain::Serializer& serializer, GetEventSupport& self); -void insert(::microstrain::Buffer& serializer, const GetEventSupport::Info& self); -void extract(::microstrain::Buffer& serializer, GetEventSupport::Info& self); +void insert(::microstrain::Serializer& serializer, const GetEventSupport::Info& self); +void extract(::microstrain::Serializer& serializer, GetEventSupport::Info& self); -void insert(::microstrain::Buffer& serializer, const GetEventSupport::Response& self); -void extract(::microstrain::Buffer& serializer, GetEventSupport::Response& self); +void insert(::microstrain::Serializer& serializer, const GetEventSupport::Response& self); +void extract(::microstrain::Serializer& serializer, GetEventSupport::Response& self); TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut); @@ -2471,11 +2473,11 @@ struct EventControl } }; }; -void insert(::microstrain::Buffer& serializer, const EventControl& self); -void extract(::microstrain::Buffer& serializer, EventControl& self); +void insert(::microstrain::Serializer& serializer, const EventControl& self); +void extract(::microstrain::Serializer& serializer, EventControl& self); -void insert(::microstrain::Buffer& serializer, const EventControl::Response& self); -void extract(::microstrain::Buffer& serializer, EventControl::Response& self); +void insert(::microstrain::Serializer& serializer, const EventControl::Response& self); +void extract(::microstrain::Serializer& serializer, EventControl::Response& self); TypedResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode); TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut); @@ -2571,14 +2573,14 @@ struct GetEventTriggerStatus } }; }; -void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus& self); -void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus& self); +void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus& self); +void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus& self); -void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Entry& self); -void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Entry& self); +void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus::Entry& self); +void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus::Entry& self); -void insert(::microstrain::Buffer& serializer, const GetEventTriggerStatus::Response& self); -void extract(::microstrain::Buffer& serializer, GetEventTriggerStatus::Response& self); +void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus::Response& self); +void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus::Response& self); TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut); @@ -2639,14 +2641,14 @@ struct GetEventActionStatus } }; }; -void insert(::microstrain::Buffer& serializer, const GetEventActionStatus& self); -void extract(::microstrain::Buffer& serializer, GetEventActionStatus& self); +void insert(::microstrain::Serializer& serializer, const GetEventActionStatus& self); +void extract(::microstrain::Serializer& serializer, GetEventActionStatus& self); -void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Entry& self); -void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Entry& self); +void insert(::microstrain::Serializer& serializer, const GetEventActionStatus::Entry& self); +void extract(::microstrain::Serializer& serializer, GetEventActionStatus::Entry& self); -void insert(::microstrain::Buffer& serializer, const GetEventActionStatus::Response& self); -void extract(::microstrain::Buffer& serializer, GetEventActionStatus::Response& self); +void insert(::microstrain::Serializer& serializer, const GetEventActionStatus::Response& self); +void extract(::microstrain::Serializer& serializer, GetEventActionStatus::Response& self); TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut); @@ -2792,20 +2794,20 @@ struct EventTrigger } }; }; -void insert(::microstrain::Buffer& serializer, const EventTrigger& self); -void extract(::microstrain::Buffer& serializer, EventTrigger& self); +void insert(::microstrain::Serializer& serializer, const EventTrigger& self); +void extract(::microstrain::Serializer& serializer, EventTrigger& self); -void insert(::microstrain::Buffer& serializer, const EventTrigger::GpioParams& self); -void extract(::microstrain::Buffer& serializer, EventTrigger::GpioParams& self); +void insert(::microstrain::Serializer& serializer, const EventTrigger::GpioParams& self); +void extract(::microstrain::Serializer& serializer, EventTrigger::GpioParams& self); -void insert(::microstrain::Buffer& serializer, const EventTrigger::ThresholdParams& self); -void extract(::microstrain::Buffer& serializer, EventTrigger::ThresholdParams& self); +void insert(::microstrain::Serializer& serializer, const EventTrigger::ThresholdParams& self); +void extract(::microstrain::Serializer& serializer, EventTrigger::ThresholdParams& self); -void insert(::microstrain::Buffer& serializer, const EventTrigger::CombinationParams& self); -void extract(::microstrain::Buffer& serializer, EventTrigger::CombinationParams& self); +void insert(::microstrain::Serializer& serializer, const EventTrigger::CombinationParams& self); +void extract(::microstrain::Serializer& serializer, EventTrigger::CombinationParams& self); -void insert(::microstrain::Buffer& serializer, const EventTrigger::Response& self); -void extract(::microstrain::Buffer& serializer, EventTrigger::Response& self); +void insert(::microstrain::Serializer& serializer, const EventTrigger::Response& self); +void extract(::microstrain::Serializer& serializer, EventTrigger::Response& self); TypedResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters); TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut); @@ -2922,17 +2924,17 @@ struct EventAction } }; }; -void insert(::microstrain::Buffer& serializer, const EventAction& self); -void extract(::microstrain::Buffer& serializer, EventAction& self); +void insert(::microstrain::Serializer& serializer, const EventAction& self); +void extract(::microstrain::Serializer& serializer, EventAction& self); -void insert(::microstrain::Buffer& serializer, const EventAction::GpioParams& self); -void extract(::microstrain::Buffer& serializer, EventAction::GpioParams& self); +void insert(::microstrain::Serializer& serializer, const EventAction::GpioParams& self); +void extract(::microstrain::Serializer& serializer, EventAction::GpioParams& self); -void insert(::microstrain::Buffer& serializer, const EventAction::MessageParams& self); -void extract(::microstrain::Buffer& serializer, EventAction::MessageParams& self); +void insert(::microstrain::Serializer& serializer, const EventAction::MessageParams& self); +void extract(::microstrain::Serializer& serializer, EventAction::MessageParams& self); -void insert(::microstrain::Buffer& serializer, const EventAction::Response& self); -void extract(::microstrain::Buffer& serializer, EventAction::Response& self); +void insert(::microstrain::Serializer& serializer, const EventAction::Response& self); +void extract(::microstrain::Serializer& serializer, EventAction::Response& self); TypedResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters); TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut); @@ -3006,11 +3008,11 @@ struct AccelBias } }; }; -void insert(::microstrain::Buffer& serializer, const AccelBias& self); -void extract(::microstrain::Buffer& serializer, AccelBias& self); +void insert(::microstrain::Serializer& serializer, const AccelBias& self); +void extract(::microstrain::Serializer& serializer, AccelBias& self); -void insert(::microstrain::Buffer& serializer, const AccelBias::Response& self); -void extract(::microstrain::Buffer& serializer, AccelBias::Response& self); +void insert(::microstrain::Serializer& serializer, const AccelBias::Response& self); +void extract(::microstrain::Serializer& serializer, AccelBias::Response& self); TypedResult writeAccelBias(C::mip_interface& device, const float* bias); TypedResult readAccelBias(C::mip_interface& device, float* biasOut); @@ -3084,11 +3086,11 @@ struct GyroBias } }; }; -void insert(::microstrain::Buffer& serializer, const GyroBias& self); -void extract(::microstrain::Buffer& serializer, GyroBias& self); +void insert(::microstrain::Serializer& serializer, const GyroBias& self); +void extract(::microstrain::Serializer& serializer, GyroBias& self); -void insert(::microstrain::Buffer& serializer, const GyroBias::Response& self); -void extract(::microstrain::Buffer& serializer, GyroBias::Response& self); +void insert(::microstrain::Serializer& serializer, const GyroBias::Response& self); +void extract(::microstrain::Serializer& serializer, GyroBias::Response& self); TypedResult writeGyroBias(C::mip_interface& device, const float* bias); TypedResult readGyroBias(C::mip_interface& device, float* biasOut); @@ -3151,11 +3153,11 @@ struct CaptureGyroBias } }; }; -void insert(::microstrain::Buffer& serializer, const CaptureGyroBias& self); -void extract(::microstrain::Buffer& serializer, CaptureGyroBias& self); +void insert(::microstrain::Serializer& serializer, const CaptureGyroBias& self); +void extract(::microstrain::Serializer& serializer, CaptureGyroBias& self); -void insert(::microstrain::Buffer& serializer, const CaptureGyroBias::Response& self); -void extract(::microstrain::Buffer& serializer, CaptureGyroBias::Response& self); +void insert(::microstrain::Serializer& serializer, const CaptureGyroBias::Response& self); +void extract(::microstrain::Serializer& serializer, CaptureGyroBias::Response& self); TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut); @@ -3229,11 +3231,11 @@ struct MagHardIronOffset } }; }; -void insert(::microstrain::Buffer& serializer, const MagHardIronOffset& self); -void extract(::microstrain::Buffer& serializer, MagHardIronOffset& self); +void insert(::microstrain::Serializer& serializer, const MagHardIronOffset& self); +void extract(::microstrain::Serializer& serializer, MagHardIronOffset& self); -void insert(::microstrain::Buffer& serializer, const MagHardIronOffset::Response& self); -void extract(::microstrain::Buffer& serializer, MagHardIronOffset::Response& self); +void insert(::microstrain::Serializer& serializer, const MagHardIronOffset::Response& self); +void extract(::microstrain::Serializer& serializer, MagHardIronOffset::Response& self); TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset); TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut); @@ -3315,11 +3317,11 @@ struct MagSoftIronMatrix } }; }; -void insert(::microstrain::Buffer& serializer, const MagSoftIronMatrix& self); -void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix& self); +void insert(::microstrain::Serializer& serializer, const MagSoftIronMatrix& self); +void extract(::microstrain::Serializer& serializer, MagSoftIronMatrix& self); -void insert(::microstrain::Buffer& serializer, const MagSoftIronMatrix::Response& self); -void extract(::microstrain::Buffer& serializer, MagSoftIronMatrix::Response& self); +void insert(::microstrain::Serializer& serializer, const MagSoftIronMatrix::Response& self); +void extract(::microstrain::Serializer& serializer, MagSoftIronMatrix::Response& self); TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset); TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut); @@ -3391,11 +3393,11 @@ struct ConingScullingEnable } }; }; -void insert(::microstrain::Buffer& serializer, const ConingScullingEnable& self); -void extract(::microstrain::Buffer& serializer, ConingScullingEnable& self); +void insert(::microstrain::Serializer& serializer, const ConingScullingEnable& self); +void extract(::microstrain::Serializer& serializer, ConingScullingEnable& self); -void insert(::microstrain::Buffer& serializer, const ConingScullingEnable::Response& self); -void extract(::microstrain::Buffer& serializer, ConingScullingEnable::Response& self); +void insert(::microstrain::Serializer& serializer, const ConingScullingEnable::Response& self); +void extract(::microstrain::Serializer& serializer, ConingScullingEnable::Response& self); TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable); TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut); @@ -3495,11 +3497,11 @@ struct Sensor2VehicleTransformEuler } }; }; -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEuler& self); -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler& self); +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformEuler& self); +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformEuler& self); -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformEuler::Response& self); -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformEuler::Response& self); +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformEuler::Response& self); +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformEuler::Response& self); TypedResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw); TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut); @@ -3603,11 +3605,11 @@ struct Sensor2VehicleTransformQuaternion } }; }; -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformQuaternion& self); -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternion& self); +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformQuaternion& self); +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformQuaternion& self); -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformQuaternion::Response& self); -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformQuaternion::Response& self); +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformQuaternion::Response& self); +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformQuaternion::Response& self); TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q); TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut); @@ -3709,11 +3711,11 @@ struct Sensor2VehicleTransformDcm } }; }; -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformDcm& self); -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm& self); +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformDcm& self); +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformDcm& self); -void insert(::microstrain::Buffer& serializer, const Sensor2VehicleTransformDcm::Response& self); -void extract(::microstrain::Buffer& serializer, Sensor2VehicleTransformDcm::Response& self); +void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformDcm::Response& self); +void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformDcm::Response& self); TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm); TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut); @@ -3795,11 +3797,11 @@ struct ComplementaryFilter } }; }; -void insert(::microstrain::Buffer& serializer, const ComplementaryFilter& self); -void extract(::microstrain::Buffer& serializer, ComplementaryFilter& self); +void insert(::microstrain::Serializer& serializer, const ComplementaryFilter& self); +void extract(::microstrain::Serializer& serializer, ComplementaryFilter& self); -void insert(::microstrain::Buffer& serializer, const ComplementaryFilter::Response& self); -void extract(::microstrain::Buffer& serializer, ComplementaryFilter::Response& self); +void insert(::microstrain::Serializer& serializer, const ComplementaryFilter::Response& self); +void extract(::microstrain::Serializer& serializer, ComplementaryFilter::Response& self); TypedResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant); TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut); @@ -3881,11 +3883,11 @@ struct SensorRange } }; }; -void insert(::microstrain::Buffer& serializer, const SensorRange& self); -void extract(::microstrain::Buffer& serializer, SensorRange& self); +void insert(::microstrain::Serializer& serializer, const SensorRange& self); +void extract(::microstrain::Serializer& serializer, SensorRange& self); -void insert(::microstrain::Buffer& serializer, const SensorRange::Response& self); -void extract(::microstrain::Buffer& serializer, SensorRange::Response& self); +void insert(::microstrain::Serializer& serializer, const SensorRange::Response& self); +void extract(::microstrain::Serializer& serializer, SensorRange::Response& self); TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting); TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut); @@ -3954,14 +3956,14 @@ struct CalibratedSensorRanges } }; }; -void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges& self); -void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges& self); +void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges& self); +void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges& self); -void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges::Entry& self); -void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Entry& self); +void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges::Entry& self); +void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges::Entry& self); -void insert(::microstrain::Buffer& serializer, const CalibratedSensorRanges::Response& self); -void extract(::microstrain::Buffer& serializer, CalibratedSensorRanges::Response& self); +void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges::Response& self); +void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges::Response& self); TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut); @@ -4052,11 +4054,11 @@ struct LowpassFilter } }; }; -void insert(::microstrain::Buffer& serializer, const LowpassFilter& self); -void extract(::microstrain::Buffer& serializer, LowpassFilter& self); +void insert(::microstrain::Serializer& serializer, const LowpassFilter& self); +void extract(::microstrain::Serializer& serializer, LowpassFilter& self); -void insert(::microstrain::Buffer& serializer, const LowpassFilter::Response& self); -void extract(::microstrain::Buffer& serializer, LowpassFilter::Response& self); +void insert(::microstrain::Serializer& serializer, const LowpassFilter::Response& self); +void extract(::microstrain::Serializer& serializer, LowpassFilter::Response& self); TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool enable, bool manual, float frequency); TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut); diff --git a/src/mip/definitions/commands_aiding.cpp b/src/mip/definitions/commands_aiding.cpp index 93f4d5221..319abdb5d 100644 --- a/src/mip/definitions/commands_aiding.cpp +++ b/src/mip/definitions/commands_aiding.cpp @@ -1,7 +1,7 @@ #include "commands_aiding.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -24,7 +24,7 @@ using namespace ::mip::C; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const Time& self) +void insert(::microstrain::Serializer& serializer, const Time& self) { insert(serializer, self.timebase); @@ -33,7 +33,7 @@ void insert(::microstrain::Buffer& serializer, const Time& self) insert(serializer, self.nanoseconds); } -void extract(::microstrain::Buffer& serializer, Time& self) +void extract(::microstrain::Serializer& serializer, Time& self) { extract(serializer, self.timebase); @@ -48,7 +48,7 @@ void extract(::microstrain::Buffer& serializer, Time& self) // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const FrameConfig& self) +void insert(::microstrain::Serializer& serializer, const FrameConfig& self) { insert(serializer, self.function); @@ -78,7 +78,7 @@ void insert(::microstrain::Buffer& serializer, const FrameConfig& self) } } } -void extract(::microstrain::Buffer& serializer, FrameConfig& self) +void extract(::microstrain::Serializer& serializer, FrameConfig& self) { extract(serializer, self.function); @@ -109,7 +109,7 @@ void extract(::microstrain::Buffer& serializer, FrameConfig& self) } } -void insert(::microstrain::Buffer& serializer, const FrameConfig::Response& self) +void insert(::microstrain::Serializer& serializer, const FrameConfig::Response& self) { insert(serializer, self.frame_id); @@ -131,7 +131,7 @@ void insert(::microstrain::Buffer& serializer, const FrameConfig::Response& self } } -void extract(::microstrain::Buffer& serializer, FrameConfig::Response& self) +void extract(::microstrain::Serializer& serializer, FrameConfig::Response& self) { extract(serializer, self.frame_id); @@ -156,8 +156,8 @@ void extract(::microstrain::Buffer& serializer, FrameConfig::Response& self) TypedResult writeFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool trackingEnabled, const float* translation, const FrameConfig::Rotation& rotation) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, frameId); @@ -186,8 +186,8 @@ TypedResult writeFrameConfig(C::mip_interface& device, uint8_t fram } TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, frameId); @@ -201,7 +201,7 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, frameId); @@ -231,8 +231,8 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame } TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frameId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, frameId); @@ -243,8 +243,8 @@ TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frame } TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frameId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, frameId); @@ -255,8 +255,8 @@ TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frame } TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t frameId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, frameId); @@ -265,7 +265,7 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AidingEchoControl& self) +void insert(::microstrain::Serializer& serializer, const AidingEchoControl& self) { insert(serializer, self.function); @@ -275,7 +275,7 @@ void insert(::microstrain::Buffer& serializer, const AidingEchoControl& self) } } -void extract(::microstrain::Buffer& serializer, AidingEchoControl& self) +void extract(::microstrain::Serializer& serializer, AidingEchoControl& self) { extract(serializer, self.function); @@ -286,12 +286,12 @@ void extract(::microstrain::Buffer& serializer, AidingEchoControl& self) } } -void insert(::microstrain::Buffer& serializer, const AidingEchoControl::Response& self) +void insert(::microstrain::Serializer& serializer, const AidingEchoControl::Response& self) { insert(serializer, self.mode); } -void extract(::microstrain::Buffer& serializer, AidingEchoControl::Response& self) +void extract(::microstrain::Serializer& serializer, AidingEchoControl::Response& self) { extract(serializer, self.mode); @@ -299,8 +299,8 @@ void extract(::microstrain::Buffer& serializer, AidingEchoControl::Response& sel TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); @@ -311,8 +311,8 @@ TypedResult writeAidingEchoControl(C::mip_interface& device, } TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -322,7 +322,7 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -334,8 +334,8 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A } TypedResult saveAidingEchoControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -344,8 +344,8 @@ TypedResult saveAidingEchoControl(C::mip_interface& device) } TypedResult loadAidingEchoControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -354,15 +354,15 @@ TypedResult loadAidingEchoControl(C::mip_interface& device) } TypedResult defaultAidingEchoControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const EcefPos& self) +void insert(::microstrain::Serializer& serializer, const EcefPos& self) { insert(serializer, self.time); @@ -377,7 +377,7 @@ void insert(::microstrain::Buffer& serializer, const EcefPos& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, EcefPos& self) +void extract(::microstrain::Serializer& serializer, EcefPos& self) { extract(serializer, self.time); @@ -395,8 +395,8 @@ void extract(::microstrain::Buffer& serializer, EcefPos& self) TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -416,7 +416,7 @@ TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const LlhPos& self) +void insert(::microstrain::Serializer& serializer, const LlhPos& self) { insert(serializer, self.time); @@ -434,7 +434,7 @@ void insert(::microstrain::Buffer& serializer, const LlhPos& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, LlhPos& self) +void extract(::microstrain::Serializer& serializer, LlhPos& self) { extract(serializer, self.time); @@ -455,8 +455,8 @@ void extract(::microstrain::Buffer& serializer, LlhPos& self) TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -478,7 +478,7 @@ TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const Height& self) +void insert(::microstrain::Serializer& serializer, const Height& self) { insert(serializer, self.time); @@ -491,7 +491,7 @@ void insert(::microstrain::Buffer& serializer, const Height& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, Height& self) +void extract(::microstrain::Serializer& serializer, Height& self) { extract(serializer, self.time); @@ -507,8 +507,8 @@ void extract(::microstrain::Buffer& serializer, Height& self) TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -524,7 +524,7 @@ TypedResult height(C::mip_interface& device, const Time& time, uint8_t f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const EcefVel& self) +void insert(::microstrain::Serializer& serializer, const EcefVel& self) { insert(serializer, self.time); @@ -539,7 +539,7 @@ void insert(::microstrain::Buffer& serializer, const EcefVel& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, EcefVel& self) +void extract(::microstrain::Serializer& serializer, EcefVel& self) { extract(serializer, self.time); @@ -557,8 +557,8 @@ void extract(::microstrain::Buffer& serializer, EcefVel& self) TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -578,7 +578,7 @@ TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const NedVel& self) +void insert(::microstrain::Serializer& serializer, const NedVel& self) { insert(serializer, self.time); @@ -593,7 +593,7 @@ void insert(::microstrain::Buffer& serializer, const NedVel& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, NedVel& self) +void extract(::microstrain::Serializer& serializer, NedVel& self) { extract(serializer, self.time); @@ -611,8 +611,8 @@ void extract(::microstrain::Buffer& serializer, NedVel& self) TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -632,7 +632,7 @@ TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const VehicleFixedFrameVelocity& self) +void insert(::microstrain::Serializer& serializer, const VehicleFixedFrameVelocity& self) { insert(serializer, self.time); @@ -647,7 +647,7 @@ void insert(::microstrain::Buffer& serializer, const VehicleFixedFrameVelocity& insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, VehicleFixedFrameVelocity& self) +void extract(::microstrain::Serializer& serializer, VehicleFixedFrameVelocity& self) { extract(serializer, self.time); @@ -665,8 +665,8 @@ void extract(::microstrain::Buffer& serializer, VehicleFixedFrameVelocity& self) TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -686,7 +686,7 @@ TypedResult vehicleFixedFrameVelocity(C::mip_interfac return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ODOM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const TrueHeading& self) +void insert(::microstrain::Serializer& serializer, const TrueHeading& self) { insert(serializer, self.time); @@ -699,7 +699,7 @@ void insert(::microstrain::Buffer& serializer, const TrueHeading& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, TrueHeading& self) +void extract(::microstrain::Serializer& serializer, TrueHeading& self) { extract(serializer, self.time); @@ -715,8 +715,8 @@ void extract(::microstrain::Buffer& serializer, TrueHeading& self) TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -732,7 +732,7 @@ TypedResult trueHeading(C::mip_interface& device, const Time& time, return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_TRUE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const MagneticField& self) +void insert(::microstrain::Serializer& serializer, const MagneticField& self) { insert(serializer, self.time); @@ -747,7 +747,7 @@ void insert(::microstrain::Buffer& serializer, const MagneticField& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagneticField& self) +void extract(::microstrain::Serializer& serializer, MagneticField& self) { extract(serializer, self.time); @@ -765,8 +765,8 @@ void extract(::microstrain::Buffer& serializer, MagneticField& self) TypedResult magneticField(C::mip_interface& device, const Time& time, uint8_t frameId, const float* magneticField, const float* uncertainty, MagneticField::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, time); @@ -786,7 +786,7 @@ TypedResult magneticField(C::mip_interface& device, const Time& t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_FIELD, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const Pressure& self) +void insert(::microstrain::Serializer& serializer, const Pressure& self) { insert(serializer, self.time); @@ -799,7 +799,7 @@ void insert(::microstrain::Buffer& serializer, const Pressure& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, Pressure& self) +void extract(::microstrain::Serializer& serializer, Pressure& self) { extract(serializer, self.time); @@ -815,8 +815,8 @@ void extract(::microstrain::Buffer& serializer, Pressure& self) TypedResult pressure(C::mip_interface& device, const Time& time, uint8_t frameId, float pressure, float uncertainty, uint16_t validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, time); diff --git a/src/mip/definitions/commands_aiding.hpp b/src/mip/definitions/commands_aiding.hpp index f2b7bd23e..b8f3cef89 100644 --- a/src/mip/definitions/commands_aiding.hpp +++ b/src/mip/definitions/commands_aiding.hpp @@ -73,8 +73,8 @@ struct Time uint64_t nanoseconds = 0; ///< Nanoseconds since the timebase epoch. }; -void insert(::microstrain::Buffer& serializer, const Time& self); -void extract(::microstrain::Buffer& serializer, Time& self); +void insert(::microstrain::Serializer& serializer, const Time& self); +void extract(::microstrain::Serializer& serializer, Time& self); //////////////////////////////////////////////////////////////////////////////// @@ -188,11 +188,11 @@ struct FrameConfig } }; }; -void insert(::microstrain::Buffer& serializer, const FrameConfig& self); -void extract(::microstrain::Buffer& serializer, FrameConfig& self); +void insert(::microstrain::Serializer& serializer, const FrameConfig& self); +void extract(::microstrain::Serializer& serializer, FrameConfig& self); -void insert(::microstrain::Buffer& serializer, const FrameConfig::Response& self); -void extract(::microstrain::Buffer& serializer, FrameConfig::Response& self); +void insert(::microstrain::Serializer& serializer, const FrameConfig::Response& self); +void extract(::microstrain::Serializer& serializer, FrameConfig::Response& self); TypedResult writeFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool trackingEnabled, const float* translation, const FrameConfig::Rotation& rotation); TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut); @@ -271,11 +271,11 @@ struct AidingEchoControl } }; }; -void insert(::microstrain::Buffer& serializer, const AidingEchoControl& self); -void extract(::microstrain::Buffer& serializer, AidingEchoControl& self); +void insert(::microstrain::Serializer& serializer, const AidingEchoControl& self); +void extract(::microstrain::Serializer& serializer, AidingEchoControl& self); -void insert(::microstrain::Buffer& serializer, const AidingEchoControl::Response& self); -void extract(::microstrain::Buffer& serializer, AidingEchoControl::Response& self); +void insert(::microstrain::Serializer& serializer, const AidingEchoControl::Response& self); +void extract(::microstrain::Serializer& serializer, AidingEchoControl::Response& self); TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode); TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut); @@ -350,8 +350,8 @@ struct EcefPos } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const EcefPos& self); -void extract(::microstrain::Buffer& serializer, EcefPos& self); +void insert(::microstrain::Serializer& serializer, const EcefPos& self); +void extract(::microstrain::Serializer& serializer, EcefPos& self); TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags); @@ -425,8 +425,8 @@ struct LlhPos } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const LlhPos& self); -void extract(::microstrain::Buffer& serializer, LlhPos& self); +void insert(::microstrain::Serializer& serializer, const LlhPos& self); +void extract(::microstrain::Serializer& serializer, LlhPos& self); TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags); @@ -466,8 +466,8 @@ struct Height } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const Height& self); -void extract(::microstrain::Buffer& serializer, Height& self); +void insert(::microstrain::Serializer& serializer, const Height& self); +void extract(::microstrain::Serializer& serializer, Height& self); TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags); @@ -538,8 +538,8 @@ struct EcefVel } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const EcefVel& self); -void extract(::microstrain::Buffer& serializer, EcefVel& self); +void insert(::microstrain::Serializer& serializer, const EcefVel& self); +void extract(::microstrain::Serializer& serializer, EcefVel& self); TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags); @@ -610,8 +610,8 @@ struct NedVel } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const NedVel& self); -void extract(::microstrain::Buffer& serializer, NedVel& self); +void insert(::microstrain::Serializer& serializer, const NedVel& self); +void extract(::microstrain::Serializer& serializer, NedVel& self); TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags); @@ -683,8 +683,8 @@ struct VehicleFixedFrameVelocity } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const VehicleFixedFrameVelocity& self); -void extract(::microstrain::Buffer& serializer, VehicleFixedFrameVelocity& self); +void insert(::microstrain::Serializer& serializer, const VehicleFixedFrameVelocity& self); +void extract(::microstrain::Serializer& serializer, VehicleFixedFrameVelocity& self); TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags); @@ -723,8 +723,8 @@ struct TrueHeading } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const TrueHeading& self); -void extract(::microstrain::Buffer& serializer, TrueHeading& self); +void insert(::microstrain::Serializer& serializer, const TrueHeading& self); +void extract(::microstrain::Serializer& serializer, TrueHeading& self); TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); @@ -795,8 +795,8 @@ struct MagneticField } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const MagneticField& self); -void extract(::microstrain::Buffer& serializer, MagneticField& self); +void insert(::microstrain::Serializer& serializer, const MagneticField& self); +void extract(::microstrain::Serializer& serializer, MagneticField& self); TypedResult magneticField(C::mip_interface& device, const Time& time, uint8_t frameId, const float* magneticField, const float* uncertainty, MagneticField::ValidFlags validFlags); @@ -836,8 +836,8 @@ struct Pressure } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const Pressure& self); -void extract(::microstrain::Buffer& serializer, Pressure& self); +void insert(::microstrain::Serializer& serializer, const Pressure& self); +void extract(::microstrain::Serializer& serializer, Pressure& self); TypedResult pressure(C::mip_interface& device, const Time& time, uint8_t frameId, float pressure, float uncertainty, uint16_t validFlags); diff --git a/src/mip/definitions/commands_base.cpp b/src/mip/definitions/commands_base.cpp index 43d34a490..6f22ae166 100644 --- a/src/mip/definitions/commands_base.cpp +++ b/src/mip/definitions/commands_base.cpp @@ -1,7 +1,7 @@ #include "commands_base.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -14,7 +14,7 @@ struct mip_interface; namespace commands_base { -using ::microstrain::Buffer; +using ::microstrain::Serializer; using ::microstrain::insert; using ::microstrain::extract; using namespace ::mip::C; @@ -23,7 +23,7 @@ using namespace ::mip::C; // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const BaseDeviceInfo& self) +void insert(::microstrain::Serializer& serializer, const BaseDeviceInfo& self) { insert(serializer, self.firmware_version); @@ -43,7 +43,7 @@ void insert(::microstrain::Buffer& serializer, const BaseDeviceInfo& self) insert(serializer, self.device_options[i]); } -void extract(::microstrain::Buffer& serializer, BaseDeviceInfo& self) +void extract(::microstrain::Serializer& serializer, BaseDeviceInfo& self) { extract(serializer, self.firmware_version); @@ -69,12 +69,12 @@ void extract(::microstrain::Buffer& serializer, BaseDeviceInfo& self) // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const Ping& self) +void insert(::microstrain::Serializer& serializer, const Ping& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, Ping& self) +void extract(::microstrain::Serializer& serializer, Ping& self) { (void)serializer; (void)self; @@ -84,12 +84,12 @@ TypedResult ping(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PING, NULL, 0); } -void insert(::microstrain::Buffer& serializer, const SetIdle& self) +void insert(::microstrain::Serializer& serializer, const SetIdle& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, SetIdle& self) +void extract(::microstrain::Serializer& serializer, SetIdle& self) { (void)serializer; (void)self; @@ -99,23 +99,23 @@ TypedResult setIdle(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_TO_IDLE, NULL, 0); } -void insert(::microstrain::Buffer& serializer, const GetDeviceInfo& self) +void insert(::microstrain::Serializer& serializer, const GetDeviceInfo& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetDeviceInfo& self) +void extract(::microstrain::Serializer& serializer, GetDeviceInfo& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetDeviceInfo::Response& self) +void insert(::microstrain::Serializer& serializer, const GetDeviceInfo::Response& self) { insert(serializer, self.device_info); } -void extract(::microstrain::Buffer& serializer, GetDeviceInfo::Response& self) +void extract(::microstrain::Serializer& serializer, GetDeviceInfo::Response& self) { extract(serializer, self.device_info); @@ -130,7 +130,7 @@ TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInf if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(deviceInfoOut); extract(deserializer, *deviceInfoOut); @@ -140,24 +140,24 @@ TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInf } return result; } -void insert(::microstrain::Buffer& serializer, const GetDeviceDescriptors& self) +void insert(::microstrain::Serializer& serializer, const GetDeviceDescriptors& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetDeviceDescriptors& self) +void extract(::microstrain::Serializer& serializer, GetDeviceDescriptors& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetDeviceDescriptors::Response& self) +void insert(::microstrain::Serializer& serializer, const GetDeviceDescriptors::Response& self) { for(unsigned int i=0; i < self.descriptors_count; i++) insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, GetDeviceDescriptors::Response& self) +void extract(::microstrain::Serializer& serializer, GetDeviceDescriptors::Response& self) { for(self.descriptors_count = 0; (self.descriptors_count < sizeof(self.descriptors)/sizeof(self.descriptors[0])) && (serializer.remaining() > 0); (self.descriptors_count)++) extract(serializer, self.descriptors[self.descriptors_count]); @@ -173,7 +173,7 @@ TypedResult getDeviceDescriptors(C::mip_interface& device, if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) extract(deserializer, descriptorsOut[*descriptorsOutCount]); @@ -183,23 +183,23 @@ TypedResult getDeviceDescriptors(C::mip_interface& device, } return result; } -void insert(::microstrain::Buffer& serializer, const BuiltInTest& self) +void insert(::microstrain::Serializer& serializer, const BuiltInTest& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, BuiltInTest& self) +void extract(::microstrain::Serializer& serializer, BuiltInTest& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const BuiltInTest::Response& self) +void insert(::microstrain::Serializer& serializer, const BuiltInTest::Response& self) { insert(serializer, self.result); } -void extract(::microstrain::Buffer& serializer, BuiltInTest::Response& self) +void extract(::microstrain::Serializer& serializer, BuiltInTest::Response& self) { extract(serializer, self.result); @@ -214,7 +214,7 @@ TypedResult builtInTest(C::mip_interface& device, uint32_t* resultO if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(resultOut); extract(deserializer, *resultOut); @@ -224,12 +224,12 @@ TypedResult builtInTest(C::mip_interface& device, uint32_t* resultO } return result; } -void insert(::microstrain::Buffer& serializer, const Resume& self) +void insert(::microstrain::Serializer& serializer, const Resume& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, Resume& self) +void extract(::microstrain::Serializer& serializer, Resume& self) { (void)serializer; (void)self; @@ -239,24 +239,24 @@ TypedResult resume(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESUME, NULL, 0); } -void insert(::microstrain::Buffer& serializer, const GetExtendedDescriptors& self) +void insert(::microstrain::Serializer& serializer, const GetExtendedDescriptors& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetExtendedDescriptors& self) +void extract(::microstrain::Serializer& serializer, GetExtendedDescriptors& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetExtendedDescriptors::Response& self) +void insert(::microstrain::Serializer& serializer, const GetExtendedDescriptors::Response& self) { for(unsigned int i=0; i < self.descriptors_count; i++) insert(serializer, self.descriptors[i]); } -void extract(::microstrain::Buffer& serializer, GetExtendedDescriptors::Response& self) +void extract(::microstrain::Serializer& serializer, GetExtendedDescriptors::Response& self) { for(self.descriptors_count = 0; (self.descriptors_count < sizeof(self.descriptors)/sizeof(self.descriptors[0])) && (serializer.remaining() > 0); (self.descriptors_count)++) extract(serializer, self.descriptors[self.descriptors_count]); @@ -272,7 +272,7 @@ TypedResult getExtendedDescriptors(C::mip_interface& dev if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) extract(deserializer, descriptorsOut[*descriptorsOutCount]); @@ -282,24 +282,24 @@ TypedResult getExtendedDescriptors(C::mip_interface& dev } return result; } -void insert(::microstrain::Buffer& serializer, const ContinuousBit& self) +void insert(::microstrain::Serializer& serializer, const ContinuousBit& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, ContinuousBit& self) +void extract(::microstrain::Serializer& serializer, ContinuousBit& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const ContinuousBit::Response& self) +void insert(::microstrain::Serializer& serializer, const ContinuousBit::Response& self) { for(unsigned int i=0; i < 16; i++) insert(serializer, self.result[i]); } -void extract(::microstrain::Buffer& serializer, ContinuousBit::Response& self) +void extract(::microstrain::Serializer& serializer, ContinuousBit::Response& self) { for(unsigned int i=0; i < 16; i++) extract(serializer, self.result[i]); @@ -315,7 +315,7 @@ TypedResult continuousBit(C::mip_interface& device, uint8_t* resu if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(resultOut || (16 == 0)); for(unsigned int i=0; i < 16; i++) @@ -326,7 +326,7 @@ TypedResult continuousBit(C::mip_interface& device, uint8_t* resu } return result; } -void insert(::microstrain::Buffer& serializer, const CommSpeed& self) +void insert(::microstrain::Serializer& serializer, const CommSpeed& self) { insert(serializer, self.function); @@ -338,7 +338,7 @@ void insert(::microstrain::Buffer& serializer, const CommSpeed& self) } } -void extract(::microstrain::Buffer& serializer, CommSpeed& self) +void extract(::microstrain::Serializer& serializer, CommSpeed& self) { extract(serializer, self.function); @@ -351,14 +351,14 @@ void extract(::microstrain::Buffer& serializer, CommSpeed& self) } } -void insert(::microstrain::Buffer& serializer, const CommSpeed::Response& self) +void insert(::microstrain::Serializer& serializer, const CommSpeed::Response& self) { insert(serializer, self.port); insert(serializer, self.baud); } -void extract(::microstrain::Buffer& serializer, CommSpeed::Response& self) +void extract(::microstrain::Serializer& serializer, CommSpeed::Response& self) { extract(serializer, self.port); @@ -368,8 +368,8 @@ void extract(::microstrain::Buffer& serializer, CommSpeed::Response& self) TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, port); @@ -382,8 +382,8 @@ TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, ui } TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, port); @@ -395,7 +395,7 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, port); @@ -409,8 +409,8 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin } TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, port); @@ -421,8 +421,8 @@ TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) } TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, port); @@ -433,8 +433,8 @@ TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) } TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, port); @@ -443,7 +443,7 @@ TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GpsTimeUpdate& self) +void insert(::microstrain::Serializer& serializer, const GpsTimeUpdate& self) { insert(serializer, self.function); @@ -455,7 +455,7 @@ void insert(::microstrain::Buffer& serializer, const GpsTimeUpdate& self) } } -void extract(::microstrain::Buffer& serializer, GpsTimeUpdate& self) +void extract(::microstrain::Serializer& serializer, GpsTimeUpdate& self) { extract(serializer, self.function); @@ -470,8 +470,8 @@ void extract(::microstrain::Buffer& serializer, GpsTimeUpdate& self) TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, fieldId); @@ -482,12 +482,12 @@ TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeU return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SoftReset& self) +void insert(::microstrain::Serializer& serializer, const SoftReset& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, SoftReset& self) +void extract(::microstrain::Serializer& serializer, SoftReset& self) { (void)serializer; (void)self; diff --git a/src/mip/definitions/commands_base.hpp b/src/mip/definitions/commands_base.hpp index b62a413ff..6cfed1a41 100644 --- a/src/mip/definitions/commands_base.hpp +++ b/src/mip/definitions/commands_base.hpp @@ -10,7 +10,7 @@ namespace microstrain { -class Buffer; +class Serializer; } namespace mip { @@ -73,8 +73,8 @@ struct BaseDeviceInfo char device_options[16] = {0}; }; -void insert(::microstrain::Buffer& serializer, const BaseDeviceInfo& self); -void extract(::microstrain::Buffer& serializer, BaseDeviceInfo& self); +void insert(::microstrain::Serializer& serializer, const BaseDeviceInfo& self); +void extract(::microstrain::Serializer& serializer, BaseDeviceInfo& self); enum class TimeFormat : uint8_t { @@ -222,8 +222,8 @@ struct Ping } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const Ping& self); -void extract(::microstrain::Buffer& serializer, Ping& self); +void insert(::microstrain::Serializer& serializer, const Ping& self); +void extract(::microstrain::Serializer& serializer, Ping& self); TypedResult ping(C::mip_interface& device); @@ -262,8 +262,8 @@ struct SetIdle } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const SetIdle& self); -void extract(::microstrain::Buffer& serializer, SetIdle& self); +void insert(::microstrain::Serializer& serializer, const SetIdle& self); +void extract(::microstrain::Serializer& serializer, SetIdle& self); TypedResult setIdle(C::mip_interface& device); @@ -316,11 +316,11 @@ struct GetDeviceInfo } }; }; -void insert(::microstrain::Buffer& serializer, const GetDeviceInfo& self); -void extract(::microstrain::Buffer& serializer, GetDeviceInfo& self); +void insert(::microstrain::Serializer& serializer, const GetDeviceInfo& self); +void extract(::microstrain::Serializer& serializer, GetDeviceInfo& self); -void insert(::microstrain::Buffer& serializer, const GetDeviceInfo::Response& self); -void extract(::microstrain::Buffer& serializer, GetDeviceInfo::Response& self); +void insert(::microstrain::Serializer& serializer, const GetDeviceInfo::Response& self); +void extract(::microstrain::Serializer& serializer, GetDeviceInfo::Response& self); TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut); @@ -377,11 +377,11 @@ struct GetDeviceDescriptors } }; }; -void insert(::microstrain::Buffer& serializer, const GetDeviceDescriptors& self); -void extract(::microstrain::Buffer& serializer, GetDeviceDescriptors& self); +void insert(::microstrain::Serializer& serializer, const GetDeviceDescriptors& self); +void extract(::microstrain::Serializer& serializer, GetDeviceDescriptors& self); -void insert(::microstrain::Buffer& serializer, const GetDeviceDescriptors::Response& self); -void extract(::microstrain::Buffer& serializer, GetDeviceDescriptors::Response& self); +void insert(::microstrain::Serializer& serializer, const GetDeviceDescriptors::Response& self); +void extract(::microstrain::Serializer& serializer, GetDeviceDescriptors::Response& self); TypedResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); @@ -439,11 +439,11 @@ struct BuiltInTest } }; }; -void insert(::microstrain::Buffer& serializer, const BuiltInTest& self); -void extract(::microstrain::Buffer& serializer, BuiltInTest& self); +void insert(::microstrain::Serializer& serializer, const BuiltInTest& self); +void extract(::microstrain::Serializer& serializer, BuiltInTest& self); -void insert(::microstrain::Buffer& serializer, const BuiltInTest::Response& self); -void extract(::microstrain::Buffer& serializer, BuiltInTest::Response& self); +void insert(::microstrain::Serializer& serializer, const BuiltInTest::Response& self); +void extract(::microstrain::Serializer& serializer, BuiltInTest::Response& self); TypedResult builtInTest(C::mip_interface& device, uint32_t* resultOut); @@ -480,8 +480,8 @@ struct Resume } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const Resume& self); -void extract(::microstrain::Buffer& serializer, Resume& self); +void insert(::microstrain::Serializer& serializer, const Resume& self); +void extract(::microstrain::Serializer& serializer, Resume& self); TypedResult resume(C::mip_interface& device); @@ -538,11 +538,11 @@ struct GetExtendedDescriptors } }; }; -void insert(::microstrain::Buffer& serializer, const GetExtendedDescriptors& self); -void extract(::microstrain::Buffer& serializer, GetExtendedDescriptors& self); +void insert(::microstrain::Serializer& serializer, const GetExtendedDescriptors& self); +void extract(::microstrain::Serializer& serializer, GetExtendedDescriptors& self); -void insert(::microstrain::Buffer& serializer, const GetExtendedDescriptors::Response& self); -void extract(::microstrain::Buffer& serializer, GetExtendedDescriptors::Response& self); +void insert(::microstrain::Serializer& serializer, const GetExtendedDescriptors::Response& self); +void extract(::microstrain::Serializer& serializer, GetExtendedDescriptors::Response& self); TypedResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); @@ -597,11 +597,11 @@ struct ContinuousBit } }; }; -void insert(::microstrain::Buffer& serializer, const ContinuousBit& self); -void extract(::microstrain::Buffer& serializer, ContinuousBit& self); +void insert(::microstrain::Serializer& serializer, const ContinuousBit& self); +void extract(::microstrain::Serializer& serializer, ContinuousBit& self); -void insert(::microstrain::Buffer& serializer, const ContinuousBit::Response& self); -void extract(::microstrain::Buffer& serializer, ContinuousBit::Response& self); +void insert(::microstrain::Serializer& serializer, const ContinuousBit::Response& self); +void extract(::microstrain::Serializer& serializer, ContinuousBit::Response& self); TypedResult continuousBit(C::mip_interface& device, uint8_t* resultOut); @@ -686,11 +686,11 @@ struct CommSpeed } }; }; -void insert(::microstrain::Buffer& serializer, const CommSpeed& self); -void extract(::microstrain::Buffer& serializer, CommSpeed& self); +void insert(::microstrain::Serializer& serializer, const CommSpeed& self); +void extract(::microstrain::Serializer& serializer, CommSpeed& self); -void insert(::microstrain::Buffer& serializer, const CommSpeed::Response& self); -void extract(::microstrain::Buffer& serializer, CommSpeed::Response& self); +void insert(::microstrain::Serializer& serializer, const CommSpeed::Response& self); +void extract(::microstrain::Serializer& serializer, CommSpeed::Response& self); TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud); TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut); @@ -754,8 +754,8 @@ struct GpsTimeUpdate typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const GpsTimeUpdate& self); -void extract(::microstrain::Buffer& serializer, GpsTimeUpdate& self); +void insert(::microstrain::Serializer& serializer, const GpsTimeUpdate& self); +void extract(::microstrain::Serializer& serializer, GpsTimeUpdate& self); TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value); @@ -792,8 +792,8 @@ struct SoftReset } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const SoftReset& self); -void extract(::microstrain::Buffer& serializer, SoftReset& self); +void insert(::microstrain::Serializer& serializer, const SoftReset& self); +void extract(::microstrain::Serializer& serializer, SoftReset& self); TypedResult softReset(C::mip_interface& device); diff --git a/src/mip/definitions/commands_filter.cpp b/src/mip/definitions/commands_filter.cpp index 4ee016e8f..40ed6e902 100644 --- a/src/mip/definitions/commands_filter.cpp +++ b/src/mip/definitions/commands_filter.cpp @@ -1,7 +1,7 @@ #include "commands_filter.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -16,7 +16,7 @@ struct mip_interface; namespace commands_filter { -using ::microstrain::Buffer; +using ::microstrain::Serializer; using ::mip::insert; using ::mip::extract; using namespace ::mip::C; @@ -30,12 +30,12 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const Reset& self) +void insert(::microstrain::Serializer& serializer, const Reset& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, Reset& self) +void extract(::microstrain::Serializer& serializer, Reset& self) { (void)serializer; (void)self; @@ -45,7 +45,7 @@ TypedResult reset(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESET_FILTER, NULL, 0); } -void insert(::microstrain::Buffer& serializer, const SetInitialAttitude& self) +void insert(::microstrain::Serializer& serializer, const SetInitialAttitude& self) { insert(serializer, self.roll); @@ -54,7 +54,7 @@ void insert(::microstrain::Buffer& serializer, const SetInitialAttitude& self) insert(serializer, self.heading); } -void extract(::microstrain::Buffer& serializer, SetInitialAttitude& self) +void extract(::microstrain::Serializer& serializer, SetInitialAttitude& self) { extract(serializer, self.roll); @@ -66,8 +66,8 @@ void extract(::microstrain::Buffer& serializer, SetInitialAttitude& self) TypedResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, roll); @@ -79,7 +79,7 @@ TypedResult setInitialAttitude(C::mip_interface& device, flo return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_ATTITUDE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const EstimationControl& self) +void insert(::microstrain::Serializer& serializer, const EstimationControl& self) { insert(serializer, self.function); @@ -89,7 +89,7 @@ void insert(::microstrain::Buffer& serializer, const EstimationControl& self) } } -void extract(::microstrain::Buffer& serializer, EstimationControl& self) +void extract(::microstrain::Serializer& serializer, EstimationControl& self) { extract(serializer, self.function); @@ -100,12 +100,12 @@ void extract(::microstrain::Buffer& serializer, EstimationControl& self) } } -void insert(::microstrain::Buffer& serializer, const EstimationControl::Response& self) +void insert(::microstrain::Serializer& serializer, const EstimationControl::Response& self) { insert(serializer, self.enable); } -void extract(::microstrain::Buffer& serializer, EstimationControl::Response& self) +void extract(::microstrain::Serializer& serializer, EstimationControl::Response& self) { extract(serializer, self.enable); @@ -113,8 +113,8 @@ void extract(::microstrain::Buffer& serializer, EstimationControl::Response& sel TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -125,8 +125,8 @@ TypedResult writeEstimationControl(C::mip_interface& device, } TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -136,7 +136,7 @@ TypedResult readEstimationControl(C::mip_interface& device, E if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -148,8 +148,8 @@ TypedResult readEstimationControl(C::mip_interface& device, E } TypedResult saveEstimationControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -158,8 +158,8 @@ TypedResult saveEstimationControl(C::mip_interface& device) } TypedResult loadEstimationControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -168,15 +168,15 @@ TypedResult loadEstimationControl(C::mip_interface& device) } TypedResult defaultEstimationControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ExternalGnssUpdate& self) +void insert(::microstrain::Serializer& serializer, const ExternalGnssUpdate& self) { insert(serializer, self.gps_time); @@ -198,7 +198,7 @@ void insert(::microstrain::Buffer& serializer, const ExternalGnssUpdate& self) insert(serializer, self.vel_uncertainty[i]); } -void extract(::microstrain::Buffer& serializer, ExternalGnssUpdate& self) +void extract(::microstrain::Serializer& serializer, ExternalGnssUpdate& self) { extract(serializer, self.gps_time); @@ -223,8 +223,8 @@ void extract(::microstrain::Buffer& serializer, ExternalGnssUpdate& self) TypedResult externalGnssUpdate(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, double latitude, double longitude, double height, const float* velocity, const float* posUncertainty, const float* velUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, gpsTime); @@ -252,7 +252,7 @@ TypedResult externalGnssUpdate(C::mip_interface& device, dou return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdate& self) +void insert(::microstrain::Serializer& serializer, const ExternalHeadingUpdate& self) { insert(serializer, self.heading); @@ -261,7 +261,7 @@ void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdate& self insert(serializer, self.type); } -void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdate& self) +void extract(::microstrain::Serializer& serializer, ExternalHeadingUpdate& self) { extract(serializer, self.heading); @@ -273,8 +273,8 @@ void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdate& self) TypedResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, heading); @@ -286,7 +286,7 @@ TypedResult externalHeadingUpdate(C::mip_interface& devic return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdateWithTime& self) +void insert(::microstrain::Serializer& serializer, const ExternalHeadingUpdateWithTime& self) { insert(serializer, self.gps_time); @@ -299,7 +299,7 @@ void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdateWithTi insert(serializer, self.type); } -void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdateWithTime& self) +void extract(::microstrain::Serializer& serializer, ExternalHeadingUpdateWithTime& self) { extract(serializer, self.gps_time); @@ -315,8 +315,8 @@ void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdateWithTime& s TypedResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, gpsTime); @@ -332,7 +332,7 @@ TypedResult externalHeadingUpdateWithTime(C::mip_ return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const TareOrientation& self) +void insert(::microstrain::Serializer& serializer, const TareOrientation& self) { insert(serializer, self.function); @@ -342,7 +342,7 @@ void insert(::microstrain::Buffer& serializer, const TareOrientation& self) } } -void extract(::microstrain::Buffer& serializer, TareOrientation& self) +void extract(::microstrain::Serializer& serializer, TareOrientation& self) { extract(serializer, self.function); @@ -353,12 +353,12 @@ void extract(::microstrain::Buffer& serializer, TareOrientation& self) } } -void insert(::microstrain::Buffer& serializer, const TareOrientation::Response& self) +void insert(::microstrain::Serializer& serializer, const TareOrientation::Response& self) { insert(serializer, self.axes); } -void extract(::microstrain::Buffer& serializer, TareOrientation::Response& self) +void extract(::microstrain::Serializer& serializer, TareOrientation::Response& self) { extract(serializer, self.axes); @@ -366,8 +366,8 @@ void extract(::microstrain::Buffer& serializer, TareOrientation::Response& self) TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, axes); @@ -378,8 +378,8 @@ TypedResult writeTareOrientation(C::mip_interface& device, Tare } TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -389,7 +389,7 @@ TypedResult readTareOrientation(C::mip_interface& device, TareO if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(axesOut); extract(deserializer, *axesOut); @@ -401,8 +401,8 @@ TypedResult readTareOrientation(C::mip_interface& device, TareO } TypedResult saveTareOrientation(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -411,8 +411,8 @@ TypedResult saveTareOrientation(C::mip_interface& device) } TypedResult loadTareOrientation(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -421,15 +421,15 @@ TypedResult loadTareOrientation(C::mip_interface& device) } TypedResult defaultTareOrientation(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const VehicleDynamicsMode& self) +void insert(::microstrain::Serializer& serializer, const VehicleDynamicsMode& self) { insert(serializer, self.function); @@ -439,7 +439,7 @@ void insert(::microstrain::Buffer& serializer, const VehicleDynamicsMode& self) } } -void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode& self) +void extract(::microstrain::Serializer& serializer, VehicleDynamicsMode& self) { extract(serializer, self.function); @@ -450,12 +450,12 @@ void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode& self) } } -void insert(::microstrain::Buffer& serializer, const VehicleDynamicsMode::Response& self) +void insert(::microstrain::Serializer& serializer, const VehicleDynamicsMode::Response& self) { insert(serializer, self.mode); } -void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode::Response& self) +void extract(::microstrain::Serializer& serializer, VehicleDynamicsMode::Response& self) { extract(serializer, self.mode); @@ -463,8 +463,8 @@ void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode::Response& s TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); @@ -475,8 +475,8 @@ TypedResult writeVehicleDynamicsMode(C::mip_interface& devi } TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -486,7 +486,7 @@ TypedResult readVehicleDynamicsMode(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -498,8 +498,8 @@ TypedResult readVehicleDynamicsMode(C::mip_interface& devic } TypedResult saveVehicleDynamicsMode(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -508,8 +508,8 @@ TypedResult saveVehicleDynamicsMode(C::mip_interface& devic } TypedResult loadVehicleDynamicsMode(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -518,15 +518,15 @@ TypedResult loadVehicleDynamicsMode(C::mip_interface& devic } TypedResult defaultVehicleDynamicsMode(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEuler& self) +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationEuler& self) { insert(serializer, self.function); @@ -540,7 +540,7 @@ void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEule } } -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler& self) +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationEuler& self) { extract(serializer, self.function); @@ -555,7 +555,7 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler& se } } -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEuler::Response& self) +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationEuler::Response& self) { insert(serializer, self.roll); @@ -564,7 +564,7 @@ void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEule insert(serializer, self.yaw); } -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler::Response& self) +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationEuler::Response& self) { extract(serializer, self.roll); @@ -576,8 +576,8 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler::Re TypedResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, roll); @@ -592,8 +592,8 @@ TypedResult writeSensorToVehicleRotationEuler(C::m } TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -603,7 +603,7 @@ TypedResult readSensorToVehicleRotationEuler(C::mi if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(rollOut); extract(deserializer, *rollOut); @@ -621,8 +621,8 @@ TypedResult readSensorToVehicleRotationEuler(C::mi } TypedResult saveSensorToVehicleRotationEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -631,8 +631,8 @@ TypedResult saveSensorToVehicleRotationEuler(C::mi } TypedResult loadSensorToVehicleRotationEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -641,15 +641,15 @@ TypedResult loadSensorToVehicleRotationEuler(C::mi } TypedResult defaultSensorToVehicleRotationEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationDcm& self) +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationDcm& self) { insert(serializer, self.function); @@ -660,7 +660,7 @@ void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationDcm& } } -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm& self) +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationDcm& self) { extract(serializer, self.function); @@ -672,13 +672,13 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm& self } } -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationDcm::Response& self) +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationDcm::Response& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.dcm[i]); } -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm::Response& self) +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationDcm::Response& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.dcm[i]); @@ -687,8 +687,8 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm::Resp TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(dcm || (9 == 0)); @@ -701,8 +701,8 @@ TypedResult writeSensorToVehicleRotationDcm(C::mip_i } TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -712,7 +712,7 @@ TypedResult readSensorToVehicleRotationDcm(C::mip_in if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(dcmOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -725,8 +725,8 @@ TypedResult readSensorToVehicleRotationDcm(C::mip_in } TypedResult saveSensorToVehicleRotationDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -735,8 +735,8 @@ TypedResult saveSensorToVehicleRotationDcm(C::mip_in } TypedResult loadSensorToVehicleRotationDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -745,15 +745,15 @@ TypedResult loadSensorToVehicleRotationDcm(C::mip_in } TypedResult defaultSensorToVehicleRotationDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationQuaternion& self) +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationQuaternion& self) { insert(serializer, self.function); @@ -764,7 +764,7 @@ void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationQuat } } -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternion& self) +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationQuaternion& self) { extract(serializer, self.function); @@ -776,13 +776,13 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternio } } -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationQuaternion::Response& self) +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationQuaternion::Response& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.quat[i]); } -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternion::Response& self) +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationQuaternion::Response& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.quat[i]); @@ -791,8 +791,8 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternio TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(quat || (4 == 0)); @@ -805,8 +805,8 @@ TypedResult writeSensorToVehicleRotationQuate } TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -816,7 +816,7 @@ TypedResult readSensorToVehicleRotationQuater if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(quatOut || (4 == 0)); for(unsigned int i=0; i < 4; i++) @@ -829,8 +829,8 @@ TypedResult readSensorToVehicleRotationQuater } TypedResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -839,8 +839,8 @@ TypedResult saveSensorToVehicleRotationQuater } TypedResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -849,15 +849,15 @@ TypedResult loadSensorToVehicleRotationQuater } TypedResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SensorToVehicleOffset& self) +void insert(::microstrain::Serializer& serializer, const SensorToVehicleOffset& self) { insert(serializer, self.function); @@ -868,7 +868,7 @@ void insert(::microstrain::Buffer& serializer, const SensorToVehicleOffset& self } } -void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset& self) +void extract(::microstrain::Serializer& serializer, SensorToVehicleOffset& self) { extract(serializer, self.function); @@ -880,13 +880,13 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset& self) } } -void insert(::microstrain::Buffer& serializer, const SensorToVehicleOffset::Response& self) +void insert(::microstrain::Serializer& serializer, const SensorToVehicleOffset::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset[i]); } -void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset::Response& self) +void extract(::microstrain::Serializer& serializer, SensorToVehicleOffset::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset[i]); @@ -895,8 +895,8 @@ void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset::Response& TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (3 == 0)); @@ -909,8 +909,8 @@ TypedResult writeSensorToVehicleOffset(C::mip_interface& } TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -920,7 +920,7 @@ TypedResult readSensorToVehicleOffset(C::mip_interface& d if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(offsetOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -933,8 +933,8 @@ TypedResult readSensorToVehicleOffset(C::mip_interface& d } TypedResult saveSensorToVehicleOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -943,8 +943,8 @@ TypedResult saveSensorToVehicleOffset(C::mip_interface& d } TypedResult loadSensorToVehicleOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -953,15 +953,15 @@ TypedResult loadSensorToVehicleOffset(C::mip_interface& d } TypedResult defaultSensorToVehicleOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AntennaOffset& self) +void insert(::microstrain::Serializer& serializer, const AntennaOffset& self) { insert(serializer, self.function); @@ -972,7 +972,7 @@ void insert(::microstrain::Buffer& serializer, const AntennaOffset& self) } } -void extract(::microstrain::Buffer& serializer, AntennaOffset& self) +void extract(::microstrain::Serializer& serializer, AntennaOffset& self) { extract(serializer, self.function); @@ -984,13 +984,13 @@ void extract(::microstrain::Buffer& serializer, AntennaOffset& self) } } -void insert(::microstrain::Buffer& serializer, const AntennaOffset::Response& self) +void insert(::microstrain::Serializer& serializer, const AntennaOffset::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset[i]); } -void extract(::microstrain::Buffer& serializer, AntennaOffset::Response& self) +void extract(::microstrain::Serializer& serializer, AntennaOffset::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset[i]); @@ -999,8 +999,8 @@ void extract(::microstrain::Buffer& serializer, AntennaOffset::Response& self) TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(offset || (3 == 0)); @@ -1013,8 +1013,8 @@ TypedResult writeAntennaOffset(C::mip_interface& device, const fl } TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1024,7 +1024,7 @@ TypedResult readAntennaOffset(C::mip_interface& device, float* of if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(offsetOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1037,8 +1037,8 @@ TypedResult readAntennaOffset(C::mip_interface& device, float* of } TypedResult saveAntennaOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1047,8 +1047,8 @@ TypedResult saveAntennaOffset(C::mip_interface& device) } TypedResult loadAntennaOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1057,15 +1057,15 @@ TypedResult loadAntennaOffset(C::mip_interface& device) } TypedResult defaultAntennaOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GnssSource& self) +void insert(::microstrain::Serializer& serializer, const GnssSource& self) { insert(serializer, self.function); @@ -1075,7 +1075,7 @@ void insert(::microstrain::Buffer& serializer, const GnssSource& self) } } -void extract(::microstrain::Buffer& serializer, GnssSource& self) +void extract(::microstrain::Serializer& serializer, GnssSource& self) { extract(serializer, self.function); @@ -1086,12 +1086,12 @@ void extract(::microstrain::Buffer& serializer, GnssSource& self) } } -void insert(::microstrain::Buffer& serializer, const GnssSource::Response& self) +void insert(::microstrain::Serializer& serializer, const GnssSource::Response& self) { insert(serializer, self.source); } -void extract(::microstrain::Buffer& serializer, GnssSource::Response& self) +void extract(::microstrain::Serializer& serializer, GnssSource::Response& self) { extract(serializer, self.source); @@ -1099,8 +1099,8 @@ void extract(::microstrain::Buffer& serializer, GnssSource::Response& self) TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -1111,8 +1111,8 @@ TypedResult writeGnssSource(C::mip_interface& device, GnssSource::So } TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1122,7 +1122,7 @@ TypedResult readGnssSource(C::mip_interface& device, GnssSource::Sou if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -1134,8 +1134,8 @@ TypedResult readGnssSource(C::mip_interface& device, GnssSource::Sou } TypedResult saveGnssSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1144,8 +1144,8 @@ TypedResult saveGnssSource(C::mip_interface& device) } TypedResult loadGnssSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1154,15 +1154,15 @@ TypedResult loadGnssSource(C::mip_interface& device) } TypedResult defaultGnssSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const HeadingSource& self) +void insert(::microstrain::Serializer& serializer, const HeadingSource& self) { insert(serializer, self.function); @@ -1172,7 +1172,7 @@ void insert(::microstrain::Buffer& serializer, const HeadingSource& self) } } -void extract(::microstrain::Buffer& serializer, HeadingSource& self) +void extract(::microstrain::Serializer& serializer, HeadingSource& self) { extract(serializer, self.function); @@ -1183,12 +1183,12 @@ void extract(::microstrain::Buffer& serializer, HeadingSource& self) } } -void insert(::microstrain::Buffer& serializer, const HeadingSource::Response& self) +void insert(::microstrain::Serializer& serializer, const HeadingSource::Response& self) { insert(serializer, self.source); } -void extract(::microstrain::Buffer& serializer, HeadingSource::Response& self) +void extract(::microstrain::Serializer& serializer, HeadingSource::Response& self) { extract(serializer, self.source); @@ -1196,8 +1196,8 @@ void extract(::microstrain::Buffer& serializer, HeadingSource::Response& self) TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -1208,8 +1208,8 @@ TypedResult writeHeadingSource(C::mip_interface& device, HeadingS } TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1219,7 +1219,7 @@ TypedResult readHeadingSource(C::mip_interface& device, HeadingSo if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -1231,8 +1231,8 @@ TypedResult readHeadingSource(C::mip_interface& device, HeadingSo } TypedResult saveHeadingSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1241,8 +1241,8 @@ TypedResult saveHeadingSource(C::mip_interface& device) } TypedResult loadHeadingSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1251,15 +1251,15 @@ TypedResult loadHeadingSource(C::mip_interface& device) } TypedResult defaultHeadingSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AutoInitControl& self) +void insert(::microstrain::Serializer& serializer, const AutoInitControl& self) { insert(serializer, self.function); @@ -1269,7 +1269,7 @@ void insert(::microstrain::Buffer& serializer, const AutoInitControl& self) } } -void extract(::microstrain::Buffer& serializer, AutoInitControl& self) +void extract(::microstrain::Serializer& serializer, AutoInitControl& self) { extract(serializer, self.function); @@ -1280,12 +1280,12 @@ void extract(::microstrain::Buffer& serializer, AutoInitControl& self) } } -void insert(::microstrain::Buffer& serializer, const AutoInitControl::Response& self) +void insert(::microstrain::Serializer& serializer, const AutoInitControl::Response& self) { insert(serializer, self.enable); } -void extract(::microstrain::Buffer& serializer, AutoInitControl::Response& self) +void extract(::microstrain::Serializer& serializer, AutoInitControl::Response& self) { extract(serializer, self.enable); @@ -1293,8 +1293,8 @@ void extract(::microstrain::Buffer& serializer, AutoInitControl::Response& self) TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -1305,8 +1305,8 @@ TypedResult writeAutoInitControl(C::mip_interface& device, uint } TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1316,7 +1316,7 @@ TypedResult readAutoInitControl(C::mip_interface& device, uint8 if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -1328,8 +1328,8 @@ TypedResult readAutoInitControl(C::mip_interface& device, uint8 } TypedResult saveAutoInitControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1338,8 +1338,8 @@ TypedResult saveAutoInitControl(C::mip_interface& device) } TypedResult loadAutoInitControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1348,15 +1348,15 @@ TypedResult loadAutoInitControl(C::mip_interface& device) } TypedResult defaultAutoInitControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AccelNoise& self) +void insert(::microstrain::Serializer& serializer, const AccelNoise& self) { insert(serializer, self.function); @@ -1367,7 +1367,7 @@ void insert(::microstrain::Buffer& serializer, const AccelNoise& self) } } -void extract(::microstrain::Buffer& serializer, AccelNoise& self) +void extract(::microstrain::Serializer& serializer, AccelNoise& self) { extract(serializer, self.function); @@ -1379,13 +1379,13 @@ void extract(::microstrain::Buffer& serializer, AccelNoise& self) } } -void insert(::microstrain::Buffer& serializer, const AccelNoise::Response& self) +void insert(::microstrain::Serializer& serializer, const AccelNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(::microstrain::Buffer& serializer, AccelNoise::Response& self) +void extract(::microstrain::Serializer& serializer, AccelNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -1394,8 +1394,8 @@ void extract(::microstrain::Buffer& serializer, AccelNoise::Response& self) TypedResult writeAccelNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -1408,8 +1408,8 @@ TypedResult writeAccelNoise(C::mip_interface& device, const float* n } TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1419,7 +1419,7 @@ TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1432,8 +1432,8 @@ TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut } TypedResult saveAccelNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1442,8 +1442,8 @@ TypedResult saveAccelNoise(C::mip_interface& device) } TypedResult loadAccelNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1452,15 +1452,15 @@ TypedResult loadAccelNoise(C::mip_interface& device) } TypedResult defaultAccelNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GyroNoise& self) +void insert(::microstrain::Serializer& serializer, const GyroNoise& self) { insert(serializer, self.function); @@ -1471,7 +1471,7 @@ void insert(::microstrain::Buffer& serializer, const GyroNoise& self) } } -void extract(::microstrain::Buffer& serializer, GyroNoise& self) +void extract(::microstrain::Serializer& serializer, GyroNoise& self) { extract(serializer, self.function); @@ -1483,13 +1483,13 @@ void extract(::microstrain::Buffer& serializer, GyroNoise& self) } } -void insert(::microstrain::Buffer& serializer, const GyroNoise::Response& self) +void insert(::microstrain::Serializer& serializer, const GyroNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(::microstrain::Buffer& serializer, GyroNoise::Response& self) +void extract(::microstrain::Serializer& serializer, GyroNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -1498,8 +1498,8 @@ void extract(::microstrain::Buffer& serializer, GyroNoise::Response& self) TypedResult writeGyroNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -1512,8 +1512,8 @@ TypedResult writeGyroNoise(C::mip_interface& device, const float* noi } TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1523,7 +1523,7 @@ TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1536,8 +1536,8 @@ TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) } TypedResult saveGyroNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1546,8 +1546,8 @@ TypedResult saveGyroNoise(C::mip_interface& device) } TypedResult loadGyroNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1556,15 +1556,15 @@ TypedResult loadGyroNoise(C::mip_interface& device) } TypedResult defaultGyroNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AccelBiasModel& self) +void insert(::microstrain::Serializer& serializer, const AccelBiasModel& self) { insert(serializer, self.function); @@ -1578,7 +1578,7 @@ void insert(::microstrain::Buffer& serializer, const AccelBiasModel& self) } } -void extract(::microstrain::Buffer& serializer, AccelBiasModel& self) +void extract(::microstrain::Serializer& serializer, AccelBiasModel& self) { extract(serializer, self.function); @@ -1593,7 +1593,7 @@ void extract(::microstrain::Buffer& serializer, AccelBiasModel& self) } } -void insert(::microstrain::Buffer& serializer, const AccelBiasModel::Response& self) +void insert(::microstrain::Serializer& serializer, const AccelBiasModel::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.beta[i]); @@ -1602,7 +1602,7 @@ void insert(::microstrain::Buffer& serializer, const AccelBiasModel::Response& s insert(serializer, self.noise[i]); } -void extract(::microstrain::Buffer& serializer, AccelBiasModel::Response& self) +void extract(::microstrain::Serializer& serializer, AccelBiasModel::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.beta[i]); @@ -1614,8 +1614,8 @@ void extract(::microstrain::Buffer& serializer, AccelBiasModel::Response& self) TypedResult writeAccelBiasModel(C::mip_interface& device, const float* beta, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(beta || (3 == 0)); @@ -1632,8 +1632,8 @@ TypedResult writeAccelBiasModel(C::mip_interface& device, const } TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1643,7 +1643,7 @@ TypedResult readAccelBiasModel(C::mip_interface& device, float* if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(betaOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1660,8 +1660,8 @@ TypedResult readAccelBiasModel(C::mip_interface& device, float* } TypedResult saveAccelBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1670,8 +1670,8 @@ TypedResult saveAccelBiasModel(C::mip_interface& device) } TypedResult loadAccelBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1680,15 +1680,15 @@ TypedResult loadAccelBiasModel(C::mip_interface& device) } TypedResult defaultAccelBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GyroBiasModel& self) +void insert(::microstrain::Serializer& serializer, const GyroBiasModel& self) { insert(serializer, self.function); @@ -1702,7 +1702,7 @@ void insert(::microstrain::Buffer& serializer, const GyroBiasModel& self) } } -void extract(::microstrain::Buffer& serializer, GyroBiasModel& self) +void extract(::microstrain::Serializer& serializer, GyroBiasModel& self) { extract(serializer, self.function); @@ -1717,7 +1717,7 @@ void extract(::microstrain::Buffer& serializer, GyroBiasModel& self) } } -void insert(::microstrain::Buffer& serializer, const GyroBiasModel::Response& self) +void insert(::microstrain::Serializer& serializer, const GyroBiasModel::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.beta[i]); @@ -1726,7 +1726,7 @@ void insert(::microstrain::Buffer& serializer, const GyroBiasModel::Response& se insert(serializer, self.noise[i]); } -void extract(::microstrain::Buffer& serializer, GyroBiasModel::Response& self) +void extract(::microstrain::Serializer& serializer, GyroBiasModel::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.beta[i]); @@ -1738,8 +1738,8 @@ void extract(::microstrain::Buffer& serializer, GyroBiasModel::Response& self) TypedResult writeGyroBiasModel(C::mip_interface& device, const float* beta, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(beta || (3 == 0)); @@ -1756,8 +1756,8 @@ TypedResult writeGyroBiasModel(C::mip_interface& device, const fl } TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1767,7 +1767,7 @@ TypedResult readGyroBiasModel(C::mip_interface& device, float* be if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(betaOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -1784,8 +1784,8 @@ TypedResult readGyroBiasModel(C::mip_interface& device, float* be } TypedResult saveGyroBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1794,8 +1794,8 @@ TypedResult saveGyroBiasModel(C::mip_interface& device) } TypedResult loadGyroBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1804,15 +1804,15 @@ TypedResult loadGyroBiasModel(C::mip_interface& device) } TypedResult defaultGyroBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AltitudeAiding& self) +void insert(::microstrain::Serializer& serializer, const AltitudeAiding& self) { insert(serializer, self.function); @@ -1822,7 +1822,7 @@ void insert(::microstrain::Buffer& serializer, const AltitudeAiding& self) } } -void extract(::microstrain::Buffer& serializer, AltitudeAiding& self) +void extract(::microstrain::Serializer& serializer, AltitudeAiding& self) { extract(serializer, self.function); @@ -1833,12 +1833,12 @@ void extract(::microstrain::Buffer& serializer, AltitudeAiding& self) } } -void insert(::microstrain::Buffer& serializer, const AltitudeAiding::Response& self) +void insert(::microstrain::Serializer& serializer, const AltitudeAiding::Response& self) { insert(serializer, self.selector); } -void extract(::microstrain::Buffer& serializer, AltitudeAiding::Response& self) +void extract(::microstrain::Serializer& serializer, AltitudeAiding::Response& self) { extract(serializer, self.selector); @@ -1846,8 +1846,8 @@ void extract(::microstrain::Buffer& serializer, AltitudeAiding::Response& self) TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, selector); @@ -1858,8 +1858,8 @@ TypedResult writeAltitudeAiding(C::mip_interface& device, Altitu } TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1869,7 +1869,7 @@ TypedResult readAltitudeAiding(C::mip_interface& device, Altitud if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(selectorOut); extract(deserializer, *selectorOut); @@ -1881,8 +1881,8 @@ TypedResult readAltitudeAiding(C::mip_interface& device, Altitud } TypedResult saveAltitudeAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1891,8 +1891,8 @@ TypedResult saveAltitudeAiding(C::mip_interface& device) } TypedResult loadAltitudeAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1901,15 +1901,15 @@ TypedResult loadAltitudeAiding(C::mip_interface& device) } TypedResult defaultAltitudeAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const PitchRollAiding& self) +void insert(::microstrain::Serializer& serializer, const PitchRollAiding& self) { insert(serializer, self.function); @@ -1919,7 +1919,7 @@ void insert(::microstrain::Buffer& serializer, const PitchRollAiding& self) } } -void extract(::microstrain::Buffer& serializer, PitchRollAiding& self) +void extract(::microstrain::Serializer& serializer, PitchRollAiding& self) { extract(serializer, self.function); @@ -1930,12 +1930,12 @@ void extract(::microstrain::Buffer& serializer, PitchRollAiding& self) } } -void insert(::microstrain::Buffer& serializer, const PitchRollAiding::Response& self) +void insert(::microstrain::Serializer& serializer, const PitchRollAiding::Response& self) { insert(serializer, self.source); } -void extract(::microstrain::Buffer& serializer, PitchRollAiding::Response& self) +void extract(::microstrain::Serializer& serializer, PitchRollAiding::Response& self) { extract(serializer, self.source); @@ -1943,8 +1943,8 @@ void extract(::microstrain::Buffer& serializer, PitchRollAiding::Response& self) TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -1955,8 +1955,8 @@ TypedResult writePitchRollAiding(C::mip_interface& device, Pitc } TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -1966,7 +1966,7 @@ TypedResult readPitchRollAiding(C::mip_interface& device, Pitch if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -1978,8 +1978,8 @@ TypedResult readPitchRollAiding(C::mip_interface& device, Pitch } TypedResult savePitchRollAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -1988,8 +1988,8 @@ TypedResult savePitchRollAiding(C::mip_interface& device) } TypedResult loadPitchRollAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -1998,15 +1998,15 @@ TypedResult loadPitchRollAiding(C::mip_interface& device) } TypedResult defaultPitchRollAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AutoZupt& self) +void insert(::microstrain::Serializer& serializer, const AutoZupt& self) { insert(serializer, self.function); @@ -2018,7 +2018,7 @@ void insert(::microstrain::Buffer& serializer, const AutoZupt& self) } } -void extract(::microstrain::Buffer& serializer, AutoZupt& self) +void extract(::microstrain::Serializer& serializer, AutoZupt& self) { extract(serializer, self.function); @@ -2031,14 +2031,14 @@ void extract(::microstrain::Buffer& serializer, AutoZupt& self) } } -void insert(::microstrain::Buffer& serializer, const AutoZupt::Response& self) +void insert(::microstrain::Serializer& serializer, const AutoZupt::Response& self) { insert(serializer, self.enable); insert(serializer, self.threshold); } -void extract(::microstrain::Buffer& serializer, AutoZupt::Response& self) +void extract(::microstrain::Serializer& serializer, AutoZupt::Response& self) { extract(serializer, self.enable); @@ -2048,8 +2048,8 @@ void extract(::microstrain::Buffer& serializer, AutoZupt::Response& self) TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -2062,8 +2062,8 @@ TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, fl } TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2073,7 +2073,7 @@ TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -2088,8 +2088,8 @@ TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, } TypedResult saveAutoZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2098,8 +2098,8 @@ TypedResult saveAutoZupt(C::mip_interface& device) } TypedResult loadAutoZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2108,15 +2108,15 @@ TypedResult loadAutoZupt(C::mip_interface& device) } TypedResult defaultAutoZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AutoAngularZupt& self) +void insert(::microstrain::Serializer& serializer, const AutoAngularZupt& self) { insert(serializer, self.function); @@ -2128,7 +2128,7 @@ void insert(::microstrain::Buffer& serializer, const AutoAngularZupt& self) } } -void extract(::microstrain::Buffer& serializer, AutoAngularZupt& self) +void extract(::microstrain::Serializer& serializer, AutoAngularZupt& self) { extract(serializer, self.function); @@ -2141,14 +2141,14 @@ void extract(::microstrain::Buffer& serializer, AutoAngularZupt& self) } } -void insert(::microstrain::Buffer& serializer, const AutoAngularZupt::Response& self) +void insert(::microstrain::Serializer& serializer, const AutoAngularZupt::Response& self) { insert(serializer, self.enable); insert(serializer, self.threshold); } -void extract(::microstrain::Buffer& serializer, AutoAngularZupt::Response& self) +void extract(::microstrain::Serializer& serializer, AutoAngularZupt::Response& self) { extract(serializer, self.enable); @@ -2158,8 +2158,8 @@ void extract(::microstrain::Buffer& serializer, AutoAngularZupt::Response& self) TypedResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -2172,8 +2172,8 @@ TypedResult writeAutoAngularZupt(C::mip_interface& device, uint } TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2183,7 +2183,7 @@ TypedResult readAutoAngularZupt(C::mip_interface& device, uint8 if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -2198,8 +2198,8 @@ TypedResult readAutoAngularZupt(C::mip_interface& device, uint8 } TypedResult saveAutoAngularZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2208,8 +2208,8 @@ TypedResult saveAutoAngularZupt(C::mip_interface& device) } TypedResult loadAutoAngularZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2218,20 +2218,20 @@ TypedResult loadAutoAngularZupt(C::mip_interface& device) } TypedResult defaultAutoAngularZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const CommandedZupt& self) +void insert(::microstrain::Serializer& serializer, const CommandedZupt& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, CommandedZupt& self) +void extract(::microstrain::Serializer& serializer, CommandedZupt& self) { (void)serializer; (void)self; @@ -2241,12 +2241,12 @@ TypedResult commandedZupt(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMMANDED_ZUPT, NULL, 0); } -void insert(::microstrain::Buffer& serializer, const CommandedAngularZupt& self) +void insert(::microstrain::Serializer& serializer, const CommandedAngularZupt& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, CommandedAngularZupt& self) +void extract(::microstrain::Serializer& serializer, CommandedAngularZupt& self) { (void)serializer; (void)self; @@ -2256,12 +2256,12 @@ TypedResult commandedAngularZupt(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMMANDED_ANGULAR_ZUPT, NULL, 0); } -void insert(::microstrain::Buffer& serializer, const MagCaptureAutoCal& self) +void insert(::microstrain::Serializer& serializer, const MagCaptureAutoCal& self) { insert(serializer, self.function); } -void extract(::microstrain::Buffer& serializer, MagCaptureAutoCal& self) +void extract(::microstrain::Serializer& serializer, MagCaptureAutoCal& self) { extract(serializer, self.function); @@ -2269,8 +2269,8 @@ void extract(::microstrain::Buffer& serializer, MagCaptureAutoCal& self) TypedResult writeMagCaptureAutoCal(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(serializer.isOk()); @@ -2279,15 +2279,15 @@ TypedResult writeMagCaptureAutoCal(C::mip_interface& device) } TypedResult saveMagCaptureAutoCal(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GravityNoise& self) +void insert(::microstrain::Serializer& serializer, const GravityNoise& self) { insert(serializer, self.function); @@ -2298,7 +2298,7 @@ void insert(::microstrain::Buffer& serializer, const GravityNoise& self) } } -void extract(::microstrain::Buffer& serializer, GravityNoise& self) +void extract(::microstrain::Serializer& serializer, GravityNoise& self) { extract(serializer, self.function); @@ -2310,13 +2310,13 @@ void extract(::microstrain::Buffer& serializer, GravityNoise& self) } } -void insert(::microstrain::Buffer& serializer, const GravityNoise::Response& self) +void insert(::microstrain::Serializer& serializer, const GravityNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(::microstrain::Buffer& serializer, GravityNoise::Response& self) +void extract(::microstrain::Serializer& serializer, GravityNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -2325,8 +2325,8 @@ void extract(::microstrain::Buffer& serializer, GravityNoise::Response& self) TypedResult writeGravityNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -2339,8 +2339,8 @@ TypedResult writeGravityNoise(C::mip_interface& device, const floa } TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2350,7 +2350,7 @@ TypedResult readGravityNoise(C::mip_interface& device, float* nois if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2363,8 +2363,8 @@ TypedResult readGravityNoise(C::mip_interface& device, float* nois } TypedResult saveGravityNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2373,8 +2373,8 @@ TypedResult saveGravityNoise(C::mip_interface& device) } TypedResult loadGravityNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2383,15 +2383,15 @@ TypedResult loadGravityNoise(C::mip_interface& device) } TypedResult defaultGravityNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const PressureAltitudeNoise& self) +void insert(::microstrain::Serializer& serializer, const PressureAltitudeNoise& self) { insert(serializer, self.function); @@ -2401,7 +2401,7 @@ void insert(::microstrain::Buffer& serializer, const PressureAltitudeNoise& self } } -void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise& self) +void extract(::microstrain::Serializer& serializer, PressureAltitudeNoise& self) { extract(serializer, self.function); @@ -2412,12 +2412,12 @@ void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise& self) } } -void insert(::microstrain::Buffer& serializer, const PressureAltitudeNoise::Response& self) +void insert(::microstrain::Serializer& serializer, const PressureAltitudeNoise::Response& self) { insert(serializer, self.noise); } -void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise::Response& self) +void extract(::microstrain::Serializer& serializer, PressureAltitudeNoise::Response& self) { extract(serializer, self.noise); @@ -2425,8 +2425,8 @@ void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise::Response& TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, noise); @@ -2437,8 +2437,8 @@ TypedResult writePressureAltitudeNoise(C::mip_interface& } TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2448,7 +2448,7 @@ TypedResult readPressureAltitudeNoise(C::mip_interface& d if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(noiseOut); extract(deserializer, *noiseOut); @@ -2460,8 +2460,8 @@ TypedResult readPressureAltitudeNoise(C::mip_interface& d } TypedResult savePressureAltitudeNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2470,8 +2470,8 @@ TypedResult savePressureAltitudeNoise(C::mip_interface& d } TypedResult loadPressureAltitudeNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2480,15 +2480,15 @@ TypedResult loadPressureAltitudeNoise(C::mip_interface& d } TypedResult defaultPressureAltitudeNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const HardIronOffsetNoise& self) +void insert(::microstrain::Serializer& serializer, const HardIronOffsetNoise& self) { insert(serializer, self.function); @@ -2499,7 +2499,7 @@ void insert(::microstrain::Buffer& serializer, const HardIronOffsetNoise& self) } } -void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise& self) +void extract(::microstrain::Serializer& serializer, HardIronOffsetNoise& self) { extract(serializer, self.function); @@ -2511,13 +2511,13 @@ void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise& self) } } -void insert(::microstrain::Buffer& serializer, const HardIronOffsetNoise::Response& self) +void insert(::microstrain::Serializer& serializer, const HardIronOffsetNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise::Response& self) +void extract(::microstrain::Serializer& serializer, HardIronOffsetNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -2526,8 +2526,8 @@ void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise::Response& s TypedResult writeHardIronOffsetNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -2540,8 +2540,8 @@ TypedResult writeHardIronOffsetNoise(C::mip_interface& devi } TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2551,7 +2551,7 @@ TypedResult readHardIronOffsetNoise(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2564,8 +2564,8 @@ TypedResult readHardIronOffsetNoise(C::mip_interface& devic } TypedResult saveHardIronOffsetNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2574,8 +2574,8 @@ TypedResult saveHardIronOffsetNoise(C::mip_interface& devic } TypedResult loadHardIronOffsetNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2584,15 +2584,15 @@ TypedResult loadHardIronOffsetNoise(C::mip_interface& devic } TypedResult defaultHardIronOffsetNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SoftIronMatrixNoise& self) +void insert(::microstrain::Serializer& serializer, const SoftIronMatrixNoise& self) { insert(serializer, self.function); @@ -2603,7 +2603,7 @@ void insert(::microstrain::Buffer& serializer, const SoftIronMatrixNoise& self) } } -void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise& self) +void extract(::microstrain::Serializer& serializer, SoftIronMatrixNoise& self) { extract(serializer, self.function); @@ -2615,13 +2615,13 @@ void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise& self) } } -void insert(::microstrain::Buffer& serializer, const SoftIronMatrixNoise::Response& self) +void insert(::microstrain::Serializer& serializer, const SoftIronMatrixNoise::Response& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.noise[i]); } -void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise::Response& self) +void extract(::microstrain::Serializer& serializer, SoftIronMatrixNoise::Response& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.noise[i]); @@ -2630,8 +2630,8 @@ void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise::Response& s TypedResult writeSoftIronMatrixNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (9 == 0)); @@ -2644,8 +2644,8 @@ TypedResult writeSoftIronMatrixNoise(C::mip_interface& devi } TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2655,7 +2655,7 @@ TypedResult readSoftIronMatrixNoise(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(noiseOut || (9 == 0)); for(unsigned int i=0; i < 9; i++) @@ -2668,8 +2668,8 @@ TypedResult readSoftIronMatrixNoise(C::mip_interface& devic } TypedResult saveSoftIronMatrixNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2678,8 +2678,8 @@ TypedResult saveSoftIronMatrixNoise(C::mip_interface& devic } TypedResult loadSoftIronMatrixNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2688,15 +2688,15 @@ TypedResult loadSoftIronMatrixNoise(C::mip_interface& devic } TypedResult defaultSoftIronMatrixNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const MagNoise& self) +void insert(::microstrain::Serializer& serializer, const MagNoise& self) { insert(serializer, self.function); @@ -2707,7 +2707,7 @@ void insert(::microstrain::Buffer& serializer, const MagNoise& self) } } -void extract(::microstrain::Buffer& serializer, MagNoise& self) +void extract(::microstrain::Serializer& serializer, MagNoise& self) { extract(serializer, self.function); @@ -2719,13 +2719,13 @@ void extract(::microstrain::Buffer& serializer, MagNoise& self) } } -void insert(::microstrain::Buffer& serializer, const MagNoise::Response& self) +void insert(::microstrain::Serializer& serializer, const MagNoise::Response& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.noise[i]); } -void extract(::microstrain::Buffer& serializer, MagNoise::Response& self) +void extract(::microstrain::Serializer& serializer, MagNoise::Response& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.noise[i]); @@ -2734,8 +2734,8 @@ void extract(::microstrain::Buffer& serializer, MagNoise::Response& self) TypedResult writeMagNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); assert(noise || (3 == 0)); @@ -2748,8 +2748,8 @@ TypedResult writeMagNoise(C::mip_interface& device, const float* noise } TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2759,7 +2759,7 @@ TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(noiseOut || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -2772,8 +2772,8 @@ TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) } TypedResult saveMagNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2782,8 +2782,8 @@ TypedResult saveMagNoise(C::mip_interface& device) } TypedResult loadMagNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2792,15 +2792,15 @@ TypedResult loadMagNoise(C::mip_interface& device) } TypedResult defaultMagNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const InclinationSource& self) +void insert(::microstrain::Serializer& serializer, const InclinationSource& self) { insert(serializer, self.function); @@ -2812,7 +2812,7 @@ void insert(::microstrain::Buffer& serializer, const InclinationSource& self) } } -void extract(::microstrain::Buffer& serializer, InclinationSource& self) +void extract(::microstrain::Serializer& serializer, InclinationSource& self) { extract(serializer, self.function); @@ -2825,14 +2825,14 @@ void extract(::microstrain::Buffer& serializer, InclinationSource& self) } } -void insert(::microstrain::Buffer& serializer, const InclinationSource::Response& self) +void insert(::microstrain::Serializer& serializer, const InclinationSource::Response& self) { insert(serializer, self.source); insert(serializer, self.inclination); } -void extract(::microstrain::Buffer& serializer, InclinationSource::Response& self) +void extract(::microstrain::Serializer& serializer, InclinationSource::Response& self) { extract(serializer, self.source); @@ -2842,8 +2842,8 @@ void extract(::microstrain::Buffer& serializer, InclinationSource::Response& sel TypedResult writeInclinationSource(C::mip_interface& device, FilterMagParamSource source, float inclination) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -2856,8 +2856,8 @@ TypedResult writeInclinationSource(C::mip_interface& device, } TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2867,7 +2867,7 @@ TypedResult readInclinationSource(C::mip_interface& device, F if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -2882,8 +2882,8 @@ TypedResult readInclinationSource(C::mip_interface& device, F } TypedResult saveInclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -2892,8 +2892,8 @@ TypedResult saveInclinationSource(C::mip_interface& device) } TypedResult loadInclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -2902,15 +2902,15 @@ TypedResult loadInclinationSource(C::mip_interface& device) } TypedResult defaultInclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const MagneticDeclinationSource& self) +void insert(::microstrain::Serializer& serializer, const MagneticDeclinationSource& self) { insert(serializer, self.function); @@ -2922,7 +2922,7 @@ void insert(::microstrain::Buffer& serializer, const MagneticDeclinationSource& } } -void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource& self) +void extract(::microstrain::Serializer& serializer, MagneticDeclinationSource& self) { extract(serializer, self.function); @@ -2935,14 +2935,14 @@ void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource& self) } } -void insert(::microstrain::Buffer& serializer, const MagneticDeclinationSource::Response& self) +void insert(::microstrain::Serializer& serializer, const MagneticDeclinationSource::Response& self) { insert(serializer, self.source); insert(serializer, self.declination); } -void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource::Response& self) +void extract(::microstrain::Serializer& serializer, MagneticDeclinationSource::Response& self) { extract(serializer, self.source); @@ -2952,8 +2952,8 @@ void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource::Respo TypedResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource source, float declination) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -2966,8 +2966,8 @@ TypedResult writeMagneticDeclinationSource(C::mip_int } TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -2977,7 +2977,7 @@ TypedResult readMagneticDeclinationSource(C::mip_inte if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -2992,8 +2992,8 @@ TypedResult readMagneticDeclinationSource(C::mip_inte } TypedResult saveMagneticDeclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3002,8 +3002,8 @@ TypedResult saveMagneticDeclinationSource(C::mip_inte } TypedResult loadMagneticDeclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3012,15 +3012,15 @@ TypedResult loadMagneticDeclinationSource(C::mip_inte } TypedResult defaultMagneticDeclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const MagFieldMagnitudeSource& self) +void insert(::microstrain::Serializer& serializer, const MagFieldMagnitudeSource& self) { insert(serializer, self.function); @@ -3032,7 +3032,7 @@ void insert(::microstrain::Buffer& serializer, const MagFieldMagnitudeSource& se } } -void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource& self) +void extract(::microstrain::Serializer& serializer, MagFieldMagnitudeSource& self) { extract(serializer, self.function); @@ -3045,14 +3045,14 @@ void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource& self) } } -void insert(::microstrain::Buffer& serializer, const MagFieldMagnitudeSource::Response& self) +void insert(::microstrain::Serializer& serializer, const MagFieldMagnitudeSource::Response& self) { insert(serializer, self.source); insert(serializer, self.magnitude); } -void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource::Response& self) +void extract(::microstrain::Serializer& serializer, MagFieldMagnitudeSource::Response& self) { extract(serializer, self.source); @@ -3062,8 +3062,8 @@ void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource::Respons TypedResult writeMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource source, float magnitude) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -3076,8 +3076,8 @@ TypedResult writeMagFieldMagnitudeSource(C::mip_interfa } TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3087,7 +3087,7 @@ TypedResult readMagFieldMagnitudeSource(C::mip_interfac if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -3102,8 +3102,8 @@ TypedResult readMagFieldMagnitudeSource(C::mip_interfac } TypedResult saveMagFieldMagnitudeSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3112,8 +3112,8 @@ TypedResult saveMagFieldMagnitudeSource(C::mip_interfac } TypedResult loadMagFieldMagnitudeSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3122,15 +3122,15 @@ TypedResult loadMagFieldMagnitudeSource(C::mip_interfac } TypedResult defaultMagFieldMagnitudeSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ReferencePosition& self) +void insert(::microstrain::Serializer& serializer, const ReferencePosition& self) { insert(serializer, self.function); @@ -3146,7 +3146,7 @@ void insert(::microstrain::Buffer& serializer, const ReferencePosition& self) } } -void extract(::microstrain::Buffer& serializer, ReferencePosition& self) +void extract(::microstrain::Serializer& serializer, ReferencePosition& self) { extract(serializer, self.function); @@ -3163,7 +3163,7 @@ void extract(::microstrain::Buffer& serializer, ReferencePosition& self) } } -void insert(::microstrain::Buffer& serializer, const ReferencePosition::Response& self) +void insert(::microstrain::Serializer& serializer, const ReferencePosition::Response& self) { insert(serializer, self.enable); @@ -3174,7 +3174,7 @@ void insert(::microstrain::Buffer& serializer, const ReferencePosition::Response insert(serializer, self.altitude); } -void extract(::microstrain::Buffer& serializer, ReferencePosition::Response& self) +void extract(::microstrain::Serializer& serializer, ReferencePosition::Response& self) { extract(serializer, self.enable); @@ -3188,8 +3188,8 @@ void extract(::microstrain::Buffer& serializer, ReferencePosition::Response& sel TypedResult writeReferencePosition(C::mip_interface& device, bool enable, double latitude, double longitude, double altitude) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -3206,8 +3206,8 @@ TypedResult writeReferencePosition(C::mip_interface& device, } TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3217,7 +3217,7 @@ TypedResult readReferencePosition(C::mip_interface& device, b if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -3238,8 +3238,8 @@ TypedResult readReferencePosition(C::mip_interface& device, b } TypedResult saveReferencePosition(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3248,8 +3248,8 @@ TypedResult saveReferencePosition(C::mip_interface& device) } TypedResult loadReferencePosition(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3258,15 +3258,15 @@ TypedResult loadReferencePosition(C::mip_interface& device) } TypedResult defaultReferencePosition(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self) +void insert(::microstrain::Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self) { insert(serializer, self.function); @@ -3288,7 +3288,7 @@ void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptive } } -void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self) +void extract(::microstrain::Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self) { extract(serializer, self.function); @@ -3311,7 +3311,7 @@ void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasu } } -void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self) +void insert(::microstrain::Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self) { insert(serializer, self.adaptive_measurement); @@ -3328,7 +3328,7 @@ void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptive insert(serializer, self.minimum_uncertainty); } -void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self) +void extract(::microstrain::Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self) { extract(serializer, self.adaptive_measurement); @@ -3348,8 +3348,8 @@ void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasu TypedResult writeAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, adaptiveMeasurement); @@ -3372,8 +3372,8 @@ TypedResult writeAccelMagnitudeErrorAdap } TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3383,7 +3383,7 @@ TypedResult readAccelMagnitudeErrorAdapt if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(adaptiveMeasurementOut); extract(deserializer, *adaptiveMeasurementOut); @@ -3413,8 +3413,8 @@ TypedResult readAccelMagnitudeErrorAdapt } TypedResult saveAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3423,8 +3423,8 @@ TypedResult saveAccelMagnitudeErrorAdapt } TypedResult loadAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3433,15 +3433,15 @@ TypedResult loadAccelMagnitudeErrorAdapt } TypedResult defaultAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self) +void insert(::microstrain::Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self) { insert(serializer, self.function); @@ -3463,7 +3463,7 @@ void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMe } } -void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self) +void extract(::microstrain::Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self) { extract(serializer, self.function); @@ -3486,7 +3486,7 @@ void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasure } } -void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self) +void insert(::microstrain::Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self) { insert(serializer, self.adaptive_measurement); @@ -3503,7 +3503,7 @@ void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMe insert(serializer, self.minimum_uncertainty); } -void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self) +void extract(::microstrain::Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self) { extract(serializer, self.adaptive_measurement); @@ -3523,8 +3523,8 @@ void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasure TypedResult writeMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, adaptiveMeasurement); @@ -3547,8 +3547,8 @@ TypedResult writeMagMagnitudeErrorAdaptive } TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3558,7 +3558,7 @@ TypedResult readMagMagnitudeErrorAdaptiveM if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(adaptiveMeasurementOut); extract(deserializer, *adaptiveMeasurementOut); @@ -3588,8 +3588,8 @@ TypedResult readMagMagnitudeErrorAdaptiveM } TypedResult saveMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3598,8 +3598,8 @@ TypedResult saveMagMagnitudeErrorAdaptiveM } TypedResult loadMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3608,15 +3608,15 @@ TypedResult loadMagMagnitudeErrorAdaptiveM } TypedResult defaultMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self) +void insert(::microstrain::Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self) { insert(serializer, self.function); @@ -3634,7 +3634,7 @@ void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMea } } -void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurement& self) +void extract(::microstrain::Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement& self) { extract(serializer, self.function); @@ -3653,7 +3653,7 @@ void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurem } } -void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self) +void insert(::microstrain::Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self) { insert(serializer, self.enable); @@ -3666,7 +3666,7 @@ void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMea insert(serializer, self.minimum_uncertainty); } -void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self) +void extract(::microstrain::Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self) { extract(serializer, self.enable); @@ -3682,8 +3682,8 @@ void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurem TypedResult writeMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool enable, float frequency, float highLimit, float highLimitUncertainty, float minimumUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -3702,8 +3702,8 @@ TypedResult writeMagDipAngleErrorAdaptiveMe } TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3713,7 +3713,7 @@ TypedResult readMagDipAngleErrorAdaptiveMea if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -3737,8 +3737,8 @@ TypedResult readMagDipAngleErrorAdaptiveMea } TypedResult saveMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -3747,8 +3747,8 @@ TypedResult saveMagDipAngleErrorAdaptiveMea } TypedResult loadMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -3757,15 +3757,15 @@ TypedResult loadMagDipAngleErrorAdaptiveMea } TypedResult defaultMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AidingMeasurementEnable& self) +void insert(::microstrain::Serializer& serializer, const AidingMeasurementEnable& self) { insert(serializer, self.function); @@ -3777,7 +3777,7 @@ void insert(::microstrain::Buffer& serializer, const AidingMeasurementEnable& se } } -void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable& self) +void extract(::microstrain::Serializer& serializer, AidingMeasurementEnable& self) { extract(serializer, self.function); @@ -3790,14 +3790,14 @@ void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable& self) } } -void insert(::microstrain::Buffer& serializer, const AidingMeasurementEnable::Response& self) +void insert(::microstrain::Serializer& serializer, const AidingMeasurementEnable::Response& self) { insert(serializer, self.aiding_source); insert(serializer, self.enable); } -void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable::Response& self) +void extract(::microstrain::Serializer& serializer, AidingMeasurementEnable::Response& self) { extract(serializer, self.aiding_source); @@ -3807,8 +3807,8 @@ void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable::Respons TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, aidingSource); @@ -3821,8 +3821,8 @@ TypedResult writeAidingMeasurementEnable(C::mip_interfa } TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, aidingSource); @@ -3834,7 +3834,7 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, aidingSource); @@ -3848,8 +3848,8 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac } TypedResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, aidingSource); @@ -3860,8 +3860,8 @@ TypedResult saveAidingMeasurementEnable(C::mip_interfac } TypedResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, aidingSource); @@ -3872,8 +3872,8 @@ TypedResult loadAidingMeasurementEnable(C::mip_interfac } TypedResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, aidingSource); @@ -3882,12 +3882,12 @@ TypedResult defaultAidingMeasurementEnable(C::mip_inter return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const Run& self) +void insert(::microstrain::Serializer& serializer, const Run& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, Run& self) +void extract(::microstrain::Serializer& serializer, Run& self) { (void)serializer; (void)self; @@ -3897,7 +3897,7 @@ TypedResult run(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RUN, NULL, 0); } -void insert(::microstrain::Buffer& serializer, const KinematicConstraint& self) +void insert(::microstrain::Serializer& serializer, const KinematicConstraint& self) { insert(serializer, self.function); @@ -3911,7 +3911,7 @@ void insert(::microstrain::Buffer& serializer, const KinematicConstraint& self) } } -void extract(::microstrain::Buffer& serializer, KinematicConstraint& self) +void extract(::microstrain::Serializer& serializer, KinematicConstraint& self) { extract(serializer, self.function); @@ -3926,7 +3926,7 @@ void extract(::microstrain::Buffer& serializer, KinematicConstraint& self) } } -void insert(::microstrain::Buffer& serializer, const KinematicConstraint::Response& self) +void insert(::microstrain::Serializer& serializer, const KinematicConstraint::Response& self) { insert(serializer, self.acceleration_constraint_selection); @@ -3935,7 +3935,7 @@ void insert(::microstrain::Buffer& serializer, const KinematicConstraint::Respon insert(serializer, self.angular_constraint_selection); } -void extract(::microstrain::Buffer& serializer, KinematicConstraint::Response& self) +void extract(::microstrain::Serializer& serializer, KinematicConstraint::Response& self) { extract(serializer, self.acceleration_constraint_selection); @@ -3947,8 +3947,8 @@ void extract(::microstrain::Buffer& serializer, KinematicConstraint::Response& s TypedResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, accelerationConstraintSelection); @@ -3963,8 +3963,8 @@ TypedResult writeKinematicConstraint(C::mip_interface& devi } TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -3974,7 +3974,7 @@ TypedResult readKinematicConstraint(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(accelerationConstraintSelectionOut); extract(deserializer, *accelerationConstraintSelectionOut); @@ -3992,8 +3992,8 @@ TypedResult readKinematicConstraint(C::mip_interface& devic } TypedResult saveKinematicConstraint(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4002,8 +4002,8 @@ TypedResult saveKinematicConstraint(C::mip_interface& devic } TypedResult loadKinematicConstraint(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4012,15 +4012,15 @@ TypedResult loadKinematicConstraint(C::mip_interface& devic } TypedResult defaultKinematicConstraint(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const InitializationConfiguration& self) +void insert(::microstrain::Serializer& serializer, const InitializationConfiguration& self) { insert(serializer, self.function); @@ -4048,7 +4048,7 @@ void insert(::microstrain::Buffer& serializer, const InitializationConfiguration } } -void extract(::microstrain::Buffer& serializer, InitializationConfiguration& self) +void extract(::microstrain::Serializer& serializer, InitializationConfiguration& self) { extract(serializer, self.function); @@ -4077,7 +4077,7 @@ void extract(::microstrain::Buffer& serializer, InitializationConfiguration& sel } } -void insert(::microstrain::Buffer& serializer, const InitializationConfiguration::Response& self) +void insert(::microstrain::Serializer& serializer, const InitializationConfiguration::Response& self) { insert(serializer, self.wait_for_run_command); @@ -4100,7 +4100,7 @@ void insert(::microstrain::Buffer& serializer, const InitializationConfiguration insert(serializer, self.reference_frame_selector); } -void extract(::microstrain::Buffer& serializer, InitializationConfiguration::Response& self) +void extract(::microstrain::Serializer& serializer, InitializationConfiguration::Response& self) { extract(serializer, self.wait_for_run_command); @@ -4126,8 +4126,8 @@ void extract(::microstrain::Buffer& serializer, InitializationConfiguration::Res TypedResult writeInitializationConfiguration(C::mip_interface& device, uint8_t waitForRunCommand, InitializationConfiguration::InitialConditionSource initialCondSrc, InitializationConfiguration::AlignmentSelector autoHeadingAlignmentSelector, float initialHeading, float initialPitch, float initialRoll, const float* initialPosition, const float* initialVelocity, FilterReferenceFrame referenceFrameSelector) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, waitForRunCommand); @@ -4158,8 +4158,8 @@ TypedResult writeInitializationConfiguration(C::mip } TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4169,7 +4169,7 @@ TypedResult readInitializationConfiguration(C::mip_ if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(waitForRunCommandOut); extract(deserializer, *waitForRunCommandOut); @@ -4207,8 +4207,8 @@ TypedResult readInitializationConfiguration(C::mip_ } TypedResult saveInitializationConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4217,8 +4217,8 @@ TypedResult saveInitializationConfiguration(C::mip_ } TypedResult loadInitializationConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4227,15 +4227,15 @@ TypedResult loadInitializationConfiguration(C::mip_ } TypedResult defaultInitializationConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const AdaptiveFilterOptions& self) +void insert(::microstrain::Serializer& serializer, const AdaptiveFilterOptions& self) { insert(serializer, self.function); @@ -4247,7 +4247,7 @@ void insert(::microstrain::Buffer& serializer, const AdaptiveFilterOptions& self } } -void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions& self) +void extract(::microstrain::Serializer& serializer, AdaptiveFilterOptions& self) { extract(serializer, self.function); @@ -4260,14 +4260,14 @@ void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions& self) } } -void insert(::microstrain::Buffer& serializer, const AdaptiveFilterOptions::Response& self) +void insert(::microstrain::Serializer& serializer, const AdaptiveFilterOptions::Response& self) { insert(serializer, self.level); insert(serializer, self.time_limit); } -void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions::Response& self) +void extract(::microstrain::Serializer& serializer, AdaptiveFilterOptions::Response& self) { extract(serializer, self.level); @@ -4277,8 +4277,8 @@ void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions::Response& TypedResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, level); @@ -4291,8 +4291,8 @@ TypedResult writeAdaptiveFilterOptions(C::mip_interface& } TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4302,7 +4302,7 @@ TypedResult readAdaptiveFilterOptions(C::mip_interface& d if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(levelOut); extract(deserializer, *levelOut); @@ -4317,8 +4317,8 @@ TypedResult readAdaptiveFilterOptions(C::mip_interface& d } TypedResult saveAdaptiveFilterOptions(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4327,8 +4327,8 @@ TypedResult saveAdaptiveFilterOptions(C::mip_interface& d } TypedResult loadAdaptiveFilterOptions(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4337,15 +4337,15 @@ TypedResult loadAdaptiveFilterOptions(C::mip_interface& d } TypedResult defaultAdaptiveFilterOptions(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset& self) +void insert(::microstrain::Serializer& serializer, const MultiAntennaOffset& self) { insert(serializer, self.function); @@ -4358,7 +4358,7 @@ void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset& self) } } -void extract(::microstrain::Buffer& serializer, MultiAntennaOffset& self) +void extract(::microstrain::Serializer& serializer, MultiAntennaOffset& self) { extract(serializer, self.function); @@ -4372,7 +4372,7 @@ void extract(::microstrain::Buffer& serializer, MultiAntennaOffset& self) } } -void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset::Response& self) +void insert(::microstrain::Serializer& serializer, const MultiAntennaOffset::Response& self) { insert(serializer, self.receiver_id); @@ -4380,7 +4380,7 @@ void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset::Respons insert(serializer, self.antenna_offset[i]); } -void extract(::microstrain::Buffer& serializer, MultiAntennaOffset::Response& self) +void extract(::microstrain::Serializer& serializer, MultiAntennaOffset::Response& self) { extract(serializer, self.receiver_id); @@ -4391,8 +4391,8 @@ void extract(::microstrain::Buffer& serializer, MultiAntennaOffset::Response& se TypedResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, receiverId); @@ -4407,8 +4407,8 @@ TypedResult writeMultiAntennaOffset(C::mip_interface& device } TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, receiverId); @@ -4420,7 +4420,7 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, receiverId); @@ -4435,8 +4435,8 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, } TypedResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, receiverId); @@ -4447,8 +4447,8 @@ TypedResult saveMultiAntennaOffset(C::mip_interface& device, } TypedResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, receiverId); @@ -4459,8 +4459,8 @@ TypedResult loadMultiAntennaOffset(C::mip_interface& device, } TypedResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, receiverId); @@ -4469,7 +4469,7 @@ TypedResult defaultMultiAntennaOffset(C::mip_interface& devi return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const RelPosConfiguration& self) +void insert(::microstrain::Serializer& serializer, const RelPosConfiguration& self) { insert(serializer, self.function); @@ -4484,7 +4484,7 @@ void insert(::microstrain::Buffer& serializer, const RelPosConfiguration& self) } } -void extract(::microstrain::Buffer& serializer, RelPosConfiguration& self) +void extract(::microstrain::Serializer& serializer, RelPosConfiguration& self) { extract(serializer, self.function); @@ -4500,7 +4500,7 @@ void extract(::microstrain::Buffer& serializer, RelPosConfiguration& self) } } -void insert(::microstrain::Buffer& serializer, const RelPosConfiguration::Response& self) +void insert(::microstrain::Serializer& serializer, const RelPosConfiguration::Response& self) { insert(serializer, self.source); @@ -4510,7 +4510,7 @@ void insert(::microstrain::Buffer& serializer, const RelPosConfiguration::Respon insert(serializer, self.reference_coordinates[i]); } -void extract(::microstrain::Buffer& serializer, RelPosConfiguration::Response& self) +void extract(::microstrain::Serializer& serializer, RelPosConfiguration::Response& self) { extract(serializer, self.source); @@ -4523,8 +4523,8 @@ void extract(::microstrain::Buffer& serializer, RelPosConfiguration::Response& s TypedResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -4541,8 +4541,8 @@ TypedResult writeRelPosConfiguration(C::mip_interface& devi } TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4552,7 +4552,7 @@ TypedResult readRelPosConfiguration(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(sourceOut); extract(deserializer, *sourceOut); @@ -4571,8 +4571,8 @@ TypedResult readRelPosConfiguration(C::mip_interface& devic } TypedResult saveRelPosConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4581,8 +4581,8 @@ TypedResult saveRelPosConfiguration(C::mip_interface& devic } TypedResult loadRelPosConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4591,15 +4591,15 @@ TypedResult loadRelPosConfiguration(C::mip_interface& devic } TypedResult defaultRelPosConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const RefPointLeverArm& self) +void insert(::microstrain::Serializer& serializer, const RefPointLeverArm& self) { insert(serializer, self.function); @@ -4612,7 +4612,7 @@ void insert(::microstrain::Buffer& serializer, const RefPointLeverArm& self) } } -void extract(::microstrain::Buffer& serializer, RefPointLeverArm& self) +void extract(::microstrain::Serializer& serializer, RefPointLeverArm& self) { extract(serializer, self.function); @@ -4626,7 +4626,7 @@ void extract(::microstrain::Buffer& serializer, RefPointLeverArm& self) } } -void insert(::microstrain::Buffer& serializer, const RefPointLeverArm::Response& self) +void insert(::microstrain::Serializer& serializer, const RefPointLeverArm::Response& self) { insert(serializer, self.ref_point_sel); @@ -4634,7 +4634,7 @@ void insert(::microstrain::Buffer& serializer, const RefPointLeverArm::Response& insert(serializer, self.lever_arm_offset[i]); } -void extract(::microstrain::Buffer& serializer, RefPointLeverArm::Response& self) +void extract(::microstrain::Serializer& serializer, RefPointLeverArm::Response& self) { extract(serializer, self.ref_point_sel); @@ -4645,8 +4645,8 @@ void extract(::microstrain::Buffer& serializer, RefPointLeverArm::Response& self TypedResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, refPointSel); @@ -4661,8 +4661,8 @@ TypedResult writeRefPointLeverArm(C::mip_interface& device, Re } TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4672,7 +4672,7 @@ TypedResult readRefPointLeverArm(C::mip_interface& device, Ref if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(refPointSelOut); extract(deserializer, *refPointSelOut); @@ -4688,8 +4688,8 @@ TypedResult readRefPointLeverArm(C::mip_interface& device, Ref } TypedResult saveRefPointLeverArm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4698,8 +4698,8 @@ TypedResult saveRefPointLeverArm(C::mip_interface& device) } TypedResult loadRefPointLeverArm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4708,15 +4708,15 @@ TypedResult loadRefPointLeverArm(C::mip_interface& device) } TypedResult defaultRefPointLeverArm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SpeedMeasurement& self) +void insert(::microstrain::Serializer& serializer, const SpeedMeasurement& self) { insert(serializer, self.source); @@ -4727,7 +4727,7 @@ void insert(::microstrain::Buffer& serializer, const SpeedMeasurement& self) insert(serializer, self.speed_uncertainty); } -void extract(::microstrain::Buffer& serializer, SpeedMeasurement& self) +void extract(::microstrain::Serializer& serializer, SpeedMeasurement& self) { extract(serializer, self.source); @@ -4741,8 +4741,8 @@ void extract(::microstrain::Buffer& serializer, SpeedMeasurement& self) TypedResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, source); @@ -4756,7 +4756,7 @@ TypedResult speedMeasurement(C::mip_interface& device, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_MEASUREMENT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SpeedLeverArm& self) +void insert(::microstrain::Serializer& serializer, const SpeedLeverArm& self) { insert(serializer, self.function); @@ -4769,7 +4769,7 @@ void insert(::microstrain::Buffer& serializer, const SpeedLeverArm& self) } } -void extract(::microstrain::Buffer& serializer, SpeedLeverArm& self) +void extract(::microstrain::Serializer& serializer, SpeedLeverArm& self) { extract(serializer, self.function); @@ -4783,7 +4783,7 @@ void extract(::microstrain::Buffer& serializer, SpeedLeverArm& self) } } -void insert(::microstrain::Buffer& serializer, const SpeedLeverArm::Response& self) +void insert(::microstrain::Serializer& serializer, const SpeedLeverArm::Response& self) { insert(serializer, self.source); @@ -4791,7 +4791,7 @@ void insert(::microstrain::Buffer& serializer, const SpeedLeverArm::Response& se insert(serializer, self.lever_arm_offset[i]); } -void extract(::microstrain::Buffer& serializer, SpeedLeverArm::Response& self) +void extract(::microstrain::Serializer& serializer, SpeedLeverArm::Response& self) { extract(serializer, self.source); @@ -4802,8 +4802,8 @@ void extract(::microstrain::Buffer& serializer, SpeedLeverArm::Response& self) TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, source); @@ -4818,8 +4818,8 @@ TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t } TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); insert(serializer, source); @@ -4831,7 +4831,7 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract(deserializer, source); @@ -4846,8 +4846,8 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s } TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); insert(serializer, source); @@ -4858,8 +4858,8 @@ TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t s } TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); insert(serializer, source); @@ -4870,8 +4870,8 @@ TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t s } TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); insert(serializer, source); @@ -4880,7 +4880,7 @@ TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_ return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const WheeledVehicleConstraintControl& self) +void insert(::microstrain::Serializer& serializer, const WheeledVehicleConstraintControl& self) { insert(serializer, self.function); @@ -4890,7 +4890,7 @@ void insert(::microstrain::Buffer& serializer, const WheeledVehicleConstraintCon } } -void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl& self) +void extract(::microstrain::Serializer& serializer, WheeledVehicleConstraintControl& self) { extract(serializer, self.function); @@ -4901,12 +4901,12 @@ void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl& } } -void insert(::microstrain::Buffer& serializer, const WheeledVehicleConstraintControl::Response& self) +void insert(::microstrain::Serializer& serializer, const WheeledVehicleConstraintControl::Response& self) { insert(serializer, self.enable); } -void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl::Response& self) +void extract(::microstrain::Serializer& serializer, WheeledVehicleConstraintControl::Response& self) { extract(serializer, self.enable); @@ -4914,8 +4914,8 @@ void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl: TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -4926,8 +4926,8 @@ TypedResult writeWheeledVehicleConstraintContro } TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -4937,7 +4937,7 @@ TypedResult readWheeledVehicleConstraintControl if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -4949,8 +4949,8 @@ TypedResult readWheeledVehicleConstraintControl } TypedResult saveWheeledVehicleConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -4959,8 +4959,8 @@ TypedResult saveWheeledVehicleConstraintControl } TypedResult loadWheeledVehicleConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -4969,15 +4969,15 @@ TypedResult loadWheeledVehicleConstraintControl } TypedResult defaultWheeledVehicleConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const VerticalGyroConstraintControl& self) +void insert(::microstrain::Serializer& serializer, const VerticalGyroConstraintControl& self) { insert(serializer, self.function); @@ -4987,7 +4987,7 @@ void insert(::microstrain::Buffer& serializer, const VerticalGyroConstraintContr } } -void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl& self) +void extract(::microstrain::Serializer& serializer, VerticalGyroConstraintControl& self) { extract(serializer, self.function); @@ -4998,12 +4998,12 @@ void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl& s } } -void insert(::microstrain::Buffer& serializer, const VerticalGyroConstraintControl::Response& self) +void insert(::microstrain::Serializer& serializer, const VerticalGyroConstraintControl::Response& self) { insert(serializer, self.enable); } -void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl::Response& self) +void extract(::microstrain::Serializer& serializer, VerticalGyroConstraintControl::Response& self) { extract(serializer, self.enable); @@ -5011,8 +5011,8 @@ void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl::R TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -5023,8 +5023,8 @@ TypedResult writeVerticalGyroConstraintControl(C: } TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -5034,7 +5034,7 @@ TypedResult readVerticalGyroConstraintControl(C:: if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -5046,8 +5046,8 @@ TypedResult readVerticalGyroConstraintControl(C:: } TypedResult saveVerticalGyroConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -5056,8 +5056,8 @@ TypedResult saveVerticalGyroConstraintControl(C:: } TypedResult loadVerticalGyroConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -5066,15 +5066,15 @@ TypedResult loadVerticalGyroConstraintControl(C:: } TypedResult defaultVerticalGyroConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GnssAntennaCalControl& self) +void insert(::microstrain::Serializer& serializer, const GnssAntennaCalControl& self) { insert(serializer, self.function); @@ -5086,7 +5086,7 @@ void insert(::microstrain::Buffer& serializer, const GnssAntennaCalControl& self } } -void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl& self) +void extract(::microstrain::Serializer& serializer, GnssAntennaCalControl& self) { extract(serializer, self.function); @@ -5099,14 +5099,14 @@ void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl& self) } } -void insert(::microstrain::Buffer& serializer, const GnssAntennaCalControl::Response& self) +void insert(::microstrain::Serializer& serializer, const GnssAntennaCalControl::Response& self) { insert(serializer, self.enable); insert(serializer, self.max_offset); } -void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl::Response& self) +void extract(::microstrain::Serializer& serializer, GnssAntennaCalControl::Response& self) { extract(serializer, self.enable); @@ -5116,8 +5116,8 @@ void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl::Response& TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -5130,8 +5130,8 @@ TypedResult writeGnssAntennaCalControl(C::mip_interface& } TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -5141,7 +5141,7 @@ TypedResult readGnssAntennaCalControl(C::mip_interface& d if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -5156,8 +5156,8 @@ TypedResult readGnssAntennaCalControl(C::mip_interface& d } TypedResult saveGnssAntennaCalControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -5166,8 +5166,8 @@ TypedResult saveGnssAntennaCalControl(C::mip_interface& d } TypedResult loadGnssAntennaCalControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -5176,20 +5176,20 @@ TypedResult loadGnssAntennaCalControl(C::mip_interface& d } TypedResult defaultGnssAntennaCalControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const SetInitialHeading& self) +void insert(::microstrain::Serializer& serializer, const SetInitialHeading& self) { insert(serializer, self.heading); } -void extract(::microstrain::Buffer& serializer, SetInitialHeading& self) +void extract(::microstrain::Serializer& serializer, SetInitialHeading& self) { extract(serializer, self.heading); @@ -5197,8 +5197,8 @@ void extract(::microstrain::Buffer& serializer, SetInitialHeading& self) TypedResult setInitialHeading(C::mip_interface& device, float heading) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, heading); diff --git a/src/mip/definitions/commands_filter.hpp b/src/mip/definitions/commands_filter.hpp index 0cbfb8b1e..b3036e0e1 100644 --- a/src/mip/definitions/commands_filter.hpp +++ b/src/mip/definitions/commands_filter.hpp @@ -212,8 +212,8 @@ struct Reset } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const Reset& self); -void extract(::microstrain::Buffer& serializer, Reset& self); +void insert(::microstrain::Serializer& serializer, const Reset& self); +void extract(::microstrain::Serializer& serializer, Reset& self); TypedResult reset(C::mip_interface& device); @@ -262,8 +262,8 @@ struct SetInitialAttitude } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const SetInitialAttitude& self); -void extract(::microstrain::Buffer& serializer, SetInitialAttitude& self); +void insert(::microstrain::Serializer& serializer, const SetInitialAttitude& self); +void extract(::microstrain::Serializer& serializer, SetInitialAttitude& self); TypedResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading); @@ -384,11 +384,11 @@ struct EstimationControl } }; }; -void insert(::microstrain::Buffer& serializer, const EstimationControl& self); -void extract(::microstrain::Buffer& serializer, EstimationControl& self); +void insert(::microstrain::Serializer& serializer, const EstimationControl& self); +void extract(::microstrain::Serializer& serializer, EstimationControl& self); -void insert(::microstrain::Buffer& serializer, const EstimationControl::Response& self); -void extract(::microstrain::Buffer& serializer, EstimationControl::Response& self); +void insert(::microstrain::Serializer& serializer, const EstimationControl::Response& self); +void extract(::microstrain::Serializer& serializer, EstimationControl::Response& self); TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable); TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut); @@ -439,8 +439,8 @@ struct ExternalGnssUpdate } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const ExternalGnssUpdate& self); -void extract(::microstrain::Buffer& serializer, ExternalGnssUpdate& self); +void insert(::microstrain::Serializer& serializer, const ExternalGnssUpdate& self); +void extract(::microstrain::Serializer& serializer, ExternalGnssUpdate& self); TypedResult externalGnssUpdate(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, double latitude, double longitude, double height, const float* velocity, const float* posUncertainty, const float* velUncertainty); @@ -490,8 +490,8 @@ struct ExternalHeadingUpdate } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdate& self); -void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdate& self); +void insert(::microstrain::Serializer& serializer, const ExternalHeadingUpdate& self); +void extract(::microstrain::Serializer& serializer, ExternalHeadingUpdate& self); TypedResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type); @@ -547,8 +547,8 @@ struct ExternalHeadingUpdateWithTime } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const ExternalHeadingUpdateWithTime& self); -void extract(::microstrain::Buffer& serializer, ExternalHeadingUpdateWithTime& self); +void insert(::microstrain::Serializer& serializer, const ExternalHeadingUpdateWithTime& self); +void extract(::microstrain::Serializer& serializer, ExternalHeadingUpdateWithTime& self); TypedResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type); @@ -651,11 +651,11 @@ struct TareOrientation } }; }; -void insert(::microstrain::Buffer& serializer, const TareOrientation& self); -void extract(::microstrain::Buffer& serializer, TareOrientation& self); +void insert(::microstrain::Serializer& serializer, const TareOrientation& self); +void extract(::microstrain::Serializer& serializer, TareOrientation& self); -void insert(::microstrain::Buffer& serializer, const TareOrientation::Response& self); -void extract(::microstrain::Buffer& serializer, TareOrientation::Response& self); +void insert(::microstrain::Serializer& serializer, const TareOrientation::Response& self); +void extract(::microstrain::Serializer& serializer, TareOrientation::Response& self); TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes); TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut); @@ -735,11 +735,11 @@ struct VehicleDynamicsMode } }; }; -void insert(::microstrain::Buffer& serializer, const VehicleDynamicsMode& self); -void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode& self); +void insert(::microstrain::Serializer& serializer, const VehicleDynamicsMode& self); +void extract(::microstrain::Serializer& serializer, VehicleDynamicsMode& self); -void insert(::microstrain::Buffer& serializer, const VehicleDynamicsMode::Response& self); -void extract(::microstrain::Buffer& serializer, VehicleDynamicsMode::Response& self); +void insert(::microstrain::Serializer& serializer, const VehicleDynamicsMode::Response& self); +void extract(::microstrain::Serializer& serializer, VehicleDynamicsMode::Response& self); TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode); TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut); @@ -837,11 +837,11 @@ struct SensorToVehicleRotationEuler } }; }; -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEuler& self); -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler& self); +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationEuler& self); +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationEuler& self); -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationEuler::Response& self); -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationEuler::Response& self); +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationEuler::Response& self); +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationEuler::Response& self); TypedResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw); TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut); @@ -941,11 +941,11 @@ struct SensorToVehicleRotationDcm } }; }; -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationDcm& self); -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm& self); +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationDcm& self); +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationDcm& self); -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationDcm::Response& self); -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationDcm::Response& self); +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationDcm::Response& self); +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationDcm::Response& self); TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm); TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut); @@ -1044,11 +1044,11 @@ struct SensorToVehicleRotationQuaternion } }; }; -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationQuaternion& self); -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternion& self); +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationQuaternion& self); +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationQuaternion& self); -void insert(::microstrain::Buffer& serializer, const SensorToVehicleRotationQuaternion::Response& self); -void extract(::microstrain::Buffer& serializer, SensorToVehicleRotationQuaternion::Response& self); +void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationQuaternion::Response& self); +void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationQuaternion::Response& self); TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat); TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut); @@ -1128,11 +1128,11 @@ struct SensorToVehicleOffset } }; }; -void insert(::microstrain::Buffer& serializer, const SensorToVehicleOffset& self); -void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset& self); +void insert(::microstrain::Serializer& serializer, const SensorToVehicleOffset& self); +void extract(::microstrain::Serializer& serializer, SensorToVehicleOffset& self); -void insert(::microstrain::Buffer& serializer, const SensorToVehicleOffset::Response& self); -void extract(::microstrain::Buffer& serializer, SensorToVehicleOffset::Response& self); +void insert(::microstrain::Serializer& serializer, const SensorToVehicleOffset::Response& self); +void extract(::microstrain::Serializer& serializer, SensorToVehicleOffset::Response& self); TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset); TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut); @@ -1209,11 +1209,11 @@ struct AntennaOffset } }; }; -void insert(::microstrain::Buffer& serializer, const AntennaOffset& self); -void extract(::microstrain::Buffer& serializer, AntennaOffset& self); +void insert(::microstrain::Serializer& serializer, const AntennaOffset& self); +void extract(::microstrain::Serializer& serializer, AntennaOffset& self); -void insert(::microstrain::Buffer& serializer, const AntennaOffset::Response& self); -void extract(::microstrain::Buffer& serializer, AntennaOffset::Response& self); +void insert(::microstrain::Serializer& serializer, const AntennaOffset::Response& self); +void extract(::microstrain::Serializer& serializer, AntennaOffset::Response& self); TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset); TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut); @@ -1297,11 +1297,11 @@ struct GnssSource } }; }; -void insert(::microstrain::Buffer& serializer, const GnssSource& self); -void extract(::microstrain::Buffer& serializer, GnssSource& self); +void insert(::microstrain::Serializer& serializer, const GnssSource& self); +void extract(::microstrain::Serializer& serializer, GnssSource& self); -void insert(::microstrain::Buffer& serializer, const GnssSource::Response& self); -void extract(::microstrain::Buffer& serializer, GnssSource::Response& self); +void insert(::microstrain::Serializer& serializer, const GnssSource::Response& self); +void extract(::microstrain::Serializer& serializer, GnssSource::Response& self); TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source); TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut); @@ -1396,11 +1396,11 @@ struct HeadingSource } }; }; -void insert(::microstrain::Buffer& serializer, const HeadingSource& self); -void extract(::microstrain::Buffer& serializer, HeadingSource& self); +void insert(::microstrain::Serializer& serializer, const HeadingSource& self); +void extract(::microstrain::Serializer& serializer, HeadingSource& self); -void insert(::microstrain::Buffer& serializer, const HeadingSource::Response& self); -void extract(::microstrain::Buffer& serializer, HeadingSource::Response& self); +void insert(::microstrain::Serializer& serializer, const HeadingSource::Response& self); +void extract(::microstrain::Serializer& serializer, HeadingSource::Response& self); TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source); TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut); @@ -1480,11 +1480,11 @@ struct AutoInitControl } }; }; -void insert(::microstrain::Buffer& serializer, const AutoInitControl& self); -void extract(::microstrain::Buffer& serializer, AutoInitControl& self); +void insert(::microstrain::Serializer& serializer, const AutoInitControl& self); +void extract(::microstrain::Serializer& serializer, AutoInitControl& self); -void insert(::microstrain::Buffer& serializer, const AutoInitControl::Response& self); -void extract(::microstrain::Buffer& serializer, AutoInitControl::Response& self); +void insert(::microstrain::Serializer& serializer, const AutoInitControl::Response& self); +void extract(::microstrain::Serializer& serializer, AutoInitControl::Response& self); TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable); TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut); @@ -1562,11 +1562,11 @@ struct AccelNoise } }; }; -void insert(::microstrain::Buffer& serializer, const AccelNoise& self); -void extract(::microstrain::Buffer& serializer, AccelNoise& self); +void insert(::microstrain::Serializer& serializer, const AccelNoise& self); +void extract(::microstrain::Serializer& serializer, AccelNoise& self); -void insert(::microstrain::Buffer& serializer, const AccelNoise::Response& self); -void extract(::microstrain::Buffer& serializer, AccelNoise::Response& self); +void insert(::microstrain::Serializer& serializer, const AccelNoise::Response& self); +void extract(::microstrain::Serializer& serializer, AccelNoise::Response& self); TypedResult writeAccelNoise(C::mip_interface& device, const float* noise); TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut); @@ -1644,11 +1644,11 @@ struct GyroNoise } }; }; -void insert(::microstrain::Buffer& serializer, const GyroNoise& self); -void extract(::microstrain::Buffer& serializer, GyroNoise& self); +void insert(::microstrain::Serializer& serializer, const GyroNoise& self); +void extract(::microstrain::Serializer& serializer, GyroNoise& self); -void insert(::microstrain::Buffer& serializer, const GyroNoise::Response& self); -void extract(::microstrain::Buffer& serializer, GyroNoise::Response& self); +void insert(::microstrain::Serializer& serializer, const GyroNoise::Response& self); +void extract(::microstrain::Serializer& serializer, GyroNoise::Response& self); TypedResult writeGyroNoise(C::mip_interface& device, const float* noise); TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut); @@ -1725,11 +1725,11 @@ struct AccelBiasModel } }; }; -void insert(::microstrain::Buffer& serializer, const AccelBiasModel& self); -void extract(::microstrain::Buffer& serializer, AccelBiasModel& self); +void insert(::microstrain::Serializer& serializer, const AccelBiasModel& self); +void extract(::microstrain::Serializer& serializer, AccelBiasModel& self); -void insert(::microstrain::Buffer& serializer, const AccelBiasModel::Response& self); -void extract(::microstrain::Buffer& serializer, AccelBiasModel::Response& self); +void insert(::microstrain::Serializer& serializer, const AccelBiasModel::Response& self); +void extract(::microstrain::Serializer& serializer, AccelBiasModel::Response& self); TypedResult writeAccelBiasModel(C::mip_interface& device, const float* beta, const float* noise); TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut); @@ -1806,11 +1806,11 @@ struct GyroBiasModel } }; }; -void insert(::microstrain::Buffer& serializer, const GyroBiasModel& self); -void extract(::microstrain::Buffer& serializer, GyroBiasModel& self); +void insert(::microstrain::Serializer& serializer, const GyroBiasModel& self); +void extract(::microstrain::Serializer& serializer, GyroBiasModel& self); -void insert(::microstrain::Buffer& serializer, const GyroBiasModel::Response& self); -void extract(::microstrain::Buffer& serializer, GyroBiasModel::Response& self); +void insert(::microstrain::Serializer& serializer, const GyroBiasModel::Response& self); +void extract(::microstrain::Serializer& serializer, GyroBiasModel::Response& self); TypedResult writeGyroBiasModel(C::mip_interface& device, const float* beta, const float* noise); TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut); @@ -1892,11 +1892,11 @@ struct AltitudeAiding } }; }; -void insert(::microstrain::Buffer& serializer, const AltitudeAiding& self); -void extract(::microstrain::Buffer& serializer, AltitudeAiding& self); +void insert(::microstrain::Serializer& serializer, const AltitudeAiding& self); +void extract(::microstrain::Serializer& serializer, AltitudeAiding& self); -void insert(::microstrain::Buffer& serializer, const AltitudeAiding::Response& self); -void extract(::microstrain::Buffer& serializer, AltitudeAiding::Response& self); +void insert(::microstrain::Serializer& serializer, const AltitudeAiding::Response& self); +void extract(::microstrain::Serializer& serializer, AltitudeAiding::Response& self); TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector); TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut); @@ -1975,11 +1975,11 @@ struct PitchRollAiding } }; }; -void insert(::microstrain::Buffer& serializer, const PitchRollAiding& self); -void extract(::microstrain::Buffer& serializer, PitchRollAiding& self); +void insert(::microstrain::Serializer& serializer, const PitchRollAiding& self); +void extract(::microstrain::Serializer& serializer, PitchRollAiding& self); -void insert(::microstrain::Buffer& serializer, const PitchRollAiding::Response& self); -void extract(::microstrain::Buffer& serializer, PitchRollAiding::Response& self); +void insert(::microstrain::Serializer& serializer, const PitchRollAiding::Response& self); +void extract(::microstrain::Serializer& serializer, PitchRollAiding::Response& self); TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source); TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut); @@ -2054,11 +2054,11 @@ struct AutoZupt } }; }; -void insert(::microstrain::Buffer& serializer, const AutoZupt& self); -void extract(::microstrain::Buffer& serializer, AutoZupt& self); +void insert(::microstrain::Serializer& serializer, const AutoZupt& self); +void extract(::microstrain::Serializer& serializer, AutoZupt& self); -void insert(::microstrain::Buffer& serializer, const AutoZupt::Response& self); -void extract(::microstrain::Buffer& serializer, AutoZupt::Response& self); +void insert(::microstrain::Serializer& serializer, const AutoZupt::Response& self); +void extract(::microstrain::Serializer& serializer, AutoZupt::Response& self); TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold); TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut); @@ -2134,11 +2134,11 @@ struct AutoAngularZupt } }; }; -void insert(::microstrain::Buffer& serializer, const AutoAngularZupt& self); -void extract(::microstrain::Buffer& serializer, AutoAngularZupt& self); +void insert(::microstrain::Serializer& serializer, const AutoAngularZupt& self); +void extract(::microstrain::Serializer& serializer, AutoAngularZupt& self); -void insert(::microstrain::Buffer& serializer, const AutoAngularZupt::Response& self); -void extract(::microstrain::Buffer& serializer, AutoAngularZupt::Response& self); +void insert(::microstrain::Serializer& serializer, const AutoAngularZupt::Response& self); +void extract(::microstrain::Serializer& serializer, AutoAngularZupt::Response& self); TypedResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold); TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut); @@ -2177,8 +2177,8 @@ struct CommandedZupt } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const CommandedZupt& self); -void extract(::microstrain::Buffer& serializer, CommandedZupt& self); +void insert(::microstrain::Serializer& serializer, const CommandedZupt& self); +void extract(::microstrain::Serializer& serializer, CommandedZupt& self); TypedResult commandedZupt(C::mip_interface& device); @@ -2213,8 +2213,8 @@ struct CommandedAngularZupt } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const CommandedAngularZupt& self); -void extract(::microstrain::Buffer& serializer, CommandedAngularZupt& self); +void insert(::microstrain::Serializer& serializer, const CommandedAngularZupt& self); +void extract(::microstrain::Serializer& serializer, CommandedAngularZupt& self); TypedResult commandedAngularZupt(C::mip_interface& device); @@ -2265,8 +2265,8 @@ struct MagCaptureAutoCal typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const MagCaptureAutoCal& self); -void extract(::microstrain::Buffer& serializer, MagCaptureAutoCal& self); +void insert(::microstrain::Serializer& serializer, const MagCaptureAutoCal& self); +void extract(::microstrain::Serializer& serializer, MagCaptureAutoCal& self); TypedResult writeMagCaptureAutoCal(C::mip_interface& device); TypedResult saveMagCaptureAutoCal(C::mip_interface& device); @@ -2340,11 +2340,11 @@ struct GravityNoise } }; }; -void insert(::microstrain::Buffer& serializer, const GravityNoise& self); -void extract(::microstrain::Buffer& serializer, GravityNoise& self); +void insert(::microstrain::Serializer& serializer, const GravityNoise& self); +void extract(::microstrain::Serializer& serializer, GravityNoise& self); -void insert(::microstrain::Buffer& serializer, const GravityNoise::Response& self); -void extract(::microstrain::Buffer& serializer, GravityNoise::Response& self); +void insert(::microstrain::Serializer& serializer, const GravityNoise::Response& self); +void extract(::microstrain::Serializer& serializer, GravityNoise::Response& self); TypedResult writeGravityNoise(C::mip_interface& device, const float* noise); TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut); @@ -2421,11 +2421,11 @@ struct PressureAltitudeNoise } }; }; -void insert(::microstrain::Buffer& serializer, const PressureAltitudeNoise& self); -void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise& self); +void insert(::microstrain::Serializer& serializer, const PressureAltitudeNoise& self); +void extract(::microstrain::Serializer& serializer, PressureAltitudeNoise& self); -void insert(::microstrain::Buffer& serializer, const PressureAltitudeNoise::Response& self); -void extract(::microstrain::Buffer& serializer, PressureAltitudeNoise::Response& self); +void insert(::microstrain::Serializer& serializer, const PressureAltitudeNoise::Response& self); +void extract(::microstrain::Serializer& serializer, PressureAltitudeNoise::Response& self); TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise); TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut); @@ -2504,11 +2504,11 @@ struct HardIronOffsetNoise } }; }; -void insert(::microstrain::Buffer& serializer, const HardIronOffsetNoise& self); -void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise& self); +void insert(::microstrain::Serializer& serializer, const HardIronOffsetNoise& self); +void extract(::microstrain::Serializer& serializer, HardIronOffsetNoise& self); -void insert(::microstrain::Buffer& serializer, const HardIronOffsetNoise::Response& self); -void extract(::microstrain::Buffer& serializer, HardIronOffsetNoise::Response& self); +void insert(::microstrain::Serializer& serializer, const HardIronOffsetNoise::Response& self); +void extract(::microstrain::Serializer& serializer, HardIronOffsetNoise::Response& self); TypedResult writeHardIronOffsetNoise(C::mip_interface& device, const float* noise); TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut); @@ -2586,11 +2586,11 @@ struct SoftIronMatrixNoise } }; }; -void insert(::microstrain::Buffer& serializer, const SoftIronMatrixNoise& self); -void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise& self); +void insert(::microstrain::Serializer& serializer, const SoftIronMatrixNoise& self); +void extract(::microstrain::Serializer& serializer, SoftIronMatrixNoise& self); -void insert(::microstrain::Buffer& serializer, const SoftIronMatrixNoise::Response& self); -void extract(::microstrain::Buffer& serializer, SoftIronMatrixNoise::Response& self); +void insert(::microstrain::Serializer& serializer, const SoftIronMatrixNoise::Response& self); +void extract(::microstrain::Serializer& serializer, SoftIronMatrixNoise::Response& self); TypedResult writeSoftIronMatrixNoise(C::mip_interface& device, const float* noise); TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut); @@ -2668,11 +2668,11 @@ struct MagNoise } }; }; -void insert(::microstrain::Buffer& serializer, const MagNoise& self); -void extract(::microstrain::Buffer& serializer, MagNoise& self); +void insert(::microstrain::Serializer& serializer, const MagNoise& self); +void extract(::microstrain::Serializer& serializer, MagNoise& self); -void insert(::microstrain::Buffer& serializer, const MagNoise::Response& self); -void extract(::microstrain::Buffer& serializer, MagNoise::Response& self); +void insert(::microstrain::Serializer& serializer, const MagNoise::Response& self); +void extract(::microstrain::Serializer& serializer, MagNoise::Response& self); TypedResult writeMagNoise(C::mip_interface& device, const float* noise); TypedResult readMagNoise(C::mip_interface& device, float* noiseOut); @@ -2750,11 +2750,11 @@ struct InclinationSource } }; }; -void insert(::microstrain::Buffer& serializer, const InclinationSource& self); -void extract(::microstrain::Buffer& serializer, InclinationSource& self); +void insert(::microstrain::Serializer& serializer, const InclinationSource& self); +void extract(::microstrain::Serializer& serializer, InclinationSource& self); -void insert(::microstrain::Buffer& serializer, const InclinationSource::Response& self); -void extract(::microstrain::Buffer& serializer, InclinationSource::Response& self); +void insert(::microstrain::Serializer& serializer, const InclinationSource::Response& self); +void extract(::microstrain::Serializer& serializer, InclinationSource::Response& self); TypedResult writeInclinationSource(C::mip_interface& device, FilterMagParamSource source, float inclination); TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut); @@ -2832,11 +2832,11 @@ struct MagneticDeclinationSource } }; }; -void insert(::microstrain::Buffer& serializer, const MagneticDeclinationSource& self); -void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource& self); +void insert(::microstrain::Serializer& serializer, const MagneticDeclinationSource& self); +void extract(::microstrain::Serializer& serializer, MagneticDeclinationSource& self); -void insert(::microstrain::Buffer& serializer, const MagneticDeclinationSource::Response& self); -void extract(::microstrain::Buffer& serializer, MagneticDeclinationSource::Response& self); +void insert(::microstrain::Serializer& serializer, const MagneticDeclinationSource::Response& self); +void extract(::microstrain::Serializer& serializer, MagneticDeclinationSource::Response& self); TypedResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource source, float declination); TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut); @@ -2913,11 +2913,11 @@ struct MagFieldMagnitudeSource } }; }; -void insert(::microstrain::Buffer& serializer, const MagFieldMagnitudeSource& self); -void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource& self); +void insert(::microstrain::Serializer& serializer, const MagFieldMagnitudeSource& self); +void extract(::microstrain::Serializer& serializer, MagFieldMagnitudeSource& self); -void insert(::microstrain::Buffer& serializer, const MagFieldMagnitudeSource::Response& self); -void extract(::microstrain::Buffer& serializer, MagFieldMagnitudeSource::Response& self); +void insert(::microstrain::Serializer& serializer, const MagFieldMagnitudeSource::Response& self); +void extract(::microstrain::Serializer& serializer, MagFieldMagnitudeSource::Response& self); TypedResult writeMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource source, float magnitude); TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut); @@ -2998,11 +2998,11 @@ struct ReferencePosition } }; }; -void insert(::microstrain::Buffer& serializer, const ReferencePosition& self); -void extract(::microstrain::Buffer& serializer, ReferencePosition& self); +void insert(::microstrain::Serializer& serializer, const ReferencePosition& self); +void extract(::microstrain::Serializer& serializer, ReferencePosition& self); -void insert(::microstrain::Buffer& serializer, const ReferencePosition::Response& self); -void extract(::microstrain::Buffer& serializer, ReferencePosition::Response& self); +void insert(::microstrain::Serializer& serializer, const ReferencePosition::Response& self); +void extract(::microstrain::Serializer& serializer, ReferencePosition::Response& self); TypedResult writeReferencePosition(C::mip_interface& device, bool enable, double latitude, double longitude, double altitude); TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut); @@ -3099,11 +3099,11 @@ struct AccelMagnitudeErrorAdaptiveMeasurement } }; }; -void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self); -void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self); +void insert(::microstrain::Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self); +void extract(::microstrain::Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self); -void insert(::microstrain::Buffer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self); -void extract(::microstrain::Buffer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self); +void insert(::microstrain::Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self); +void extract(::microstrain::Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self); TypedResult writeAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty); TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut); @@ -3195,11 +3195,11 @@ struct MagMagnitudeErrorAdaptiveMeasurement } }; }; -void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self); -void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self); +void insert(::microstrain::Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self); +void extract(::microstrain::Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self); -void insert(::microstrain::Buffer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self); -void extract(::microstrain::Buffer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self); +void insert(::microstrain::Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self); +void extract(::microstrain::Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self); TypedResult writeMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty); TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut); @@ -3289,11 +3289,11 @@ struct MagDipAngleErrorAdaptiveMeasurement } }; }; -void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self); -void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurement& self); +void insert(::microstrain::Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self); +void extract(::microstrain::Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement& self); -void insert(::microstrain::Buffer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self); -void extract(::microstrain::Buffer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self); +void insert(::microstrain::Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self); +void extract(::microstrain::Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self); TypedResult writeMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool enable, float frequency, float highLimit, float highLimitUncertainty, float minimumUncertainty); TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut); @@ -3384,11 +3384,11 @@ struct AidingMeasurementEnable } }; }; -void insert(::microstrain::Buffer& serializer, const AidingMeasurementEnable& self); -void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable& self); +void insert(::microstrain::Serializer& serializer, const AidingMeasurementEnable& self); +void extract(::microstrain::Serializer& serializer, AidingMeasurementEnable& self); -void insert(::microstrain::Buffer& serializer, const AidingMeasurementEnable::Response& self); -void extract(::microstrain::Buffer& serializer, AidingMeasurementEnable::Response& self); +void insert(::microstrain::Serializer& serializer, const AidingMeasurementEnable::Response& self); +void extract(::microstrain::Serializer& serializer, AidingMeasurementEnable::Response& self); TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable); TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut); @@ -3429,8 +3429,8 @@ struct Run } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const Run& self); -void extract(::microstrain::Buffer& serializer, Run& self); +void insert(::microstrain::Serializer& serializer, const Run& self); +void extract(::microstrain::Serializer& serializer, Run& self); TypedResult run(C::mip_interface& device); @@ -3504,11 +3504,11 @@ struct KinematicConstraint } }; }; -void insert(::microstrain::Buffer& serializer, const KinematicConstraint& self); -void extract(::microstrain::Buffer& serializer, KinematicConstraint& self); +void insert(::microstrain::Serializer& serializer, const KinematicConstraint& self); +void extract(::microstrain::Serializer& serializer, KinematicConstraint& self); -void insert(::microstrain::Buffer& serializer, const KinematicConstraint::Response& self); -void extract(::microstrain::Buffer& serializer, KinematicConstraint::Response& self); +void insert(::microstrain::Serializer& serializer, const KinematicConstraint::Response& self); +void extract(::microstrain::Serializer& serializer, KinematicConstraint::Response& self); TypedResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection); TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut); @@ -3642,11 +3642,11 @@ struct InitializationConfiguration } }; }; -void insert(::microstrain::Buffer& serializer, const InitializationConfiguration& self); -void extract(::microstrain::Buffer& serializer, InitializationConfiguration& self); +void insert(::microstrain::Serializer& serializer, const InitializationConfiguration& self); +void extract(::microstrain::Serializer& serializer, InitializationConfiguration& self); -void insert(::microstrain::Buffer& serializer, const InitializationConfiguration::Response& self); -void extract(::microstrain::Buffer& serializer, InitializationConfiguration::Response& self); +void insert(::microstrain::Serializer& serializer, const InitializationConfiguration::Response& self); +void extract(::microstrain::Serializer& serializer, InitializationConfiguration::Response& self); TypedResult writeInitializationConfiguration(C::mip_interface& device, uint8_t waitForRunCommand, InitializationConfiguration::InitialConditionSource initialCondSrc, InitializationConfiguration::AlignmentSelector autoHeadingAlignmentSelector, float initialHeading, float initialPitch, float initialRoll, const float* initialPosition, const float* initialVelocity, FilterReferenceFrame referenceFrameSelector); TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut); @@ -3720,11 +3720,11 @@ struct AdaptiveFilterOptions } }; }; -void insert(::microstrain::Buffer& serializer, const AdaptiveFilterOptions& self); -void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions& self); +void insert(::microstrain::Serializer& serializer, const AdaptiveFilterOptions& self); +void extract(::microstrain::Serializer& serializer, AdaptiveFilterOptions& self); -void insert(::microstrain::Buffer& serializer, const AdaptiveFilterOptions::Response& self); -void extract(::microstrain::Buffer& serializer, AdaptiveFilterOptions::Response& self); +void insert(::microstrain::Serializer& serializer, const AdaptiveFilterOptions::Response& self); +void extract(::microstrain::Serializer& serializer, AdaptiveFilterOptions::Response& self); TypedResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit); TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut); @@ -3802,11 +3802,11 @@ struct MultiAntennaOffset } }; }; -void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset& self); -void extract(::microstrain::Buffer& serializer, MultiAntennaOffset& self); +void insert(::microstrain::Serializer& serializer, const MultiAntennaOffset& self); +void extract(::microstrain::Serializer& serializer, MultiAntennaOffset& self); -void insert(::microstrain::Buffer& serializer, const MultiAntennaOffset::Response& self); -void extract(::microstrain::Buffer& serializer, MultiAntennaOffset::Response& self); +void insert(::microstrain::Serializer& serializer, const MultiAntennaOffset::Response& self); +void extract(::microstrain::Serializer& serializer, MultiAntennaOffset::Response& self); TypedResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset); TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut); @@ -3882,11 +3882,11 @@ struct RelPosConfiguration } }; }; -void insert(::microstrain::Buffer& serializer, const RelPosConfiguration& self); -void extract(::microstrain::Buffer& serializer, RelPosConfiguration& self); +void insert(::microstrain::Serializer& serializer, const RelPosConfiguration& self); +void extract(::microstrain::Serializer& serializer, RelPosConfiguration& self); -void insert(::microstrain::Buffer& serializer, const RelPosConfiguration::Response& self); -void extract(::microstrain::Buffer& serializer, RelPosConfiguration::Response& self); +void insert(::microstrain::Serializer& serializer, const RelPosConfiguration::Response& self); +void extract(::microstrain::Serializer& serializer, RelPosConfiguration::Response& self); TypedResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates); TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut); @@ -3972,11 +3972,11 @@ struct RefPointLeverArm } }; }; -void insert(::microstrain::Buffer& serializer, const RefPointLeverArm& self); -void extract(::microstrain::Buffer& serializer, RefPointLeverArm& self); +void insert(::microstrain::Serializer& serializer, const RefPointLeverArm& self); +void extract(::microstrain::Serializer& serializer, RefPointLeverArm& self); -void insert(::microstrain::Buffer& serializer, const RefPointLeverArm::Response& self); -void extract(::microstrain::Buffer& serializer, RefPointLeverArm::Response& self); +void insert(::microstrain::Serializer& serializer, const RefPointLeverArm::Response& self); +void extract(::microstrain::Serializer& serializer, RefPointLeverArm::Response& self); TypedResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset); TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut); @@ -4021,8 +4021,8 @@ struct SpeedMeasurement } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const SpeedMeasurement& self); -void extract(::microstrain::Buffer& serializer, SpeedMeasurement& self); +void insert(::microstrain::Serializer& serializer, const SpeedMeasurement& self); +void extract(::microstrain::Serializer& serializer, SpeedMeasurement& self); TypedResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty); @@ -4099,11 +4099,11 @@ struct SpeedLeverArm } }; }; -void insert(::microstrain::Buffer& serializer, const SpeedLeverArm& self); -void extract(::microstrain::Buffer& serializer, SpeedLeverArm& self); +void insert(::microstrain::Serializer& serializer, const SpeedLeverArm& self); +void extract(::microstrain::Serializer& serializer, SpeedLeverArm& self); -void insert(::microstrain::Buffer& serializer, const SpeedLeverArm::Response& self); -void extract(::microstrain::Buffer& serializer, SpeedLeverArm::Response& self); +void insert(::microstrain::Serializer& serializer, const SpeedLeverArm::Response& self); +void extract(::microstrain::Serializer& serializer, SpeedLeverArm::Response& self); TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset); TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut); @@ -4181,11 +4181,11 @@ struct WheeledVehicleConstraintControl } }; }; -void insert(::microstrain::Buffer& serializer, const WheeledVehicleConstraintControl& self); -void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl& self); +void insert(::microstrain::Serializer& serializer, const WheeledVehicleConstraintControl& self); +void extract(::microstrain::Serializer& serializer, WheeledVehicleConstraintControl& self); -void insert(::microstrain::Buffer& serializer, const WheeledVehicleConstraintControl::Response& self); -void extract(::microstrain::Buffer& serializer, WheeledVehicleConstraintControl::Response& self); +void insert(::microstrain::Serializer& serializer, const WheeledVehicleConstraintControl::Response& self); +void extract(::microstrain::Serializer& serializer, WheeledVehicleConstraintControl::Response& self); TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable); TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut); @@ -4261,11 +4261,11 @@ struct VerticalGyroConstraintControl } }; }; -void insert(::microstrain::Buffer& serializer, const VerticalGyroConstraintControl& self); -void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl& self); +void insert(::microstrain::Serializer& serializer, const VerticalGyroConstraintControl& self); +void extract(::microstrain::Serializer& serializer, VerticalGyroConstraintControl& self); -void insert(::microstrain::Buffer& serializer, const VerticalGyroConstraintControl::Response& self); -void extract(::microstrain::Buffer& serializer, VerticalGyroConstraintControl::Response& self); +void insert(::microstrain::Serializer& serializer, const VerticalGyroConstraintControl::Response& self); +void extract(::microstrain::Serializer& serializer, VerticalGyroConstraintControl::Response& self); TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable); TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut); @@ -4341,11 +4341,11 @@ struct GnssAntennaCalControl } }; }; -void insert(::microstrain::Buffer& serializer, const GnssAntennaCalControl& self); -void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl& self); +void insert(::microstrain::Serializer& serializer, const GnssAntennaCalControl& self); +void extract(::microstrain::Serializer& serializer, GnssAntennaCalControl& self); -void insert(::microstrain::Buffer& serializer, const GnssAntennaCalControl::Response& self); -void extract(::microstrain::Buffer& serializer, GnssAntennaCalControl::Response& self); +void insert(::microstrain::Serializer& serializer, const GnssAntennaCalControl::Response& self); +void extract(::microstrain::Serializer& serializer, GnssAntennaCalControl::Response& self); TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset); TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut); @@ -4388,8 +4388,8 @@ struct SetInitialHeading } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const SetInitialHeading& self); -void extract(::microstrain::Buffer& serializer, SetInitialHeading& self); +void insert(::microstrain::Serializer& serializer, const SetInitialHeading& self); +void extract(::microstrain::Serializer& serializer, SetInitialHeading& self); TypedResult setInitialHeading(C::mip_interface& device, float heading); diff --git a/src/mip/definitions/commands_gnss.cpp b/src/mip/definitions/commands_gnss.cpp index ead46ca62..39fa58778 100644 --- a/src/mip/definitions/commands_gnss.cpp +++ b/src/mip/definitions/commands_gnss.cpp @@ -1,7 +1,7 @@ #include "commands_gnss.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -29,18 +29,18 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const ReceiverInfo& self) +void insert(::microstrain::Serializer& serializer, const ReceiverInfo& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, ReceiverInfo& self) +void extract(::microstrain::Serializer& serializer, ReceiverInfo& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Response& self) +void insert(::microstrain::Serializer& serializer, const ReceiverInfo::Response& self) { insert(serializer, self.num_receivers); @@ -48,7 +48,7 @@ void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Response& sel insert(serializer, self.receiver_info[i]); } -void extract(::microstrain::Buffer& serializer, ReceiverInfo::Response& self) +void extract(::microstrain::Serializer& serializer, ReceiverInfo::Response& self) { extract_count(serializer, &self.num_receivers, sizeof(self.receiver_info)/sizeof(self.receiver_info[0])); for(unsigned int i=0; i < self.num_receivers; i++) @@ -56,7 +56,7 @@ void extract(::microstrain::Buffer& serializer, ReceiverInfo::Response& self) } -void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Info& self) +void insert(::microstrain::Serializer& serializer, const ReceiverInfo::Info& self) { insert(serializer, self.receiver_id); @@ -66,7 +66,7 @@ void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Info& self) insert(serializer, self.description[i]); } -void extract(::microstrain::Buffer& serializer, ReceiverInfo::Info& self) +void extract(::microstrain::Serializer& serializer, ReceiverInfo::Info& self) { extract(serializer, self.receiver_id); @@ -86,7 +86,7 @@ TypedResult receiverInfo(C::mip_interface& device, uint8_t* numRec if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); extract_count(deserializer, numReceiversOut, numReceiversOutMax); assert(receiverInfoOut || (numReceiversOut == 0)); @@ -98,7 +98,7 @@ TypedResult receiverInfo(C::mip_interface& device, uint8_t* numRec } return result; } -void insert(::microstrain::Buffer& serializer, const SignalConfiguration& self) +void insert(::microstrain::Serializer& serializer, const SignalConfiguration& self) { insert(serializer, self.function); @@ -117,7 +117,7 @@ void insert(::microstrain::Buffer& serializer, const SignalConfiguration& self) } } -void extract(::microstrain::Buffer& serializer, SignalConfiguration& self) +void extract(::microstrain::Serializer& serializer, SignalConfiguration& self) { extract(serializer, self.function); @@ -137,7 +137,7 @@ void extract(::microstrain::Buffer& serializer, SignalConfiguration& self) } } -void insert(::microstrain::Buffer& serializer, const SignalConfiguration::Response& self) +void insert(::microstrain::Serializer& serializer, const SignalConfiguration::Response& self) { insert(serializer, self.gps_enable); @@ -151,7 +151,7 @@ void insert(::microstrain::Buffer& serializer, const SignalConfiguration::Respon insert(serializer, self.reserved[i]); } -void extract(::microstrain::Buffer& serializer, SignalConfiguration::Response& self) +void extract(::microstrain::Serializer& serializer, SignalConfiguration::Response& self) { extract(serializer, self.gps_enable); @@ -168,8 +168,8 @@ void extract(::microstrain::Buffer& serializer, SignalConfiguration::Response& s TypedResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, gpsEnable); @@ -190,8 +190,8 @@ TypedResult writeSignalConfiguration(C::mip_interface& devi } TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -201,7 +201,7 @@ TypedResult readSignalConfiguration(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(gpsEnableOut); extract(deserializer, *gpsEnableOut); @@ -226,8 +226,8 @@ TypedResult readSignalConfiguration(C::mip_interface& devic } TypedResult saveSignalConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -236,8 +236,8 @@ TypedResult saveSignalConfiguration(C::mip_interface& devic } TypedResult loadSignalConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -246,15 +246,15 @@ TypedResult loadSignalConfiguration(C::mip_interface& devic } TypedResult defaultSignalConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration& self) +void insert(::microstrain::Serializer& serializer, const RtkDongleConfiguration& self) { insert(serializer, self.function); @@ -267,7 +267,7 @@ void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration& sel } } -void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration& self) +void extract(::microstrain::Serializer& serializer, RtkDongleConfiguration& self) { extract(serializer, self.function); @@ -281,7 +281,7 @@ void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration& self) } } -void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration::Response& self) +void insert(::microstrain::Serializer& serializer, const RtkDongleConfiguration::Response& self) { insert(serializer, self.enable); @@ -289,7 +289,7 @@ void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration::Res insert(serializer, self.reserved[i]); } -void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration::Response& self) +void extract(::microstrain::Serializer& serializer, RtkDongleConfiguration::Response& self) { extract(serializer, self.enable); @@ -300,8 +300,8 @@ void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration::Response TypedResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, enable); @@ -316,8 +316,8 @@ TypedResult writeRtkDongleConfiguration(C::mip_interface } TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -327,7 +327,7 @@ TypedResult readRtkDongleConfiguration(C::mip_interface& if( result == CmdResult::ACK_OK ) { - ::microstrain::Buffer deserializer(buffer, responseLength); + ::microstrain::Serializer deserializer(buffer, responseLength); assert(enableOut); extract(deserializer, *enableOut); @@ -343,8 +343,8 @@ TypedResult readRtkDongleConfiguration(C::mip_interface& } TypedResult saveRtkDongleConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -353,8 +353,8 @@ TypedResult saveRtkDongleConfiguration(C::mip_interface& } TypedResult loadRtkDongleConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -363,8 +363,8 @@ TypedResult loadRtkDongleConfiguration(C::mip_interface& } TypedResult defaultRtkDongleConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + ::microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); diff --git a/src/mip/definitions/commands_gnss.hpp b/src/mip/definitions/commands_gnss.hpp index 6eeb5e109..a30014d49 100644 --- a/src/mip/definitions/commands_gnss.hpp +++ b/src/mip/definitions/commands_gnss.hpp @@ -114,14 +114,14 @@ struct ReceiverInfo } }; }; -void insert(::microstrain::Buffer& serializer, const ReceiverInfo& self); -void extract(::microstrain::Buffer& serializer, ReceiverInfo& self); +void insert(::microstrain::Serializer& serializer, const ReceiverInfo& self); +void extract(::microstrain::Serializer& serializer, ReceiverInfo& self); -void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Info& self); -void extract(::microstrain::Buffer& serializer, ReceiverInfo::Info& self); +void insert(::microstrain::Serializer& serializer, const ReceiverInfo::Info& self); +void extract(::microstrain::Serializer& serializer, ReceiverInfo::Info& self); -void insert(::microstrain::Buffer& serializer, const ReceiverInfo::Response& self); -void extract(::microstrain::Buffer& serializer, ReceiverInfo::Response& self); +void insert(::microstrain::Serializer& serializer, const ReceiverInfo::Response& self); +void extract(::microstrain::Serializer& serializer, ReceiverInfo::Response& self); TypedResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8_t numReceiversOutMax, ReceiverInfo::Info* receiverInfoOut); @@ -198,11 +198,11 @@ struct SignalConfiguration } }; }; -void insert(::microstrain::Buffer& serializer, const SignalConfiguration& self); -void extract(::microstrain::Buffer& serializer, SignalConfiguration& self); +void insert(::microstrain::Serializer& serializer, const SignalConfiguration& self); +void extract(::microstrain::Serializer& serializer, SignalConfiguration& self); -void insert(::microstrain::Buffer& serializer, const SignalConfiguration::Response& self); -void extract(::microstrain::Buffer& serializer, SignalConfiguration::Response& self); +void insert(::microstrain::Serializer& serializer, const SignalConfiguration::Response& self); +void extract(::microstrain::Serializer& serializer, SignalConfiguration::Response& self); TypedResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved); TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut); @@ -277,11 +277,11 @@ struct RtkDongleConfiguration } }; }; -void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration& self); -void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration& self); +void insert(::microstrain::Serializer& serializer, const RtkDongleConfiguration& self); +void extract(::microstrain::Serializer& serializer, RtkDongleConfiguration& self); -void insert(::microstrain::Buffer& serializer, const RtkDongleConfiguration::Response& self); -void extract(::microstrain::Buffer& serializer, RtkDongleConfiguration::Response& self); +void insert(::microstrain::Serializer& serializer, const RtkDongleConfiguration::Response& self); +void extract(::microstrain::Serializer& serializer, RtkDongleConfiguration::Response& self); TypedResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved); TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut); diff --git a/src/mip/definitions/commands_rtk.cpp b/src/mip/definitions/commands_rtk.cpp index 6333fa2df..147c7f1aa 100644 --- a/src/mip/definitions/commands_rtk.cpp +++ b/src/mip/definitions/commands_rtk.cpp @@ -1,7 +1,7 @@ #include "commands_rtk.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -29,23 +29,23 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const GetStatusFlags& self) +void insert(::microstrain::Serializer& serializer, const GetStatusFlags& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetStatusFlags& self) +void extract(::microstrain::Serializer& serializer, GetStatusFlags& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetStatusFlags::Response& self) +void insert(::microstrain::Serializer& serializer, const GetStatusFlags::Response& self) { insert(serializer, self.flags); } -void extract(::microstrain::Buffer& serializer, GetStatusFlags::Response& self) +void extract(::microstrain::Serializer& serializer, GetStatusFlags::Response& self) { extract(serializer, self.flags); @@ -60,7 +60,7 @@ TypedResult getStatusFlags(C::mip_interface& device, GetStatusFl if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(flagsOut); extract(deserializer, *flagsOut); @@ -70,24 +70,24 @@ TypedResult getStatusFlags(C::mip_interface& device, GetStatusFl } return result; } -void insert(::microstrain::Buffer& serializer, const GetImei& self) +void insert(::microstrain::Serializer& serializer, const GetImei& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetImei& self) +void extract(::microstrain::Serializer& serializer, GetImei& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetImei::Response& self) +void insert(::microstrain::Serializer& serializer, const GetImei::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.IMEI[i]); } -void extract(::microstrain::Buffer& serializer, GetImei::Response& self) +void extract(::microstrain::Serializer& serializer, GetImei::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.IMEI[i]); @@ -103,7 +103,7 @@ TypedResult getImei(C::mip_interface& device, char* imeiOut) if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(imeiOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -114,24 +114,24 @@ TypedResult getImei(C::mip_interface& device, char* imeiOut) } return result; } -void insert(::microstrain::Buffer& serializer, const GetImsi& self) +void insert(::microstrain::Serializer& serializer, const GetImsi& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetImsi& self) +void extract(::microstrain::Serializer& serializer, GetImsi& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetImsi::Response& self) +void insert(::microstrain::Serializer& serializer, const GetImsi::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.IMSI[i]); } -void extract(::microstrain::Buffer& serializer, GetImsi::Response& self) +void extract(::microstrain::Serializer& serializer, GetImsi::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.IMSI[i]); @@ -147,7 +147,7 @@ TypedResult getImsi(C::mip_interface& device, char* imsiOut) if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(imsiOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -158,24 +158,24 @@ TypedResult getImsi(C::mip_interface& device, char* imsiOut) } return result; } -void insert(::microstrain::Buffer& serializer, const GetIccid& self) +void insert(::microstrain::Serializer& serializer, const GetIccid& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetIccid& self) +void extract(::microstrain::Serializer& serializer, GetIccid& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetIccid::Response& self) +void insert(::microstrain::Serializer& serializer, const GetIccid::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.ICCID[i]); } -void extract(::microstrain::Buffer& serializer, GetIccid::Response& self) +void extract(::microstrain::Serializer& serializer, GetIccid::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.ICCID[i]); @@ -191,7 +191,7 @@ TypedResult getIccid(C::mip_interface& device, char* iccidOut) if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(iccidOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -202,7 +202,7 @@ TypedResult getIccid(C::mip_interface& device, char* iccidOut) } return result; } -void insert(::microstrain::Buffer& serializer, const ConnectedDeviceType& self) +void insert(::microstrain::Serializer& serializer, const ConnectedDeviceType& self) { insert(serializer, self.function); @@ -212,7 +212,7 @@ void insert(::microstrain::Buffer& serializer, const ConnectedDeviceType& self) } } -void extract(::microstrain::Buffer& serializer, ConnectedDeviceType& self) +void extract(::microstrain::Serializer& serializer, ConnectedDeviceType& self) { extract(serializer, self.function); @@ -223,12 +223,12 @@ void extract(::microstrain::Buffer& serializer, ConnectedDeviceType& self) } } -void insert(::microstrain::Buffer& serializer, const ConnectedDeviceType::Response& self) +void insert(::microstrain::Serializer& serializer, const ConnectedDeviceType::Response& self) { insert(serializer, self.devType); } -void extract(::microstrain::Buffer& serializer, ConnectedDeviceType::Response& self) +void extract(::microstrain::Serializer& serializer, ConnectedDeviceType::Response& self) { extract(serializer, self.devType); @@ -236,8 +236,8 @@ void extract(::microstrain::Buffer& serializer, ConnectedDeviceType::Response& s TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, devtype); @@ -248,8 +248,8 @@ TypedResult writeConnectedDeviceType(C::mip_interface& devi } TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -259,7 +259,7 @@ TypedResult readConnectedDeviceType(C::mip_interface& devic if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(devtypeOut); extract(deserializer, *devtypeOut); @@ -271,8 +271,8 @@ TypedResult readConnectedDeviceType(C::mip_interface& devic } TypedResult saveConnectedDeviceType(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::SAVE); assert(serializer.isOk()); @@ -281,8 +281,8 @@ TypedResult saveConnectedDeviceType(C::mip_interface& devic } TypedResult loadConnectedDeviceType(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::LOAD); assert(serializer.isOk()); @@ -291,32 +291,32 @@ TypedResult loadConnectedDeviceType(C::mip_interface& devic } TypedResult defaultConnectedDeviceType(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const GetActCode& self) +void insert(::microstrain::Serializer& serializer, const GetActCode& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetActCode& self) +void extract(::microstrain::Serializer& serializer, GetActCode& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetActCode::Response& self) +void insert(::microstrain::Serializer& serializer, const GetActCode::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.ActivationCode[i]); } -void extract(::microstrain::Buffer& serializer, GetActCode::Response& self) +void extract(::microstrain::Serializer& serializer, GetActCode::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.ActivationCode[i]); @@ -332,7 +332,7 @@ TypedResult getActCode(C::mip_interface& device, char* activationcod if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(activationcodeOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -343,24 +343,24 @@ TypedResult getActCode(C::mip_interface& device, char* activationcod } return result; } -void insert(::microstrain::Buffer& serializer, const GetModemFirmwareVersion& self) +void insert(::microstrain::Serializer& serializer, const GetModemFirmwareVersion& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetModemFirmwareVersion& self) +void extract(::microstrain::Serializer& serializer, GetModemFirmwareVersion& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetModemFirmwareVersion::Response& self) +void insert(::microstrain::Serializer& serializer, const GetModemFirmwareVersion::Response& self) { for(unsigned int i=0; i < 32; i++) insert(serializer, self.ModemFirmwareVersion[i]); } -void extract(::microstrain::Buffer& serializer, GetModemFirmwareVersion::Response& self) +void extract(::microstrain::Serializer& serializer, GetModemFirmwareVersion::Response& self) { for(unsigned int i=0; i < 32; i++) extract(serializer, self.ModemFirmwareVersion[i]); @@ -376,7 +376,7 @@ TypedResult getModemFirmwareVersion(C::mip_interface& d if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(modemfirmwareversionOut || (32 == 0)); for(unsigned int i=0; i < 32; i++) @@ -387,18 +387,18 @@ TypedResult getModemFirmwareVersion(C::mip_interface& d } return result; } -void insert(::microstrain::Buffer& serializer, const GetRssi& self) +void insert(::microstrain::Serializer& serializer, const GetRssi& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, GetRssi& self) +void extract(::microstrain::Serializer& serializer, GetRssi& self) { (void)serializer; (void)self; } -void insert(::microstrain::Buffer& serializer, const GetRssi::Response& self) +void insert(::microstrain::Serializer& serializer, const GetRssi::Response& self) { insert(serializer, self.valid); @@ -407,7 +407,7 @@ void insert(::microstrain::Buffer& serializer, const GetRssi::Response& self) insert(serializer, self.signalQuality); } -void extract(::microstrain::Buffer& serializer, GetRssi::Response& self) +void extract(::microstrain::Serializer& serializer, GetRssi::Response& self) { extract(serializer, self.valid); @@ -426,7 +426,7 @@ TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(validOut); extract(deserializer, *validOut); @@ -442,14 +442,14 @@ TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* } return result; } -void insert(::microstrain::Buffer& serializer, const ServiceStatus& self) +void insert(::microstrain::Serializer& serializer, const ServiceStatus& self) { insert(serializer, self.reserved1); insert(serializer, self.reserved2); } -void extract(::microstrain::Buffer& serializer, ServiceStatus& self) +void extract(::microstrain::Serializer& serializer, ServiceStatus& self) { extract(serializer, self.reserved1); @@ -457,7 +457,7 @@ void extract(::microstrain::Buffer& serializer, ServiceStatus& self) } -void insert(::microstrain::Buffer& serializer, const ServiceStatus::Response& self) +void insert(::microstrain::Serializer& serializer, const ServiceStatus::Response& self) { insert(serializer, self.flags); @@ -468,7 +468,7 @@ void insert(::microstrain::Buffer& serializer, const ServiceStatus::Response& se insert(serializer, self.lastBytesTime); } -void extract(::microstrain::Buffer& serializer, ServiceStatus::Response& self) +void extract(::microstrain::Serializer& serializer, ServiceStatus::Response& self) { extract(serializer, self.flags); @@ -482,8 +482,8 @@ void extract(::microstrain::Buffer& serializer, ServiceStatus::Response& self) TypedResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* receivedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, reserved1); @@ -496,7 +496,7 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(flagsOut); extract(deserializer, *flagsOut); @@ -515,12 +515,12 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese } return result; } -void insert(::microstrain::Buffer& serializer, const ProdEraseStorage& self) +void insert(::microstrain::Serializer& serializer, const ProdEraseStorage& self) { insert(serializer, self.media); } -void extract(::microstrain::Buffer& serializer, ProdEraseStorage& self) +void extract(::microstrain::Serializer& serializer, ProdEraseStorage& self) { extract(serializer, self.media); @@ -528,8 +528,8 @@ void extract(::microstrain::Buffer& serializer, ProdEraseStorage& self) TypedResult prodEraseStorage(C::mip_interface& device, MediaSelector media) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, media); @@ -537,7 +537,7 @@ TypedResult prodEraseStorage(C::mip_interface& device, MediaSe return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PROD_ERASE_STORAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const LedControl& self) +void insert(::microstrain::Serializer& serializer, const LedControl& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.primaryColor[i]); @@ -550,7 +550,7 @@ void insert(::microstrain::Buffer& serializer, const LedControl& self) insert(serializer, self.period); } -void extract(::microstrain::Buffer& serializer, LedControl& self) +void extract(::microstrain::Serializer& serializer, LedControl& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.primaryColor[i]); @@ -566,8 +566,8 @@ void extract(::microstrain::Buffer& serializer, LedControl& self) TypedResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); assert(primarycolor || (3 == 0)); for(unsigned int i=0; i < 3; i++) @@ -585,12 +585,12 @@ TypedResult ledControl(C::mip_interface& device, const uint8_t* prim return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Buffer& serializer, const ModemHardReset& self) +void insert(::microstrain::Serializer& serializer, const ModemHardReset& self) { (void)serializer; (void)self; } -void extract(::microstrain::Buffer& serializer, ModemHardReset& self) +void extract(::microstrain::Serializer& serializer, ModemHardReset& self) { (void)serializer; (void)self; diff --git a/src/mip/definitions/commands_rtk.hpp b/src/mip/definitions/commands_rtk.hpp index 022ba181e..a1b396abb 100644 --- a/src/mip/definitions/commands_rtk.hpp +++ b/src/mip/definitions/commands_rtk.hpp @@ -237,11 +237,11 @@ struct GetStatusFlags } }; }; -void insert(::microstrain::Buffer& serializer, const GetStatusFlags& self); -void extract(::microstrain::Buffer& serializer, GetStatusFlags& self); +void insert(::microstrain::Serializer& serializer, const GetStatusFlags& self); +void extract(::microstrain::Serializer& serializer, GetStatusFlags& self); -void insert(::microstrain::Buffer& serializer, const GetStatusFlags::Response& self); -void extract(::microstrain::Buffer& serializer, GetStatusFlags::Response& self); +void insert(::microstrain::Serializer& serializer, const GetStatusFlags::Response& self); +void extract(::microstrain::Serializer& serializer, GetStatusFlags::Response& self); TypedResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut); @@ -293,11 +293,11 @@ struct GetImei } }; }; -void insert(::microstrain::Buffer& serializer, const GetImei& self); -void extract(::microstrain::Buffer& serializer, GetImei& self); +void insert(::microstrain::Serializer& serializer, const GetImei& self); +void extract(::microstrain::Serializer& serializer, GetImei& self); -void insert(::microstrain::Buffer& serializer, const GetImei::Response& self); -void extract(::microstrain::Buffer& serializer, GetImei::Response& self); +void insert(::microstrain::Serializer& serializer, const GetImei::Response& self); +void extract(::microstrain::Serializer& serializer, GetImei::Response& self); TypedResult getImei(C::mip_interface& device, char* imeiOut); @@ -349,11 +349,11 @@ struct GetImsi } }; }; -void insert(::microstrain::Buffer& serializer, const GetImsi& self); -void extract(::microstrain::Buffer& serializer, GetImsi& self); +void insert(::microstrain::Serializer& serializer, const GetImsi& self); +void extract(::microstrain::Serializer& serializer, GetImsi& self); -void insert(::microstrain::Buffer& serializer, const GetImsi::Response& self); -void extract(::microstrain::Buffer& serializer, GetImsi::Response& self); +void insert(::microstrain::Serializer& serializer, const GetImsi::Response& self); +void extract(::microstrain::Serializer& serializer, GetImsi::Response& self); TypedResult getImsi(C::mip_interface& device, char* imsiOut); @@ -405,11 +405,11 @@ struct GetIccid } }; }; -void insert(::microstrain::Buffer& serializer, const GetIccid& self); -void extract(::microstrain::Buffer& serializer, GetIccid& self); +void insert(::microstrain::Serializer& serializer, const GetIccid& self); +void extract(::microstrain::Serializer& serializer, GetIccid& self); -void insert(::microstrain::Buffer& serializer, const GetIccid::Response& self); -void extract(::microstrain::Buffer& serializer, GetIccid::Response& self); +void insert(::microstrain::Serializer& serializer, const GetIccid::Response& self); +void extract(::microstrain::Serializer& serializer, GetIccid::Response& self); TypedResult getIccid(C::mip_interface& device, char* iccidOut); @@ -482,11 +482,11 @@ struct ConnectedDeviceType } }; }; -void insert(::microstrain::Buffer& serializer, const ConnectedDeviceType& self); -void extract(::microstrain::Buffer& serializer, ConnectedDeviceType& self); +void insert(::microstrain::Serializer& serializer, const ConnectedDeviceType& self); +void extract(::microstrain::Serializer& serializer, ConnectedDeviceType& self); -void insert(::microstrain::Buffer& serializer, const ConnectedDeviceType::Response& self); -void extract(::microstrain::Buffer& serializer, ConnectedDeviceType::Response& self); +void insert(::microstrain::Serializer& serializer, const ConnectedDeviceType::Response& self); +void extract(::microstrain::Serializer& serializer, ConnectedDeviceType::Response& self); TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype); TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut); @@ -542,11 +542,11 @@ struct GetActCode } }; }; -void insert(::microstrain::Buffer& serializer, const GetActCode& self); -void extract(::microstrain::Buffer& serializer, GetActCode& self); +void insert(::microstrain::Serializer& serializer, const GetActCode& self); +void extract(::microstrain::Serializer& serializer, GetActCode& self); -void insert(::microstrain::Buffer& serializer, const GetActCode::Response& self); -void extract(::microstrain::Buffer& serializer, GetActCode::Response& self); +void insert(::microstrain::Serializer& serializer, const GetActCode::Response& self); +void extract(::microstrain::Serializer& serializer, GetActCode::Response& self); TypedResult getActCode(C::mip_interface& device, char* activationcodeOut); @@ -598,11 +598,11 @@ struct GetModemFirmwareVersion } }; }; -void insert(::microstrain::Buffer& serializer, const GetModemFirmwareVersion& self); -void extract(::microstrain::Buffer& serializer, GetModemFirmwareVersion& self); +void insert(::microstrain::Serializer& serializer, const GetModemFirmwareVersion& self); +void extract(::microstrain::Serializer& serializer, GetModemFirmwareVersion& self); -void insert(::microstrain::Buffer& serializer, const GetModemFirmwareVersion::Response& self); -void extract(::microstrain::Buffer& serializer, GetModemFirmwareVersion::Response& self); +void insert(::microstrain::Serializer& serializer, const GetModemFirmwareVersion::Response& self); +void extract(::microstrain::Serializer& serializer, GetModemFirmwareVersion::Response& self); TypedResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut); @@ -657,11 +657,11 @@ struct GetRssi } }; }; -void insert(::microstrain::Buffer& serializer, const GetRssi& self); -void extract(::microstrain::Buffer& serializer, GetRssi& self); +void insert(::microstrain::Serializer& serializer, const GetRssi& self); +void extract(::microstrain::Serializer& serializer, GetRssi& self); -void insert(::microstrain::Buffer& serializer, const GetRssi::Response& self); -void extract(::microstrain::Buffer& serializer, GetRssi::Response& self); +void insert(::microstrain::Serializer& serializer, const GetRssi::Response& self); +void extract(::microstrain::Serializer& serializer, GetRssi::Response& self); TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut); @@ -750,11 +750,11 @@ struct ServiceStatus } }; }; -void insert(::microstrain::Buffer& serializer, const ServiceStatus& self); -void extract(::microstrain::Buffer& serializer, ServiceStatus& self); +void insert(::microstrain::Serializer& serializer, const ServiceStatus& self); +void extract(::microstrain::Serializer& serializer, ServiceStatus& self); -void insert(::microstrain::Buffer& serializer, const ServiceStatus::Response& self); -void extract(::microstrain::Buffer& serializer, ServiceStatus::Response& self); +void insert(::microstrain::Serializer& serializer, const ServiceStatus::Response& self); +void extract(::microstrain::Serializer& serializer, ServiceStatus::Response& self); TypedResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* receivedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut); @@ -791,8 +791,8 @@ struct ProdEraseStorage } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const ProdEraseStorage& self); -void extract(::microstrain::Buffer& serializer, ProdEraseStorage& self); +void insert(::microstrain::Serializer& serializer, const ProdEraseStorage& self); +void extract(::microstrain::Serializer& serializer, ProdEraseStorage& self); TypedResult prodEraseStorage(C::mip_interface& device, MediaSelector media); @@ -831,8 +831,8 @@ struct LedControl } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const LedControl& self); -void extract(::microstrain::Buffer& serializer, LedControl& self); +void insert(::microstrain::Serializer& serializer, const LedControl& self); +void extract(::microstrain::Serializer& serializer, LedControl& self); TypedResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period); @@ -868,8 +868,8 @@ struct ModemHardReset } typedef void Response; }; -void insert(::microstrain::Buffer& serializer, const ModemHardReset& self); -void extract(::microstrain::Buffer& serializer, ModemHardReset& self); +void insert(::microstrain::Serializer& serializer, const ModemHardReset& self); +void extract(::microstrain::Serializer& serializer, ModemHardReset& self); TypedResult modemHardReset(C::mip_interface& device); diff --git a/src/mip/definitions/commands_system.cpp b/src/mip/definitions/commands_system.cpp index ac9257391..4b2988671 100644 --- a/src/mip/definitions/commands_system.cpp +++ b/src/mip/definitions/commands_system.cpp @@ -1,7 +1,7 @@ #include "commands_system.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -29,7 +29,7 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const CommMode& self) +void insert(::microstrain::Serializer& serializer, const CommMode& self) { insert(serializer, self.function); @@ -39,7 +39,7 @@ void insert(::microstrain::Buffer& serializer, const CommMode& self) } } -void extract(::microstrain::Buffer& serializer, CommMode& self) +void extract(::microstrain::Serializer& serializer, CommMode& self) { extract(serializer, self.function); @@ -50,12 +50,12 @@ void extract(::microstrain::Buffer& serializer, CommMode& self) } } -void insert(::microstrain::Buffer& serializer, const CommMode::Response& self) +void insert(::microstrain::Serializer& serializer, const CommMode::Response& self) { insert(serializer, self.mode); } -void extract(::microstrain::Buffer& serializer, CommMode::Response& self) +void extract(::microstrain::Serializer& serializer, CommMode::Response& self) { extract(serializer, self.mode); @@ -63,8 +63,8 @@ void extract(::microstrain::Buffer& serializer, CommMode::Response& self) TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::WRITE); insert(serializer, mode); @@ -75,8 +75,8 @@ TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) } TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::READ); assert(serializer.isOk()); @@ -86,7 +86,7 @@ TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) if( result == CmdResult::ACK_OK ) { - microstrain::Buffer deserializer(buffer, responseLength); + microstrain::Serializer deserializer(buffer, responseLength); assert(modeOut); extract(deserializer, *modeOut); @@ -98,8 +98,8 @@ TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) } TypedResult defaultCommMode(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Buffer serializer(buffer, sizeof(buffer)); + uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain::Serializer serializer(buffer, sizeof(buffer)); insert(serializer, FunctionSelector::RESET); assert(serializer.isOk()); diff --git a/src/mip/definitions/commands_system.hpp b/src/mip/definitions/commands_system.hpp index 402e4657e..5b7eb6f88 100644 --- a/src/mip/definitions/commands_system.hpp +++ b/src/mip/definitions/commands_system.hpp @@ -125,11 +125,11 @@ struct CommMode } }; }; -void insert(::microstrain::Buffer& serializer, const CommMode& self); -void extract(::microstrain::Buffer& serializer, CommMode& self); +void insert(::microstrain::Serializer& serializer, const CommMode& self); +void extract(::microstrain::Serializer& serializer, CommMode& self); -void insert(::microstrain::Buffer& serializer, const CommMode::Response& self); -void extract(::microstrain::Buffer& serializer, CommMode::Response& self); +void insert(::microstrain::Serializer& serializer, const CommMode::Response& self); +void extract(::microstrain::Serializer& serializer, CommMode::Response& self); TypedResult writeCommMode(C::mip_interface& device, uint8_t mode); TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut); diff --git a/src/mip/definitions/common.hpp b/src/mip/definitions/common.hpp index 3706dda96..c5a96240a 100644 --- a/src/mip/definitions/common.hpp +++ b/src/mip/definitions/common.hpp @@ -1,6 +1,6 @@ #pragma once -#include +#include namespace mip @@ -15,8 +15,8 @@ struct DescriptorRate uint16_t decimation; }; -inline size_t insert(microstrain::Buffer& buffer, const DescriptorRate& self) { return buffer.insert(self.descriptor, self.decimation); } -inline size_t extract(microstrain::Buffer& buffer, DescriptorRate& self) { return buffer.extract(self.descriptor, self.decimation); } +inline size_t insert(microstrain::Serializer& buffer, const DescriptorRate& self) { return buffer.insert(self.descriptor, self.decimation); } +inline size_t extract(microstrain::Serializer& buffer, DescriptorRate& self) { return buffer.extract(self.descriptor, self.decimation); } ////////////////////////////////////////////////////////////////////////////////// @@ -114,10 +114,10 @@ using Matrix3d = Vector; using Quatf = Vector4f; template -void insert(::microstrain::Buffer& serializer, const Vector& v) { for(size_t i=0; i& v) { for(size_t i =0; i -void extract(::microstrain::Buffer& serializer, Vector& v) { for(size_t i=0; i& v) { for(size_t i =0; i @@ -29,7 +29,7 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const PositionLlh& self) +void insert(::microstrain::Serializer& serializer, const PositionLlh& self) { insert(serializer, self.latitude); @@ -40,7 +40,7 @@ void insert(::microstrain::Buffer& serializer, const PositionLlh& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, PositionLlh& self) +void extract(::microstrain::Serializer& serializer, PositionLlh& self) { extract(serializer, self.latitude); @@ -52,7 +52,7 @@ void extract(::microstrain::Buffer& serializer, PositionLlh& self) } -void insert(::microstrain::Buffer& serializer, const VelocityNed& self) +void insert(::microstrain::Serializer& serializer, const VelocityNed& self) { insert(serializer, self.north); @@ -63,7 +63,7 @@ void insert(::microstrain::Buffer& serializer, const VelocityNed& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, VelocityNed& self) +void extract(::microstrain::Serializer& serializer, VelocityNed& self) { extract(serializer, self.north); @@ -75,7 +75,7 @@ void extract(::microstrain::Buffer& serializer, VelocityNed& self) } -void insert(::microstrain::Buffer& serializer, const AttitudeQuaternion& self) +void insert(::microstrain::Serializer& serializer, const AttitudeQuaternion& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.q[i]); @@ -83,7 +83,7 @@ void insert(::microstrain::Buffer& serializer, const AttitudeQuaternion& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, AttitudeQuaternion& self) +void extract(::microstrain::Serializer& serializer, AttitudeQuaternion& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.q[i]); @@ -92,7 +92,7 @@ void extract(::microstrain::Buffer& serializer, AttitudeQuaternion& self) } -void insert(::microstrain::Buffer& serializer, const AttitudeDcm& self) +void insert(::microstrain::Serializer& serializer, const AttitudeDcm& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.dcm[i]); @@ -100,7 +100,7 @@ void insert(::microstrain::Buffer& serializer, const AttitudeDcm& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, AttitudeDcm& self) +void extract(::microstrain::Serializer& serializer, AttitudeDcm& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.dcm[i]); @@ -109,7 +109,7 @@ void extract(::microstrain::Buffer& serializer, AttitudeDcm& self) } -void insert(::microstrain::Buffer& serializer, const EulerAngles& self) +void insert(::microstrain::Serializer& serializer, const EulerAngles& self) { insert(serializer, self.roll); @@ -120,7 +120,7 @@ void insert(::microstrain::Buffer& serializer, const EulerAngles& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, EulerAngles& self) +void extract(::microstrain::Serializer& serializer, EulerAngles& self) { extract(serializer, self.roll); @@ -132,7 +132,7 @@ void extract(::microstrain::Buffer& serializer, EulerAngles& self) } -void insert(::microstrain::Buffer& serializer, const GyroBias& self) +void insert(::microstrain::Serializer& serializer, const GyroBias& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); @@ -140,7 +140,7 @@ void insert(::microstrain::Buffer& serializer, const GyroBias& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GyroBias& self) +void extract(::microstrain::Serializer& serializer, GyroBias& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -149,7 +149,7 @@ void extract(::microstrain::Buffer& serializer, GyroBias& self) } -void insert(::microstrain::Buffer& serializer, const AccelBias& self) +void insert(::microstrain::Serializer& serializer, const AccelBias& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); @@ -157,7 +157,7 @@ void insert(::microstrain::Buffer& serializer, const AccelBias& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, AccelBias& self) +void extract(::microstrain::Serializer& serializer, AccelBias& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -166,7 +166,7 @@ void extract(::microstrain::Buffer& serializer, AccelBias& self) } -void insert(::microstrain::Buffer& serializer, const PositionLlhUncertainty& self) +void insert(::microstrain::Serializer& serializer, const PositionLlhUncertainty& self) { insert(serializer, self.north); @@ -177,7 +177,7 @@ void insert(::microstrain::Buffer& serializer, const PositionLlhUncertainty& sel insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, PositionLlhUncertainty& self) +void extract(::microstrain::Serializer& serializer, PositionLlhUncertainty& self) { extract(serializer, self.north); @@ -189,7 +189,7 @@ void extract(::microstrain::Buffer& serializer, PositionLlhUncertainty& self) } -void insert(::microstrain::Buffer& serializer, const VelocityNedUncertainty& self) +void insert(::microstrain::Serializer& serializer, const VelocityNedUncertainty& self) { insert(serializer, self.north); @@ -200,7 +200,7 @@ void insert(::microstrain::Buffer& serializer, const VelocityNedUncertainty& sel insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, VelocityNedUncertainty& self) +void extract(::microstrain::Serializer& serializer, VelocityNedUncertainty& self) { extract(serializer, self.north); @@ -212,7 +212,7 @@ void extract(::microstrain::Buffer& serializer, VelocityNedUncertainty& self) } -void insert(::microstrain::Buffer& serializer, const EulerAnglesUncertainty& self) +void insert(::microstrain::Serializer& serializer, const EulerAnglesUncertainty& self) { insert(serializer, self.roll); @@ -223,7 +223,7 @@ void insert(::microstrain::Buffer& serializer, const EulerAnglesUncertainty& sel insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, EulerAnglesUncertainty& self) +void extract(::microstrain::Serializer& serializer, EulerAnglesUncertainty& self) { extract(serializer, self.roll); @@ -235,7 +235,7 @@ void extract(::microstrain::Buffer& serializer, EulerAnglesUncertainty& self) } -void insert(::microstrain::Buffer& serializer, const GyroBiasUncertainty& self) +void insert(::microstrain::Serializer& serializer, const GyroBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias_uncert[i]); @@ -243,7 +243,7 @@ void insert(::microstrain::Buffer& serializer, const GyroBiasUncertainty& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GyroBiasUncertainty& self) +void extract(::microstrain::Serializer& serializer, GyroBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias_uncert[i]); @@ -252,7 +252,7 @@ void extract(::microstrain::Buffer& serializer, GyroBiasUncertainty& self) } -void insert(::microstrain::Buffer& serializer, const AccelBiasUncertainty& self) +void insert(::microstrain::Serializer& serializer, const AccelBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias_uncert[i]); @@ -260,7 +260,7 @@ void insert(::microstrain::Buffer& serializer, const AccelBiasUncertainty& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, AccelBiasUncertainty& self) +void extract(::microstrain::Serializer& serializer, AccelBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias_uncert[i]); @@ -269,7 +269,7 @@ void extract(::microstrain::Buffer& serializer, AccelBiasUncertainty& self) } -void insert(::microstrain::Buffer& serializer, const Timestamp& self) +void insert(::microstrain::Serializer& serializer, const Timestamp& self) { insert(serializer, self.tow); @@ -278,7 +278,7 @@ void insert(::microstrain::Buffer& serializer, const Timestamp& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, Timestamp& self) +void extract(::microstrain::Serializer& serializer, Timestamp& self) { extract(serializer, self.tow); @@ -288,7 +288,7 @@ void extract(::microstrain::Buffer& serializer, Timestamp& self) } -void insert(::microstrain::Buffer& serializer, const Status& self) +void insert(::microstrain::Serializer& serializer, const Status& self) { insert(serializer, self.filter_state); @@ -297,7 +297,7 @@ void insert(::microstrain::Buffer& serializer, const Status& self) insert(serializer, self.status_flags); } -void extract(::microstrain::Buffer& serializer, Status& self) +void extract(::microstrain::Serializer& serializer, Status& self) { extract(serializer, self.filter_state); @@ -307,7 +307,7 @@ void extract(::microstrain::Buffer& serializer, Status& self) } -void insert(::microstrain::Buffer& serializer, const LinearAccel& self) +void insert(::microstrain::Serializer& serializer, const LinearAccel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.accel[i]); @@ -315,7 +315,7 @@ void insert(::microstrain::Buffer& serializer, const LinearAccel& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, LinearAccel& self) +void extract(::microstrain::Serializer& serializer, LinearAccel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.accel[i]); @@ -324,7 +324,7 @@ void extract(::microstrain::Buffer& serializer, LinearAccel& self) } -void insert(::microstrain::Buffer& serializer, const GravityVector& self) +void insert(::microstrain::Serializer& serializer, const GravityVector& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.gravity[i]); @@ -332,7 +332,7 @@ void insert(::microstrain::Buffer& serializer, const GravityVector& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GravityVector& self) +void extract(::microstrain::Serializer& serializer, GravityVector& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.gravity[i]); @@ -341,7 +341,7 @@ void extract(::microstrain::Buffer& serializer, GravityVector& self) } -void insert(::microstrain::Buffer& serializer, const CompAccel& self) +void insert(::microstrain::Serializer& serializer, const CompAccel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.accel[i]); @@ -349,7 +349,7 @@ void insert(::microstrain::Buffer& serializer, const CompAccel& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, CompAccel& self) +void extract(::microstrain::Serializer& serializer, CompAccel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.accel[i]); @@ -358,7 +358,7 @@ void extract(::microstrain::Buffer& serializer, CompAccel& self) } -void insert(::microstrain::Buffer& serializer, const CompAngularRate& self) +void insert(::microstrain::Serializer& serializer, const CompAngularRate& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.gyro[i]); @@ -366,7 +366,7 @@ void insert(::microstrain::Buffer& serializer, const CompAngularRate& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, CompAngularRate& self) +void extract(::microstrain::Serializer& serializer, CompAngularRate& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.gyro[i]); @@ -375,7 +375,7 @@ void extract(::microstrain::Buffer& serializer, CompAngularRate& self) } -void insert(::microstrain::Buffer& serializer, const QuaternionAttitudeUncertainty& self) +void insert(::microstrain::Serializer& serializer, const QuaternionAttitudeUncertainty& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.q[i]); @@ -383,7 +383,7 @@ void insert(::microstrain::Buffer& serializer, const QuaternionAttitudeUncertain insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, QuaternionAttitudeUncertainty& self) +void extract(::microstrain::Serializer& serializer, QuaternionAttitudeUncertainty& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.q[i]); @@ -392,14 +392,14 @@ void extract(::microstrain::Buffer& serializer, QuaternionAttitudeUncertainty& s } -void insert(::microstrain::Buffer& serializer, const Wgs84GravityMag& self) +void insert(::microstrain::Serializer& serializer, const Wgs84GravityMag& self) { insert(serializer, self.magnitude); insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, Wgs84GravityMag& self) +void extract(::microstrain::Serializer& serializer, Wgs84GravityMag& self) { extract(serializer, self.magnitude); @@ -407,7 +407,7 @@ void extract(::microstrain::Buffer& serializer, Wgs84GravityMag& self) } -void insert(::microstrain::Buffer& serializer, const HeadingUpdateState& self) +void insert(::microstrain::Serializer& serializer, const HeadingUpdateState& self) { insert(serializer, self.heading); @@ -418,7 +418,7 @@ void insert(::microstrain::Buffer& serializer, const HeadingUpdateState& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, HeadingUpdateState& self) +void extract(::microstrain::Serializer& serializer, HeadingUpdateState& self) { extract(serializer, self.heading); @@ -430,7 +430,7 @@ void extract(::microstrain::Buffer& serializer, HeadingUpdateState& self) } -void insert(::microstrain::Buffer& serializer, const MagneticModel& self) +void insert(::microstrain::Serializer& serializer, const MagneticModel& self) { insert(serializer, self.intensity_north); @@ -445,7 +445,7 @@ void insert(::microstrain::Buffer& serializer, const MagneticModel& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagneticModel& self) +void extract(::microstrain::Serializer& serializer, MagneticModel& self) { extract(serializer, self.intensity_north); @@ -461,7 +461,7 @@ void extract(::microstrain::Buffer& serializer, MagneticModel& self) } -void insert(::microstrain::Buffer& serializer, const AccelScaleFactor& self) +void insert(::microstrain::Serializer& serializer, const AccelScaleFactor& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scale_factor[i]); @@ -469,7 +469,7 @@ void insert(::microstrain::Buffer& serializer, const AccelScaleFactor& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, AccelScaleFactor& self) +void extract(::microstrain::Serializer& serializer, AccelScaleFactor& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scale_factor[i]); @@ -478,7 +478,7 @@ void extract(::microstrain::Buffer& serializer, AccelScaleFactor& self) } -void insert(::microstrain::Buffer& serializer, const AccelScaleFactorUncertainty& self) +void insert(::microstrain::Serializer& serializer, const AccelScaleFactorUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scale_factor_uncert[i]); @@ -486,7 +486,7 @@ void insert(::microstrain::Buffer& serializer, const AccelScaleFactorUncertainty insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, AccelScaleFactorUncertainty& self) +void extract(::microstrain::Serializer& serializer, AccelScaleFactorUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scale_factor_uncert[i]); @@ -495,7 +495,7 @@ void extract(::microstrain::Buffer& serializer, AccelScaleFactorUncertainty& sel } -void insert(::microstrain::Buffer& serializer, const GyroScaleFactor& self) +void insert(::microstrain::Serializer& serializer, const GyroScaleFactor& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scale_factor[i]); @@ -503,7 +503,7 @@ void insert(::microstrain::Buffer& serializer, const GyroScaleFactor& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GyroScaleFactor& self) +void extract(::microstrain::Serializer& serializer, GyroScaleFactor& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scale_factor[i]); @@ -512,7 +512,7 @@ void extract(::microstrain::Buffer& serializer, GyroScaleFactor& self) } -void insert(::microstrain::Buffer& serializer, const GyroScaleFactorUncertainty& self) +void insert(::microstrain::Serializer& serializer, const GyroScaleFactorUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scale_factor_uncert[i]); @@ -520,7 +520,7 @@ void insert(::microstrain::Buffer& serializer, const GyroScaleFactorUncertainty& insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GyroScaleFactorUncertainty& self) +void extract(::microstrain::Serializer& serializer, GyroScaleFactorUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scale_factor_uncert[i]); @@ -529,7 +529,7 @@ void extract(::microstrain::Buffer& serializer, GyroScaleFactorUncertainty& self } -void insert(::microstrain::Buffer& serializer, const MagBias& self) +void insert(::microstrain::Serializer& serializer, const MagBias& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias[i]); @@ -537,7 +537,7 @@ void insert(::microstrain::Buffer& serializer, const MagBias& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagBias& self) +void extract(::microstrain::Serializer& serializer, MagBias& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias[i]); @@ -546,7 +546,7 @@ void extract(::microstrain::Buffer& serializer, MagBias& self) } -void insert(::microstrain::Buffer& serializer, const MagBiasUncertainty& self) +void insert(::microstrain::Serializer& serializer, const MagBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.bias_uncert[i]); @@ -554,7 +554,7 @@ void insert(::microstrain::Buffer& serializer, const MagBiasUncertainty& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagBiasUncertainty& self) +void extract(::microstrain::Serializer& serializer, MagBiasUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.bias_uncert[i]); @@ -563,7 +563,7 @@ void extract(::microstrain::Buffer& serializer, MagBiasUncertainty& self) } -void insert(::microstrain::Buffer& serializer, const StandardAtmosphere& self) +void insert(::microstrain::Serializer& serializer, const StandardAtmosphere& self) { insert(serializer, self.geometric_altitude); @@ -578,7 +578,7 @@ void insert(::microstrain::Buffer& serializer, const StandardAtmosphere& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, StandardAtmosphere& self) +void extract(::microstrain::Serializer& serializer, StandardAtmosphere& self) { extract(serializer, self.geometric_altitude); @@ -594,14 +594,14 @@ void extract(::microstrain::Buffer& serializer, StandardAtmosphere& self) } -void insert(::microstrain::Buffer& serializer, const PressureAltitude& self) +void insert(::microstrain::Serializer& serializer, const PressureAltitude& self) { insert(serializer, self.pressure_altitude); insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, PressureAltitude& self) +void extract(::microstrain::Serializer& serializer, PressureAltitude& self) { extract(serializer, self.pressure_altitude); @@ -609,14 +609,14 @@ void extract(::microstrain::Buffer& serializer, PressureAltitude& self) } -void insert(::microstrain::Buffer& serializer, const DensityAltitude& self) +void insert(::microstrain::Serializer& serializer, const DensityAltitude& self) { insert(serializer, self.density_altitude); insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, DensityAltitude& self) +void extract(::microstrain::Serializer& serializer, DensityAltitude& self) { extract(serializer, self.density_altitude); @@ -624,7 +624,7 @@ void extract(::microstrain::Buffer& serializer, DensityAltitude& self) } -void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrection& self) +void insert(::microstrain::Serializer& serializer, const AntennaOffsetCorrection& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset[i]); @@ -632,7 +632,7 @@ void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrection& se insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrection& self) +void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrection& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset[i]); @@ -641,7 +641,7 @@ void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrection& self) } -void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrectionUncertainty& self) +void insert(::microstrain::Serializer& serializer, const AntennaOffsetCorrectionUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.offset_uncert[i]); @@ -649,7 +649,7 @@ void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrectionUnce insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrectionUncertainty& self) +void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrectionUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.offset_uncert[i]); @@ -658,7 +658,7 @@ void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrectionUncertain } -void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrection& self) +void insert(::microstrain::Serializer& serializer, const MultiAntennaOffsetCorrection& self) { insert(serializer, self.receiver_id); @@ -668,7 +668,7 @@ void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrectio insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrection& self) +void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrection& self) { extract(serializer, self.receiver_id); @@ -679,7 +679,7 @@ void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrection& se } -void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self) +void insert(::microstrain::Serializer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self) { insert(serializer, self.receiver_id); @@ -689,7 +689,7 @@ void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrectio insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrectionUncertainty& self) +void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrectionUncertainty& self) { extract(serializer, self.receiver_id); @@ -700,7 +700,7 @@ void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrectionUnce } -void insert(::microstrain::Buffer& serializer, const MagnetometerOffset& self) +void insert(::microstrain::Serializer& serializer, const MagnetometerOffset& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.hard_iron[i]); @@ -708,7 +708,7 @@ void insert(::microstrain::Buffer& serializer, const MagnetometerOffset& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagnetometerOffset& self) +void extract(::microstrain::Serializer& serializer, MagnetometerOffset& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.hard_iron[i]); @@ -717,7 +717,7 @@ void extract(::microstrain::Buffer& serializer, MagnetometerOffset& self) } -void insert(::microstrain::Buffer& serializer, const MagnetometerMatrix& self) +void insert(::microstrain::Serializer& serializer, const MagnetometerMatrix& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.soft_iron[i]); @@ -725,7 +725,7 @@ void insert(::microstrain::Buffer& serializer, const MagnetometerMatrix& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagnetometerMatrix& self) +void extract(::microstrain::Serializer& serializer, MagnetometerMatrix& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.soft_iron[i]); @@ -734,7 +734,7 @@ void extract(::microstrain::Buffer& serializer, MagnetometerMatrix& self) } -void insert(::microstrain::Buffer& serializer, const MagnetometerOffsetUncertainty& self) +void insert(::microstrain::Serializer& serializer, const MagnetometerOffsetUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.hard_iron_uncertainty[i]); @@ -742,7 +742,7 @@ void insert(::microstrain::Buffer& serializer, const MagnetometerOffsetUncertain insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagnetometerOffsetUncertainty& self) +void extract(::microstrain::Serializer& serializer, MagnetometerOffsetUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.hard_iron_uncertainty[i]); @@ -751,7 +751,7 @@ void extract(::microstrain::Buffer& serializer, MagnetometerOffsetUncertainty& s } -void insert(::microstrain::Buffer& serializer, const MagnetometerMatrixUncertainty& self) +void insert(::microstrain::Serializer& serializer, const MagnetometerMatrixUncertainty& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.soft_iron_uncertainty[i]); @@ -759,7 +759,7 @@ void insert(::microstrain::Buffer& serializer, const MagnetometerMatrixUncertain insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagnetometerMatrixUncertainty& self) +void extract(::microstrain::Serializer& serializer, MagnetometerMatrixUncertainty& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.soft_iron_uncertainty[i]); @@ -768,7 +768,7 @@ void extract(::microstrain::Buffer& serializer, MagnetometerMatrixUncertainty& s } -void insert(::microstrain::Buffer& serializer, const MagnetometerCovarianceMatrix& self) +void insert(::microstrain::Serializer& serializer, const MagnetometerCovarianceMatrix& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.covariance[i]); @@ -776,7 +776,7 @@ void insert(::microstrain::Buffer& serializer, const MagnetometerCovarianceMatri insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagnetometerCovarianceMatrix& self) +void extract(::microstrain::Serializer& serializer, MagnetometerCovarianceMatrix& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.covariance[i]); @@ -785,7 +785,7 @@ void extract(::microstrain::Buffer& serializer, MagnetometerCovarianceMatrix& se } -void insert(::microstrain::Buffer& serializer, const MagnetometerResidualVector& self) +void insert(::microstrain::Serializer& serializer, const MagnetometerResidualVector& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.residual[i]); @@ -793,7 +793,7 @@ void insert(::microstrain::Buffer& serializer, const MagnetometerResidualVector& insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, MagnetometerResidualVector& self) +void extract(::microstrain::Serializer& serializer, MagnetometerResidualVector& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.residual[i]); @@ -802,7 +802,7 @@ void extract(::microstrain::Buffer& serializer, MagnetometerResidualVector& self } -void insert(::microstrain::Buffer& serializer, const ClockCorrection& self) +void insert(::microstrain::Serializer& serializer, const ClockCorrection& self) { insert(serializer, self.receiver_id); @@ -813,7 +813,7 @@ void insert(::microstrain::Buffer& serializer, const ClockCorrection& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, ClockCorrection& self) +void extract(::microstrain::Serializer& serializer, ClockCorrection& self) { extract(serializer, self.receiver_id); @@ -825,7 +825,7 @@ void extract(::microstrain::Buffer& serializer, ClockCorrection& self) } -void insert(::microstrain::Buffer& serializer, const ClockCorrectionUncertainty& self) +void insert(::microstrain::Serializer& serializer, const ClockCorrectionUncertainty& self) { insert(serializer, self.receiver_id); @@ -836,7 +836,7 @@ void insert(::microstrain::Buffer& serializer, const ClockCorrectionUncertainty& insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, ClockCorrectionUncertainty& self) +void extract(::microstrain::Serializer& serializer, ClockCorrectionUncertainty& self) { extract(serializer, self.receiver_id); @@ -848,7 +848,7 @@ void extract(::microstrain::Buffer& serializer, ClockCorrectionUncertainty& self } -void insert(::microstrain::Buffer& serializer, const GnssPosAidStatus& self) +void insert(::microstrain::Serializer& serializer, const GnssPosAidStatus& self) { insert(serializer, self.receiver_id); @@ -860,7 +860,7 @@ void insert(::microstrain::Buffer& serializer, const GnssPosAidStatus& self) insert(serializer, self.reserved[i]); } -void extract(::microstrain::Buffer& serializer, GnssPosAidStatus& self) +void extract(::microstrain::Serializer& serializer, GnssPosAidStatus& self) { extract(serializer, self.receiver_id); @@ -873,7 +873,7 @@ void extract(::microstrain::Buffer& serializer, GnssPosAidStatus& self) } -void insert(::microstrain::Buffer& serializer, const GnssAttAidStatus& self) +void insert(::microstrain::Serializer& serializer, const GnssAttAidStatus& self) { insert(serializer, self.time_of_week); @@ -883,7 +883,7 @@ void insert(::microstrain::Buffer& serializer, const GnssAttAidStatus& self) insert(serializer, self.reserved[i]); } -void extract(::microstrain::Buffer& serializer, GnssAttAidStatus& self) +void extract(::microstrain::Serializer& serializer, GnssAttAidStatus& self) { extract(serializer, self.time_of_week); @@ -894,7 +894,7 @@ void extract(::microstrain::Buffer& serializer, GnssAttAidStatus& self) } -void insert(::microstrain::Buffer& serializer, const HeadAidStatus& self) +void insert(::microstrain::Serializer& serializer, const HeadAidStatus& self) { insert(serializer, self.time_of_week); @@ -904,7 +904,7 @@ void insert(::microstrain::Buffer& serializer, const HeadAidStatus& self) insert(serializer, self.reserved[i]); } -void extract(::microstrain::Buffer& serializer, HeadAidStatus& self) +void extract(::microstrain::Serializer& serializer, HeadAidStatus& self) { extract(serializer, self.time_of_week); @@ -915,7 +915,7 @@ void extract(::microstrain::Buffer& serializer, HeadAidStatus& self) } -void insert(::microstrain::Buffer& serializer, const RelPosNed& self) +void insert(::microstrain::Serializer& serializer, const RelPosNed& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.relative_position[i]); @@ -923,7 +923,7 @@ void insert(::microstrain::Buffer& serializer, const RelPosNed& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, RelPosNed& self) +void extract(::microstrain::Serializer& serializer, RelPosNed& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.relative_position[i]); @@ -932,7 +932,7 @@ void extract(::microstrain::Buffer& serializer, RelPosNed& self) } -void insert(::microstrain::Buffer& serializer, const EcefPos& self) +void insert(::microstrain::Serializer& serializer, const EcefPos& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.position_ecef[i]); @@ -940,7 +940,7 @@ void insert(::microstrain::Buffer& serializer, const EcefPos& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, EcefPos& self) +void extract(::microstrain::Serializer& serializer, EcefPos& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.position_ecef[i]); @@ -949,7 +949,7 @@ void extract(::microstrain::Buffer& serializer, EcefPos& self) } -void insert(::microstrain::Buffer& serializer, const EcefVel& self) +void insert(::microstrain::Serializer& serializer, const EcefVel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.velocity_ecef[i]); @@ -957,7 +957,7 @@ void insert(::microstrain::Buffer& serializer, const EcefVel& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, EcefVel& self) +void extract(::microstrain::Serializer& serializer, EcefVel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.velocity_ecef[i]); @@ -966,7 +966,7 @@ void extract(::microstrain::Buffer& serializer, EcefVel& self) } -void insert(::microstrain::Buffer& serializer, const EcefPosUncertainty& self) +void insert(::microstrain::Serializer& serializer, const EcefPosUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.pos_uncertainty[i]); @@ -974,7 +974,7 @@ void insert(::microstrain::Buffer& serializer, const EcefPosUncertainty& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, EcefPosUncertainty& self) +void extract(::microstrain::Serializer& serializer, EcefPosUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.pos_uncertainty[i]); @@ -983,7 +983,7 @@ void extract(::microstrain::Buffer& serializer, EcefPosUncertainty& self) } -void insert(::microstrain::Buffer& serializer, const EcefVelUncertainty& self) +void insert(::microstrain::Serializer& serializer, const EcefVelUncertainty& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.vel_uncertainty[i]); @@ -991,7 +991,7 @@ void insert(::microstrain::Buffer& serializer, const EcefVelUncertainty& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, EcefVelUncertainty& self) +void extract(::microstrain::Serializer& serializer, EcefVelUncertainty& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.vel_uncertainty[i]); @@ -1000,7 +1000,7 @@ void extract(::microstrain::Buffer& serializer, EcefVelUncertainty& self) } -void insert(::microstrain::Buffer& serializer, const AidingMeasurementSummary& self) +void insert(::microstrain::Serializer& serializer, const AidingMeasurementSummary& self) { insert(serializer, self.time_of_week); @@ -1011,7 +1011,7 @@ void insert(::microstrain::Buffer& serializer, const AidingMeasurementSummary& s insert(serializer, self.indicator); } -void extract(::microstrain::Buffer& serializer, AidingMeasurementSummary& self) +void extract(::microstrain::Serializer& serializer, AidingMeasurementSummary& self) { extract(serializer, self.time_of_week); @@ -1023,14 +1023,14 @@ void extract(::microstrain::Buffer& serializer, AidingMeasurementSummary& self) } -void insert(::microstrain::Buffer& serializer, const OdometerScaleFactorError& self) +void insert(::microstrain::Serializer& serializer, const OdometerScaleFactorError& self) { insert(serializer, self.scale_factor_error); insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, OdometerScaleFactorError& self) +void extract(::microstrain::Serializer& serializer, OdometerScaleFactorError& self) { extract(serializer, self.scale_factor_error); @@ -1038,14 +1038,14 @@ void extract(::microstrain::Buffer& serializer, OdometerScaleFactorError& self) } -void insert(::microstrain::Buffer& serializer, const OdometerScaleFactorErrorUncertainty& self) +void insert(::microstrain::Serializer& serializer, const OdometerScaleFactorErrorUncertainty& self) { insert(serializer, self.scale_factor_error_uncertainty); insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, OdometerScaleFactorErrorUncertainty& self) +void extract(::microstrain::Serializer& serializer, OdometerScaleFactorErrorUncertainty& self) { extract(serializer, self.scale_factor_error_uncertainty); @@ -1053,7 +1053,7 @@ void extract(::microstrain::Buffer& serializer, OdometerScaleFactorErrorUncertai } -void insert(::microstrain::Buffer& serializer, const GnssDualAntennaStatus& self) +void insert(::microstrain::Serializer& serializer, const GnssDualAntennaStatus& self) { insert(serializer, self.time_of_week); @@ -1068,7 +1068,7 @@ void insert(::microstrain::Buffer& serializer, const GnssDualAntennaStatus& self insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GnssDualAntennaStatus& self) +void extract(::microstrain::Serializer& serializer, GnssDualAntennaStatus& self) { extract(serializer, self.time_of_week); @@ -1084,7 +1084,7 @@ void extract(::microstrain::Buffer& serializer, GnssDualAntennaStatus& self) } -void insert(::microstrain::Buffer& serializer, const AidingFrameConfigError& self) +void insert(::microstrain::Serializer& serializer, const AidingFrameConfigError& self) { insert(serializer, self.frame_id); @@ -1095,7 +1095,7 @@ void insert(::microstrain::Buffer& serializer, const AidingFrameConfigError& sel insert(serializer, self.attitude[i]); } -void extract(::microstrain::Buffer& serializer, AidingFrameConfigError& self) +void extract(::microstrain::Serializer& serializer, AidingFrameConfigError& self) { extract(serializer, self.frame_id); @@ -1107,7 +1107,7 @@ void extract(::microstrain::Buffer& serializer, AidingFrameConfigError& self) } -void insert(::microstrain::Buffer& serializer, const AidingFrameConfigErrorUncertainty& self) +void insert(::microstrain::Serializer& serializer, const AidingFrameConfigErrorUncertainty& self) { insert(serializer, self.frame_id); @@ -1118,7 +1118,7 @@ void insert(::microstrain::Buffer& serializer, const AidingFrameConfigErrorUncer insert(serializer, self.attitude_unc[i]); } -void extract(::microstrain::Buffer& serializer, AidingFrameConfigErrorUncertainty& self) +void extract(::microstrain::Serializer& serializer, AidingFrameConfigErrorUncertainty& self) { extract(serializer, self.frame_id); diff --git a/src/mip/definitions/data_filter.hpp b/src/mip/definitions/data_filter.hpp index 640643316..b83b04671 100644 --- a/src/mip/definitions/data_filter.hpp +++ b/src/mip/definitions/data_filter.hpp @@ -388,8 +388,8 @@ struct PositionLlh return std::make_tuple(std::ref(latitude),std::ref(longitude),std::ref(ellipsoid_height),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const PositionLlh& self); -void extract(::microstrain::Buffer& serializer, PositionLlh& self); +void insert(::microstrain::Serializer& serializer, const PositionLlh& self); +void extract(::microstrain::Serializer& serializer, PositionLlh& self); ///@} @@ -424,8 +424,8 @@ struct VelocityNed return std::make_tuple(std::ref(north),std::ref(east),std::ref(down),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const VelocityNed& self); -void extract(::microstrain::Buffer& serializer, VelocityNed& self); +void insert(::microstrain::Serializer& serializer, const VelocityNed& self); +void extract(::microstrain::Serializer& serializer, VelocityNed& self); ///@} @@ -466,8 +466,8 @@ struct AttitudeQuaternion return std::make_tuple(std::ref(q[0]),std::ref(q[1]),std::ref(q[2]),std::ref(q[3]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const AttitudeQuaternion& self); -void extract(::microstrain::Buffer& serializer, AttitudeQuaternion& self); +void insert(::microstrain::Serializer& serializer, const AttitudeQuaternion& self); +void extract(::microstrain::Serializer& serializer, AttitudeQuaternion& self); ///@} @@ -510,8 +510,8 @@ struct AttitudeDcm return std::make_tuple(std::ref(dcm[0]),std::ref(dcm[1]),std::ref(dcm[2]),std::ref(dcm[3]),std::ref(dcm[4]),std::ref(dcm[5]),std::ref(dcm[6]),std::ref(dcm[7]),std::ref(dcm[8]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const AttitudeDcm& self); -void extract(::microstrain::Buffer& serializer, AttitudeDcm& self); +void insert(::microstrain::Serializer& serializer, const AttitudeDcm& self); +void extract(::microstrain::Serializer& serializer, AttitudeDcm& self); ///@} @@ -547,8 +547,8 @@ struct EulerAngles return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const EulerAngles& self); -void extract(::microstrain::Buffer& serializer, EulerAngles& self); +void insert(::microstrain::Serializer& serializer, const EulerAngles& self); +void extract(::microstrain::Serializer& serializer, EulerAngles& self); ///@} @@ -581,8 +581,8 @@ struct GyroBias return std::make_tuple(std::ref(bias[0]),std::ref(bias[1]),std::ref(bias[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GyroBias& self); -void extract(::microstrain::Buffer& serializer, GyroBias& self); +void insert(::microstrain::Serializer& serializer, const GyroBias& self); +void extract(::microstrain::Serializer& serializer, GyroBias& self); ///@} @@ -615,8 +615,8 @@ struct AccelBias return std::make_tuple(std::ref(bias[0]),std::ref(bias[1]),std::ref(bias[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const AccelBias& self); -void extract(::microstrain::Buffer& serializer, AccelBias& self); +void insert(::microstrain::Serializer& serializer, const AccelBias& self); +void extract(::microstrain::Serializer& serializer, AccelBias& self); ///@} @@ -651,8 +651,8 @@ struct PositionLlhUncertainty return std::make_tuple(std::ref(north),std::ref(east),std::ref(down),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const PositionLlhUncertainty& self); -void extract(::microstrain::Buffer& serializer, PositionLlhUncertainty& self); +void insert(::microstrain::Serializer& serializer, const PositionLlhUncertainty& self); +void extract(::microstrain::Serializer& serializer, PositionLlhUncertainty& self); ///@} @@ -687,8 +687,8 @@ struct VelocityNedUncertainty return std::make_tuple(std::ref(north),std::ref(east),std::ref(down),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const VelocityNedUncertainty& self); -void extract(::microstrain::Buffer& serializer, VelocityNedUncertainty& self); +void insert(::microstrain::Serializer& serializer, const VelocityNedUncertainty& self); +void extract(::microstrain::Serializer& serializer, VelocityNedUncertainty& self); ///@} @@ -724,8 +724,8 @@ struct EulerAnglesUncertainty return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const EulerAnglesUncertainty& self); -void extract(::microstrain::Buffer& serializer, EulerAnglesUncertainty& self); +void insert(::microstrain::Serializer& serializer, const EulerAnglesUncertainty& self); +void extract(::microstrain::Serializer& serializer, EulerAnglesUncertainty& self); ///@} @@ -758,8 +758,8 @@ struct GyroBiasUncertainty return std::make_tuple(std::ref(bias_uncert[0]),std::ref(bias_uncert[1]),std::ref(bias_uncert[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GyroBiasUncertainty& self); -void extract(::microstrain::Buffer& serializer, GyroBiasUncertainty& self); +void insert(::microstrain::Serializer& serializer, const GyroBiasUncertainty& self); +void extract(::microstrain::Serializer& serializer, GyroBiasUncertainty& self); ///@} @@ -792,8 +792,8 @@ struct AccelBiasUncertainty return std::make_tuple(std::ref(bias_uncert[0]),std::ref(bias_uncert[1]),std::ref(bias_uncert[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const AccelBiasUncertainty& self); -void extract(::microstrain::Buffer& serializer, AccelBiasUncertainty& self); +void insert(::microstrain::Serializer& serializer, const AccelBiasUncertainty& self); +void extract(::microstrain::Serializer& serializer, AccelBiasUncertainty& self); ///@} @@ -833,8 +833,8 @@ struct Timestamp return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const Timestamp& self); -void extract(::microstrain::Buffer& serializer, Timestamp& self); +void insert(::microstrain::Serializer& serializer, const Timestamp& self); +void extract(::microstrain::Serializer& serializer, Timestamp& self); ///@} @@ -868,8 +868,8 @@ struct Status return std::make_tuple(std::ref(filter_state),std::ref(dynamics_mode),std::ref(status_flags)); } }; -void insert(::microstrain::Buffer& serializer, const Status& self); -void extract(::microstrain::Buffer& serializer, Status& self); +void insert(::microstrain::Serializer& serializer, const Status& self); +void extract(::microstrain::Serializer& serializer, Status& self); ///@} @@ -903,8 +903,8 @@ struct LinearAccel return std::make_tuple(std::ref(accel[0]),std::ref(accel[1]),std::ref(accel[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const LinearAccel& self); -void extract(::microstrain::Buffer& serializer, LinearAccel& self); +void insert(::microstrain::Serializer& serializer, const LinearAccel& self); +void extract(::microstrain::Serializer& serializer, LinearAccel& self); ///@} @@ -937,8 +937,8 @@ struct GravityVector return std::make_tuple(std::ref(gravity[0]),std::ref(gravity[1]),std::ref(gravity[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GravityVector& self); -void extract(::microstrain::Buffer& serializer, GravityVector& self); +void insert(::microstrain::Serializer& serializer, const GravityVector& self); +void extract(::microstrain::Serializer& serializer, GravityVector& self); ///@} @@ -971,8 +971,8 @@ struct CompAccel return std::make_tuple(std::ref(accel[0]),std::ref(accel[1]),std::ref(accel[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const CompAccel& self); -void extract(::microstrain::Buffer& serializer, CompAccel& self); +void insert(::microstrain::Serializer& serializer, const CompAccel& self); +void extract(::microstrain::Serializer& serializer, CompAccel& self); ///@} @@ -1005,8 +1005,8 @@ struct CompAngularRate return std::make_tuple(std::ref(gyro[0]),std::ref(gyro[1]),std::ref(gyro[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const CompAngularRate& self); -void extract(::microstrain::Buffer& serializer, CompAngularRate& self); +void insert(::microstrain::Serializer& serializer, const CompAngularRate& self); +void extract(::microstrain::Serializer& serializer, CompAngularRate& self); ///@} @@ -1039,8 +1039,8 @@ struct QuaternionAttitudeUncertainty return std::make_tuple(std::ref(q[0]),std::ref(q[1]),std::ref(q[2]),std::ref(q[3]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const QuaternionAttitudeUncertainty& self); -void extract(::microstrain::Buffer& serializer, QuaternionAttitudeUncertainty& self); +void insert(::microstrain::Serializer& serializer, const QuaternionAttitudeUncertainty& self); +void extract(::microstrain::Serializer& serializer, QuaternionAttitudeUncertainty& self); ///@} @@ -1073,8 +1073,8 @@ struct Wgs84GravityMag return std::make_tuple(std::ref(magnitude),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const Wgs84GravityMag& self); -void extract(::microstrain::Buffer& serializer, Wgs84GravityMag& self); +void insert(::microstrain::Serializer& serializer, const Wgs84GravityMag& self); +void extract(::microstrain::Serializer& serializer, Wgs84GravityMag& self); ///@} @@ -1121,8 +1121,8 @@ struct HeadingUpdateState return std::make_tuple(std::ref(heading),std::ref(heading_1sigma),std::ref(source),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const HeadingUpdateState& self); -void extract(::microstrain::Buffer& serializer, HeadingUpdateState& self); +void insert(::microstrain::Serializer& serializer, const HeadingUpdateState& self); +void extract(::microstrain::Serializer& serializer, HeadingUpdateState& self); ///@} @@ -1160,8 +1160,8 @@ struct MagneticModel return std::make_tuple(std::ref(intensity_north),std::ref(intensity_east),std::ref(intensity_down),std::ref(inclination),std::ref(declination),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MagneticModel& self); -void extract(::microstrain::Buffer& serializer, MagneticModel& self); +void insert(::microstrain::Serializer& serializer, const MagneticModel& self); +void extract(::microstrain::Serializer& serializer, MagneticModel& self); ///@} @@ -1194,8 +1194,8 @@ struct AccelScaleFactor return std::make_tuple(std::ref(scale_factor[0]),std::ref(scale_factor[1]),std::ref(scale_factor[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const AccelScaleFactor& self); -void extract(::microstrain::Buffer& serializer, AccelScaleFactor& self); +void insert(::microstrain::Serializer& serializer, const AccelScaleFactor& self); +void extract(::microstrain::Serializer& serializer, AccelScaleFactor& self); ///@} @@ -1228,8 +1228,8 @@ struct AccelScaleFactorUncertainty return std::make_tuple(std::ref(scale_factor_uncert[0]),std::ref(scale_factor_uncert[1]),std::ref(scale_factor_uncert[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const AccelScaleFactorUncertainty& self); -void extract(::microstrain::Buffer& serializer, AccelScaleFactorUncertainty& self); +void insert(::microstrain::Serializer& serializer, const AccelScaleFactorUncertainty& self); +void extract(::microstrain::Serializer& serializer, AccelScaleFactorUncertainty& self); ///@} @@ -1262,8 +1262,8 @@ struct GyroScaleFactor return std::make_tuple(std::ref(scale_factor[0]),std::ref(scale_factor[1]),std::ref(scale_factor[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GyroScaleFactor& self); -void extract(::microstrain::Buffer& serializer, GyroScaleFactor& self); +void insert(::microstrain::Serializer& serializer, const GyroScaleFactor& self); +void extract(::microstrain::Serializer& serializer, GyroScaleFactor& self); ///@} @@ -1296,8 +1296,8 @@ struct GyroScaleFactorUncertainty return std::make_tuple(std::ref(scale_factor_uncert[0]),std::ref(scale_factor_uncert[1]),std::ref(scale_factor_uncert[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GyroScaleFactorUncertainty& self); -void extract(::microstrain::Buffer& serializer, GyroScaleFactorUncertainty& self); +void insert(::microstrain::Serializer& serializer, const GyroScaleFactorUncertainty& self); +void extract(::microstrain::Serializer& serializer, GyroScaleFactorUncertainty& self); ///@} @@ -1330,8 +1330,8 @@ struct MagBias return std::make_tuple(std::ref(bias[0]),std::ref(bias[1]),std::ref(bias[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MagBias& self); -void extract(::microstrain::Buffer& serializer, MagBias& self); +void insert(::microstrain::Serializer& serializer, const MagBias& self); +void extract(::microstrain::Serializer& serializer, MagBias& self); ///@} @@ -1364,8 +1364,8 @@ struct MagBiasUncertainty return std::make_tuple(std::ref(bias_uncert[0]),std::ref(bias_uncert[1]),std::ref(bias_uncert[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MagBiasUncertainty& self); -void extract(::microstrain::Buffer& serializer, MagBiasUncertainty& self); +void insert(::microstrain::Serializer& serializer, const MagBiasUncertainty& self); +void extract(::microstrain::Serializer& serializer, MagBiasUncertainty& self); ///@} @@ -1404,8 +1404,8 @@ struct StandardAtmosphere return std::make_tuple(std::ref(geometric_altitude),std::ref(geopotential_altitude),std::ref(standard_temperature),std::ref(standard_pressure),std::ref(standard_density),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const StandardAtmosphere& self); -void extract(::microstrain::Buffer& serializer, StandardAtmosphere& self); +void insert(::microstrain::Serializer& serializer, const StandardAtmosphere& self); +void extract(::microstrain::Serializer& serializer, StandardAtmosphere& self); ///@} @@ -1442,8 +1442,8 @@ struct PressureAltitude return std::make_tuple(std::ref(pressure_altitude),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const PressureAltitude& self); -void extract(::microstrain::Buffer& serializer, PressureAltitude& self); +void insert(::microstrain::Serializer& serializer, const PressureAltitude& self); +void extract(::microstrain::Serializer& serializer, PressureAltitude& self); ///@} @@ -1475,8 +1475,8 @@ struct DensityAltitude return std::make_tuple(std::ref(density_altitude),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const DensityAltitude& self); -void extract(::microstrain::Buffer& serializer, DensityAltitude& self); +void insert(::microstrain::Serializer& serializer, const DensityAltitude& self); +void extract(::microstrain::Serializer& serializer, DensityAltitude& self); ///@} @@ -1511,8 +1511,8 @@ struct AntennaOffsetCorrection return std::make_tuple(std::ref(offset[0]),std::ref(offset[1]),std::ref(offset[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrection& self); -void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrection& self); +void insert(::microstrain::Serializer& serializer, const AntennaOffsetCorrection& self); +void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrection& self); ///@} @@ -1545,8 +1545,8 @@ struct AntennaOffsetCorrectionUncertainty return std::make_tuple(std::ref(offset_uncert[0]),std::ref(offset_uncert[1]),std::ref(offset_uncert[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const AntennaOffsetCorrectionUncertainty& self); -void extract(::microstrain::Buffer& serializer, AntennaOffsetCorrectionUncertainty& self); +void insert(::microstrain::Serializer& serializer, const AntennaOffsetCorrectionUncertainty& self); +void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrectionUncertainty& self); ///@} @@ -1582,8 +1582,8 @@ struct MultiAntennaOffsetCorrection return std::make_tuple(std::ref(receiver_id),std::ref(offset[0]),std::ref(offset[1]),std::ref(offset[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrection& self); -void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrection& self); +void insert(::microstrain::Serializer& serializer, const MultiAntennaOffsetCorrection& self); +void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrection& self); ///@} @@ -1617,8 +1617,8 @@ struct MultiAntennaOffsetCorrectionUncertainty return std::make_tuple(std::ref(receiver_id),std::ref(offset_uncert[0]),std::ref(offset_uncert[1]),std::ref(offset_uncert[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self); -void extract(::microstrain::Buffer& serializer, MultiAntennaOffsetCorrectionUncertainty& self); +void insert(::microstrain::Serializer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self); +void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrectionUncertainty& self); ///@} @@ -1653,8 +1653,8 @@ struct MagnetometerOffset return std::make_tuple(std::ref(hard_iron[0]),std::ref(hard_iron[1]),std::ref(hard_iron[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MagnetometerOffset& self); -void extract(::microstrain::Buffer& serializer, MagnetometerOffset& self); +void insert(::microstrain::Serializer& serializer, const MagnetometerOffset& self); +void extract(::microstrain::Serializer& serializer, MagnetometerOffset& self); ///@} @@ -1689,8 +1689,8 @@ struct MagnetometerMatrix return std::make_tuple(std::ref(soft_iron[0]),std::ref(soft_iron[1]),std::ref(soft_iron[2]),std::ref(soft_iron[3]),std::ref(soft_iron[4]),std::ref(soft_iron[5]),std::ref(soft_iron[6]),std::ref(soft_iron[7]),std::ref(soft_iron[8]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MagnetometerMatrix& self); -void extract(::microstrain::Buffer& serializer, MagnetometerMatrix& self); +void insert(::microstrain::Serializer& serializer, const MagnetometerMatrix& self); +void extract(::microstrain::Serializer& serializer, MagnetometerMatrix& self); ///@} @@ -1723,8 +1723,8 @@ struct MagnetometerOffsetUncertainty return std::make_tuple(std::ref(hard_iron_uncertainty[0]),std::ref(hard_iron_uncertainty[1]),std::ref(hard_iron_uncertainty[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MagnetometerOffsetUncertainty& self); -void extract(::microstrain::Buffer& serializer, MagnetometerOffsetUncertainty& self); +void insert(::microstrain::Serializer& serializer, const MagnetometerOffsetUncertainty& self); +void extract(::microstrain::Serializer& serializer, MagnetometerOffsetUncertainty& self); ///@} @@ -1757,8 +1757,8 @@ struct MagnetometerMatrixUncertainty return std::make_tuple(std::ref(soft_iron_uncertainty[0]),std::ref(soft_iron_uncertainty[1]),std::ref(soft_iron_uncertainty[2]),std::ref(soft_iron_uncertainty[3]),std::ref(soft_iron_uncertainty[4]),std::ref(soft_iron_uncertainty[5]),std::ref(soft_iron_uncertainty[6]),std::ref(soft_iron_uncertainty[7]),std::ref(soft_iron_uncertainty[8]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MagnetometerMatrixUncertainty& self); -void extract(::microstrain::Buffer& serializer, MagnetometerMatrixUncertainty& self); +void insert(::microstrain::Serializer& serializer, const MagnetometerMatrixUncertainty& self); +void extract(::microstrain::Serializer& serializer, MagnetometerMatrixUncertainty& self); ///@} @@ -1790,8 +1790,8 @@ struct MagnetometerCovarianceMatrix return std::make_tuple(std::ref(covariance[0]),std::ref(covariance[1]),std::ref(covariance[2]),std::ref(covariance[3]),std::ref(covariance[4]),std::ref(covariance[5]),std::ref(covariance[6]),std::ref(covariance[7]),std::ref(covariance[8]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MagnetometerCovarianceMatrix& self); -void extract(::microstrain::Buffer& serializer, MagnetometerCovarianceMatrix& self); +void insert(::microstrain::Serializer& serializer, const MagnetometerCovarianceMatrix& self); +void extract(::microstrain::Serializer& serializer, MagnetometerCovarianceMatrix& self); ///@} @@ -1824,8 +1824,8 @@ struct MagnetometerResidualVector return std::make_tuple(std::ref(residual[0]),std::ref(residual[1]),std::ref(residual[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const MagnetometerResidualVector& self); -void extract(::microstrain::Buffer& serializer, MagnetometerResidualVector& self); +void insert(::microstrain::Serializer& serializer, const MagnetometerResidualVector& self); +void extract(::microstrain::Serializer& serializer, MagnetometerResidualVector& self); ///@} @@ -1860,8 +1860,8 @@ struct ClockCorrection return std::make_tuple(std::ref(receiver_id),std::ref(bias),std::ref(bias_drift),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const ClockCorrection& self); -void extract(::microstrain::Buffer& serializer, ClockCorrection& self); +void insert(::microstrain::Serializer& serializer, const ClockCorrection& self); +void extract(::microstrain::Serializer& serializer, ClockCorrection& self); ///@} @@ -1896,8 +1896,8 @@ struct ClockCorrectionUncertainty return std::make_tuple(std::ref(receiver_id),std::ref(bias_uncertainty),std::ref(bias_drift_uncertainty),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const ClockCorrectionUncertainty& self); -void extract(::microstrain::Buffer& serializer, ClockCorrectionUncertainty& self); +void insert(::microstrain::Serializer& serializer, const ClockCorrectionUncertainty& self); +void extract(::microstrain::Serializer& serializer, ClockCorrectionUncertainty& self); ///@} @@ -1932,8 +1932,8 @@ struct GnssPosAidStatus return std::make_tuple(std::ref(receiver_id),std::ref(time_of_week),std::ref(status),std::ref(reserved)); } }; -void insert(::microstrain::Buffer& serializer, const GnssPosAidStatus& self); -void extract(::microstrain::Buffer& serializer, GnssPosAidStatus& self); +void insert(::microstrain::Serializer& serializer, const GnssPosAidStatus& self); +void extract(::microstrain::Serializer& serializer, GnssPosAidStatus& self); ///@} @@ -1967,8 +1967,8 @@ struct GnssAttAidStatus return std::make_tuple(std::ref(time_of_week),std::ref(status),std::ref(reserved)); } }; -void insert(::microstrain::Buffer& serializer, const GnssAttAidStatus& self); -void extract(::microstrain::Buffer& serializer, GnssAttAidStatus& self); +void insert(::microstrain::Serializer& serializer, const GnssAttAidStatus& self); +void extract(::microstrain::Serializer& serializer, GnssAttAidStatus& self); ///@} @@ -2008,8 +2008,8 @@ struct HeadAidStatus return std::make_tuple(std::ref(time_of_week),std::ref(type),std::ref(reserved)); } }; -void insert(::microstrain::Buffer& serializer, const HeadAidStatus& self); -void extract(::microstrain::Buffer& serializer, HeadAidStatus& self); +void insert(::microstrain::Serializer& serializer, const HeadAidStatus& self); +void extract(::microstrain::Serializer& serializer, HeadAidStatus& self); ///@} @@ -2042,8 +2042,8 @@ struct RelPosNed return std::make_tuple(std::ref(relative_position[0]),std::ref(relative_position[1]),std::ref(relative_position[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const RelPosNed& self); -void extract(::microstrain::Buffer& serializer, RelPosNed& self); +void insert(::microstrain::Serializer& serializer, const RelPosNed& self); +void extract(::microstrain::Serializer& serializer, RelPosNed& self); ///@} @@ -2076,8 +2076,8 @@ struct EcefPos return std::make_tuple(std::ref(position_ecef[0]),std::ref(position_ecef[1]),std::ref(position_ecef[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const EcefPos& self); -void extract(::microstrain::Buffer& serializer, EcefPos& self); +void insert(::microstrain::Serializer& serializer, const EcefPos& self); +void extract(::microstrain::Serializer& serializer, EcefPos& self); ///@} @@ -2110,8 +2110,8 @@ struct EcefVel return std::make_tuple(std::ref(velocity_ecef[0]),std::ref(velocity_ecef[1]),std::ref(velocity_ecef[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const EcefVel& self); -void extract(::microstrain::Buffer& serializer, EcefVel& self); +void insert(::microstrain::Serializer& serializer, const EcefVel& self); +void extract(::microstrain::Serializer& serializer, EcefVel& self); ///@} @@ -2144,8 +2144,8 @@ struct EcefPosUncertainty return std::make_tuple(std::ref(pos_uncertainty[0]),std::ref(pos_uncertainty[1]),std::ref(pos_uncertainty[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const EcefPosUncertainty& self); -void extract(::microstrain::Buffer& serializer, EcefPosUncertainty& self); +void insert(::microstrain::Serializer& serializer, const EcefPosUncertainty& self); +void extract(::microstrain::Serializer& serializer, EcefPosUncertainty& self); ///@} @@ -2178,8 +2178,8 @@ struct EcefVelUncertainty return std::make_tuple(std::ref(vel_uncertainty[0]),std::ref(vel_uncertainty[1]),std::ref(vel_uncertainty[2]),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const EcefVelUncertainty& self); -void extract(::microstrain::Buffer& serializer, EcefVelUncertainty& self); +void insert(::microstrain::Serializer& serializer, const EcefVelUncertainty& self); +void extract(::microstrain::Serializer& serializer, EcefVelUncertainty& self); ///@} @@ -2214,8 +2214,8 @@ struct AidingMeasurementSummary return std::make_tuple(std::ref(time_of_week),std::ref(source),std::ref(type),std::ref(indicator)); } }; -void insert(::microstrain::Buffer& serializer, const AidingMeasurementSummary& self); -void extract(::microstrain::Buffer& serializer, AidingMeasurementSummary& self); +void insert(::microstrain::Serializer& serializer, const AidingMeasurementSummary& self); +void extract(::microstrain::Serializer& serializer, AidingMeasurementSummary& self); ///@} @@ -2248,8 +2248,8 @@ struct OdometerScaleFactorError return std::make_tuple(std::ref(scale_factor_error),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const OdometerScaleFactorError& self); -void extract(::microstrain::Buffer& serializer, OdometerScaleFactorError& self); +void insert(::microstrain::Serializer& serializer, const OdometerScaleFactorError& self); +void extract(::microstrain::Serializer& serializer, OdometerScaleFactorError& self); ///@} @@ -2282,8 +2282,8 @@ struct OdometerScaleFactorErrorUncertainty return std::make_tuple(std::ref(scale_factor_error_uncertainty),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const OdometerScaleFactorErrorUncertainty& self); -void extract(::microstrain::Buffer& serializer, OdometerScaleFactorErrorUncertainty& self); +void insert(::microstrain::Serializer& serializer, const OdometerScaleFactorErrorUncertainty& self); +void extract(::microstrain::Serializer& serializer, OdometerScaleFactorErrorUncertainty& self); ///@} @@ -2358,8 +2358,8 @@ struct GnssDualAntennaStatus return std::make_tuple(std::ref(time_of_week),std::ref(heading),std::ref(heading_unc),std::ref(fix_type),std::ref(status_flags),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GnssDualAntennaStatus& self); -void extract(::microstrain::Buffer& serializer, GnssDualAntennaStatus& self); +void insert(::microstrain::Serializer& serializer, const GnssDualAntennaStatus& self); +void extract(::microstrain::Serializer& serializer, GnssDualAntennaStatus& self); ///@} @@ -2395,8 +2395,8 @@ struct AidingFrameConfigError return std::make_tuple(std::ref(frame_id),std::ref(translation[0]),std::ref(translation[1]),std::ref(translation[2]),std::ref(attitude[0]),std::ref(attitude[1]),std::ref(attitude[2]),std::ref(attitude[3])); } }; -void insert(::microstrain::Buffer& serializer, const AidingFrameConfigError& self); -void extract(::microstrain::Buffer& serializer, AidingFrameConfigError& self); +void insert(::microstrain::Serializer& serializer, const AidingFrameConfigError& self); +void extract(::microstrain::Serializer& serializer, AidingFrameConfigError& self); ///@} @@ -2432,8 +2432,8 @@ struct AidingFrameConfigErrorUncertainty return std::make_tuple(std::ref(frame_id),std::ref(translation_unc[0]),std::ref(translation_unc[1]),std::ref(translation_unc[2]),std::ref(attitude_unc[0]),std::ref(attitude_unc[1]),std::ref(attitude_unc[2])); } }; -void insert(::microstrain::Buffer& serializer, const AidingFrameConfigErrorUncertainty& self); -void extract(::microstrain::Buffer& serializer, AidingFrameConfigErrorUncertainty& self); +void insert(::microstrain::Serializer& serializer, const AidingFrameConfigErrorUncertainty& self); +void extract(::microstrain::Serializer& serializer, AidingFrameConfigErrorUncertainty& self); ///@} diff --git a/src/mip/definitions/data_gnss.cpp b/src/mip/definitions/data_gnss.cpp index 741a73479..2f89e88b3 100644 --- a/src/mip/definitions/data_gnss.cpp +++ b/src/mip/definitions/data_gnss.cpp @@ -1,7 +1,7 @@ #include "data_gnss.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -29,7 +29,7 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const PosLlh& self) +void insert(::microstrain::Serializer& serializer, const PosLlh& self) { insert(serializer, self.latitude); @@ -46,7 +46,7 @@ void insert(::microstrain::Buffer& serializer, const PosLlh& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, PosLlh& self) +void extract(::microstrain::Serializer& serializer, PosLlh& self) { extract(serializer, self.latitude); @@ -64,7 +64,7 @@ void extract(::microstrain::Buffer& serializer, PosLlh& self) } -void insert(::microstrain::Buffer& serializer, const PosEcef& self) +void insert(::microstrain::Serializer& serializer, const PosEcef& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.x[i]); @@ -74,7 +74,7 @@ void insert(::microstrain::Buffer& serializer, const PosEcef& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, PosEcef& self) +void extract(::microstrain::Serializer& serializer, PosEcef& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.x[i]); @@ -85,7 +85,7 @@ void extract(::microstrain::Buffer& serializer, PosEcef& self) } -void insert(::microstrain::Buffer& serializer, const VelNed& self) +void insert(::microstrain::Serializer& serializer, const VelNed& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.v[i]); @@ -103,7 +103,7 @@ void insert(::microstrain::Buffer& serializer, const VelNed& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, VelNed& self) +void extract(::microstrain::Serializer& serializer, VelNed& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.v[i]); @@ -122,7 +122,7 @@ void extract(::microstrain::Buffer& serializer, VelNed& self) } -void insert(::microstrain::Buffer& serializer, const VelEcef& self) +void insert(::microstrain::Serializer& serializer, const VelEcef& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.v[i]); @@ -132,7 +132,7 @@ void insert(::microstrain::Buffer& serializer, const VelEcef& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, VelEcef& self) +void extract(::microstrain::Serializer& serializer, VelEcef& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.v[i]); @@ -143,7 +143,7 @@ void extract(::microstrain::Buffer& serializer, VelEcef& self) } -void insert(::microstrain::Buffer& serializer, const Dop& self) +void insert(::microstrain::Serializer& serializer, const Dop& self) { insert(serializer, self.gdop); @@ -162,7 +162,7 @@ void insert(::microstrain::Buffer& serializer, const Dop& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, Dop& self) +void extract(::microstrain::Serializer& serializer, Dop& self) { extract(serializer, self.gdop); @@ -182,7 +182,7 @@ void extract(::microstrain::Buffer& serializer, Dop& self) } -void insert(::microstrain::Buffer& serializer, const UtcTime& self) +void insert(::microstrain::Serializer& serializer, const UtcTime& self) { insert(serializer, self.year); @@ -201,7 +201,7 @@ void insert(::microstrain::Buffer& serializer, const UtcTime& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, UtcTime& self) +void extract(::microstrain::Serializer& serializer, UtcTime& self) { extract(serializer, self.year); @@ -221,7 +221,7 @@ void extract(::microstrain::Buffer& serializer, UtcTime& self) } -void insert(::microstrain::Buffer& serializer, const GpsTime& self) +void insert(::microstrain::Serializer& serializer, const GpsTime& self) { insert(serializer, self.tow); @@ -230,7 +230,7 @@ void insert(::microstrain::Buffer& serializer, const GpsTime& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GpsTime& self) +void extract(::microstrain::Serializer& serializer, GpsTime& self) { extract(serializer, self.tow); @@ -240,7 +240,7 @@ void extract(::microstrain::Buffer& serializer, GpsTime& self) } -void insert(::microstrain::Buffer& serializer, const ClockInfo& self) +void insert(::microstrain::Serializer& serializer, const ClockInfo& self) { insert(serializer, self.bias); @@ -251,7 +251,7 @@ void insert(::microstrain::Buffer& serializer, const ClockInfo& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, ClockInfo& self) +void extract(::microstrain::Serializer& serializer, ClockInfo& self) { extract(serializer, self.bias); @@ -263,7 +263,7 @@ void extract(::microstrain::Buffer& serializer, ClockInfo& self) } -void insert(::microstrain::Buffer& serializer, const FixInfo& self) +void insert(::microstrain::Serializer& serializer, const FixInfo& self) { insert(serializer, self.fix_type); @@ -274,7 +274,7 @@ void insert(::microstrain::Buffer& serializer, const FixInfo& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, FixInfo& self) +void extract(::microstrain::Serializer& serializer, FixInfo& self) { extract(serializer, self.fix_type); @@ -286,7 +286,7 @@ void extract(::microstrain::Buffer& serializer, FixInfo& self) } -void insert(::microstrain::Buffer& serializer, const SvInfo& self) +void insert(::microstrain::Serializer& serializer, const SvInfo& self) { insert(serializer, self.channel); @@ -303,7 +303,7 @@ void insert(::microstrain::Buffer& serializer, const SvInfo& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, SvInfo& self) +void extract(::microstrain::Serializer& serializer, SvInfo& self) { extract(serializer, self.channel); @@ -321,7 +321,7 @@ void extract(::microstrain::Buffer& serializer, SvInfo& self) } -void insert(::microstrain::Buffer& serializer, const HwStatus& self) +void insert(::microstrain::Serializer& serializer, const HwStatus& self) { insert(serializer, self.receiver_state); @@ -332,7 +332,7 @@ void insert(::microstrain::Buffer& serializer, const HwStatus& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, HwStatus& self) +void extract(::microstrain::Serializer& serializer, HwStatus& self) { extract(serializer, self.receiver_state); @@ -344,7 +344,7 @@ void extract(::microstrain::Buffer& serializer, HwStatus& self) } -void insert(::microstrain::Buffer& serializer, const DgpsInfo& self) +void insert(::microstrain::Serializer& serializer, const DgpsInfo& self) { insert(serializer, self.sv_id); @@ -357,7 +357,7 @@ void insert(::microstrain::Buffer& serializer, const DgpsInfo& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, DgpsInfo& self) +void extract(::microstrain::Serializer& serializer, DgpsInfo& self) { extract(serializer, self.sv_id); @@ -371,7 +371,7 @@ void extract(::microstrain::Buffer& serializer, DgpsInfo& self) } -void insert(::microstrain::Buffer& serializer, const DgpsChannel& self) +void insert(::microstrain::Serializer& serializer, const DgpsChannel& self) { insert(serializer, self.sv_id); @@ -384,7 +384,7 @@ void insert(::microstrain::Buffer& serializer, const DgpsChannel& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, DgpsChannel& self) +void extract(::microstrain::Serializer& serializer, DgpsChannel& self) { extract(serializer, self.sv_id); @@ -398,7 +398,7 @@ void extract(::microstrain::Buffer& serializer, DgpsChannel& self) } -void insert(::microstrain::Buffer& serializer, const ClockInfo2& self) +void insert(::microstrain::Serializer& serializer, const ClockInfo2& self) { insert(serializer, self.bias); @@ -411,7 +411,7 @@ void insert(::microstrain::Buffer& serializer, const ClockInfo2& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, ClockInfo2& self) +void extract(::microstrain::Serializer& serializer, ClockInfo2& self) { extract(serializer, self.bias); @@ -425,14 +425,14 @@ void extract(::microstrain::Buffer& serializer, ClockInfo2& self) } -void insert(::microstrain::Buffer& serializer, const GpsLeapSeconds& self) +void insert(::microstrain::Serializer& serializer, const GpsLeapSeconds& self) { insert(serializer, self.leap_seconds); insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GpsLeapSeconds& self) +void extract(::microstrain::Serializer& serializer, GpsLeapSeconds& self) { extract(serializer, self.leap_seconds); @@ -440,7 +440,7 @@ void extract(::microstrain::Buffer& serializer, GpsLeapSeconds& self) } -void insert(::microstrain::Buffer& serializer, const SbasInfo& self) +void insert(::microstrain::Serializer& serializer, const SbasInfo& self) { insert(serializer, self.time_of_week); @@ -457,7 +457,7 @@ void insert(::microstrain::Buffer& serializer, const SbasInfo& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, SbasInfo& self) +void extract(::microstrain::Serializer& serializer, SbasInfo& self) { extract(serializer, self.time_of_week); @@ -475,7 +475,7 @@ void extract(::microstrain::Buffer& serializer, SbasInfo& self) } -void insert(::microstrain::Buffer& serializer, const SbasCorrection& self) +void insert(::microstrain::Serializer& serializer, const SbasCorrection& self) { insert(serializer, self.index); @@ -498,7 +498,7 @@ void insert(::microstrain::Buffer& serializer, const SbasCorrection& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, SbasCorrection& self) +void extract(::microstrain::Serializer& serializer, SbasCorrection& self) { extract(serializer, self.index); @@ -522,7 +522,7 @@ void extract(::microstrain::Buffer& serializer, SbasCorrection& self) } -void insert(::microstrain::Buffer& serializer, const RfErrorDetection& self) +void insert(::microstrain::Serializer& serializer, const RfErrorDetection& self) { insert(serializer, self.rf_band); @@ -536,7 +536,7 @@ void insert(::microstrain::Buffer& serializer, const RfErrorDetection& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, RfErrorDetection& self) +void extract(::microstrain::Serializer& serializer, RfErrorDetection& self) { extract(serializer, self.rf_band); @@ -551,7 +551,7 @@ void extract(::microstrain::Buffer& serializer, RfErrorDetection& self) } -void insert(::microstrain::Buffer& serializer, const BaseStationInfo& self) +void insert(::microstrain::Serializer& serializer, const BaseStationInfo& self) { insert(serializer, self.time_of_week); @@ -569,7 +569,7 @@ void insert(::microstrain::Buffer& serializer, const BaseStationInfo& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, BaseStationInfo& self) +void extract(::microstrain::Serializer& serializer, BaseStationInfo& self) { extract(serializer, self.time_of_week); @@ -588,7 +588,7 @@ void extract(::microstrain::Buffer& serializer, BaseStationInfo& self) } -void insert(::microstrain::Buffer& serializer, const RtkCorrectionsStatus& self) +void insert(::microstrain::Serializer& serializer, const RtkCorrectionsStatus& self) { insert(serializer, self.time_of_week); @@ -612,7 +612,7 @@ void insert(::microstrain::Buffer& serializer, const RtkCorrectionsStatus& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, RtkCorrectionsStatus& self) +void extract(::microstrain::Serializer& serializer, RtkCorrectionsStatus& self) { extract(serializer, self.time_of_week); @@ -637,7 +637,7 @@ void extract(::microstrain::Buffer& serializer, RtkCorrectionsStatus& self) } -void insert(::microstrain::Buffer& serializer, const SatelliteStatus& self) +void insert(::microstrain::Serializer& serializer, const SatelliteStatus& self) { insert(serializer, self.index); @@ -660,7 +660,7 @@ void insert(::microstrain::Buffer& serializer, const SatelliteStatus& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, SatelliteStatus& self) +void extract(::microstrain::Serializer& serializer, SatelliteStatus& self) { extract(serializer, self.index); @@ -684,7 +684,7 @@ void extract(::microstrain::Buffer& serializer, SatelliteStatus& self) } -void insert(::microstrain::Buffer& serializer, const Raw& self) +void insert(::microstrain::Serializer& serializer, const Raw& self) { insert(serializer, self.index); @@ -725,7 +725,7 @@ void insert(::microstrain::Buffer& serializer, const Raw& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, Raw& self) +void extract(::microstrain::Serializer& serializer, Raw& self) { extract(serializer, self.index); @@ -767,7 +767,7 @@ void extract(::microstrain::Buffer& serializer, Raw& self) } -void insert(::microstrain::Buffer& serializer, const GpsEphemeris& self) +void insert(::microstrain::Serializer& serializer, const GpsEphemeris& self) { insert(serializer, self.index); @@ -838,7 +838,7 @@ void insert(::microstrain::Buffer& serializer, const GpsEphemeris& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GpsEphemeris& self) +void extract(::microstrain::Serializer& serializer, GpsEphemeris& self) { extract(serializer, self.index); @@ -910,7 +910,7 @@ void extract(::microstrain::Buffer& serializer, GpsEphemeris& self) } -void insert(::microstrain::Buffer& serializer, const GalileoEphemeris& self) +void insert(::microstrain::Serializer& serializer, const GalileoEphemeris& self) { insert(serializer, self.index); @@ -981,7 +981,7 @@ void insert(::microstrain::Buffer& serializer, const GalileoEphemeris& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GalileoEphemeris& self) +void extract(::microstrain::Serializer& serializer, GalileoEphemeris& self) { extract(serializer, self.index); @@ -1053,7 +1053,7 @@ void extract(::microstrain::Buffer& serializer, GalileoEphemeris& self) } -void insert(::microstrain::Buffer& serializer, const GloEphemeris& self) +void insert(::microstrain::Serializer& serializer, const GloEphemeris& self) { insert(serializer, self.index); @@ -1109,7 +1109,7 @@ void insert(::microstrain::Buffer& serializer, const GloEphemeris& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GloEphemeris& self) +void extract(::microstrain::Serializer& serializer, GloEphemeris& self) { extract(serializer, self.index); @@ -1166,7 +1166,7 @@ void extract(::microstrain::Buffer& serializer, GloEphemeris& self) } -void insert(::microstrain::Buffer& serializer, const GpsIonoCorr& self) +void insert(::microstrain::Serializer& serializer, const GpsIonoCorr& self) { insert(serializer, self.time_of_week); @@ -1181,7 +1181,7 @@ void insert(::microstrain::Buffer& serializer, const GpsIonoCorr& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GpsIonoCorr& self) +void extract(::microstrain::Serializer& serializer, GpsIonoCorr& self) { extract(serializer, self.time_of_week); @@ -1197,7 +1197,7 @@ void extract(::microstrain::Buffer& serializer, GpsIonoCorr& self) } -void insert(::microstrain::Buffer& serializer, const GalileoIonoCorr& self) +void insert(::microstrain::Serializer& serializer, const GalileoIonoCorr& self) { insert(serializer, self.time_of_week); @@ -1211,7 +1211,7 @@ void insert(::microstrain::Buffer& serializer, const GalileoIonoCorr& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GalileoIonoCorr& self) +void extract(::microstrain::Serializer& serializer, GalileoIonoCorr& self) { extract(serializer, self.time_of_week); diff --git a/src/mip/definitions/data_gnss.hpp b/src/mip/definitions/data_gnss.hpp index 64fa0af5f..682a5cbc2 100644 --- a/src/mip/definitions/data_gnss.hpp +++ b/src/mip/definitions/data_gnss.hpp @@ -241,8 +241,8 @@ struct PosLlh return std::make_tuple(std::ref(latitude),std::ref(longitude),std::ref(ellipsoid_height),std::ref(msl_height),std::ref(horizontal_accuracy),std::ref(vertical_accuracy),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const PosLlh& self); -void extract(::microstrain::Buffer& serializer, PosLlh& self); +void insert(::microstrain::Serializer& serializer, const PosLlh& self); +void extract(::microstrain::Serializer& serializer, PosLlh& self); ///@} @@ -307,8 +307,8 @@ struct PosEcef return std::make_tuple(std::ref(x[0]),std::ref(x[1]),std::ref(x[2]),std::ref(x_accuracy),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const PosEcef& self); -void extract(::microstrain::Buffer& serializer, PosEcef& self); +void insert(::microstrain::Serializer& serializer, const PosEcef& self); +void extract(::microstrain::Serializer& serializer, PosEcef& self); ///@} @@ -389,8 +389,8 @@ struct VelNed return std::make_tuple(std::ref(v[0]),std::ref(v[1]),std::ref(v[2]),std::ref(speed),std::ref(ground_speed),std::ref(heading),std::ref(speed_accuracy),std::ref(heading_accuracy),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const VelNed& self); -void extract(::microstrain::Buffer& serializer, VelNed& self); +void insert(::microstrain::Serializer& serializer, const VelNed& self); +void extract(::microstrain::Serializer& serializer, VelNed& self); ///@} @@ -455,8 +455,8 @@ struct VelEcef return std::make_tuple(std::ref(v[0]),std::ref(v[1]),std::ref(v[2]),std::ref(v_accuracy),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const VelEcef& self); -void extract(::microstrain::Buffer& serializer, VelEcef& self); +void insert(::microstrain::Serializer& serializer, const VelEcef& self); +void extract(::microstrain::Serializer& serializer, VelEcef& self); ///@} @@ -541,8 +541,8 @@ struct Dop return std::make_tuple(std::ref(gdop),std::ref(pdop),std::ref(hdop),std::ref(vdop),std::ref(tdop),std::ref(ndop),std::ref(edop),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const Dop& self); -void extract(::microstrain::Buffer& serializer, Dop& self); +void insert(::microstrain::Serializer& serializer, const Dop& self); +void extract(::microstrain::Serializer& serializer, Dop& self); ///@} @@ -612,8 +612,8 @@ struct UtcTime return std::make_tuple(std::ref(year),std::ref(month),std::ref(day),std::ref(hour),std::ref(min),std::ref(sec),std::ref(msec),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const UtcTime& self); -void extract(::microstrain::Buffer& serializer, UtcTime& self); +void insert(::microstrain::Serializer& serializer, const UtcTime& self); +void extract(::microstrain::Serializer& serializer, UtcTime& self); ///@} @@ -678,8 +678,8 @@ struct GpsTime return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GpsTime& self); -void extract(::microstrain::Buffer& serializer, GpsTime& self); +void insert(::microstrain::Serializer& serializer, const GpsTime& self); +void extract(::microstrain::Serializer& serializer, GpsTime& self); ///@} @@ -748,8 +748,8 @@ struct ClockInfo return std::make_tuple(std::ref(bias),std::ref(drift),std::ref(accuracy_estimate),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const ClockInfo& self); -void extract(::microstrain::Buffer& serializer, ClockInfo& self); +void insert(::microstrain::Serializer& serializer, const ClockInfo& self); +void extract(::microstrain::Serializer& serializer, ClockInfo& self); ///@} @@ -858,8 +858,8 @@ struct FixInfo return std::make_tuple(std::ref(fix_type),std::ref(num_sv),std::ref(fix_flags),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const FixInfo& self); -void extract(::microstrain::Buffer& serializer, FixInfo& self); +void insert(::microstrain::Serializer& serializer, const FixInfo& self); +void extract(::microstrain::Serializer& serializer, FixInfo& self); ///@} @@ -970,8 +970,8 @@ struct SvInfo return std::make_tuple(std::ref(channel),std::ref(sv_id),std::ref(carrier_noise_ratio),std::ref(azimuth),std::ref(elevation),std::ref(sv_flags),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const SvInfo& self); -void extract(::microstrain::Buffer& serializer, SvInfo& self); +void insert(::microstrain::Serializer& serializer, const SvInfo& self); +void extract(::microstrain::Serializer& serializer, SvInfo& self); ///@} @@ -1063,8 +1063,8 @@ struct HwStatus return std::make_tuple(std::ref(receiver_state),std::ref(antenna_state),std::ref(antenna_power),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const HwStatus& self); -void extract(::microstrain::Buffer& serializer, HwStatus& self); +void insert(::microstrain::Serializer& serializer, const HwStatus& self); +void extract(::microstrain::Serializer& serializer, HwStatus& self); ///@} @@ -1149,8 +1149,8 @@ struct DgpsInfo return std::make_tuple(std::ref(sv_id),std::ref(age),std::ref(range_correction),std::ref(range_rate_correction),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const DgpsInfo& self); -void extract(::microstrain::Buffer& serializer, DgpsInfo& self); +void insert(::microstrain::Serializer& serializer, const DgpsInfo& self); +void extract(::microstrain::Serializer& serializer, DgpsInfo& self); ///@} @@ -1225,8 +1225,8 @@ struct DgpsChannel return std::make_tuple(std::ref(sv_id),std::ref(age),std::ref(range_correction),std::ref(range_rate_correction),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const DgpsChannel& self); -void extract(::microstrain::Buffer& serializer, DgpsChannel& self); +void insert(::microstrain::Serializer& serializer, const DgpsChannel& self); +void extract(::microstrain::Serializer& serializer, DgpsChannel& self); ///@} @@ -1301,8 +1301,8 @@ struct ClockInfo2 return std::make_tuple(std::ref(bias),std::ref(drift),std::ref(bias_accuracy_estimate),std::ref(drift_accuracy_estimate),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const ClockInfo2& self); -void extract(::microstrain::Buffer& serializer, ClockInfo2& self); +void insert(::microstrain::Serializer& serializer, const ClockInfo2& self); +void extract(::microstrain::Serializer& serializer, ClockInfo2& self); ///@} @@ -1360,8 +1360,8 @@ struct GpsLeapSeconds return std::make_tuple(std::ref(leap_seconds),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GpsLeapSeconds& self); -void extract(::microstrain::Buffer& serializer, GpsLeapSeconds& self); +void insert(::microstrain::Serializer& serializer, const GpsLeapSeconds& self); +void extract(::microstrain::Serializer& serializer, GpsLeapSeconds& self); ///@} @@ -1476,8 +1476,8 @@ struct SbasInfo return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(sbas_system),std::ref(sbas_id),std::ref(count),std::ref(sbas_status),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const SbasInfo& self); -void extract(::microstrain::Buffer& serializer, SbasInfo& self); +void insert(::microstrain::Serializer& serializer, const SbasInfo& self); +void extract(::microstrain::Serializer& serializer, SbasInfo& self); ///@} @@ -1574,8 +1574,8 @@ struct SbasCorrection return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(gnss_id),std::ref(sv_id),std::ref(udrei),std::ref(pseudorange_correction),std::ref(iono_correction),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const SbasCorrection& self); -void extract(::microstrain::Buffer& serializer, SbasCorrection& self); +void insert(::microstrain::Serializer& serializer, const SbasCorrection& self); +void extract(::microstrain::Serializer& serializer, SbasCorrection& self); ///@} @@ -1669,8 +1669,8 @@ struct RfErrorDetection return std::make_tuple(std::ref(rf_band),std::ref(jamming_state),std::ref(spoofing_state),std::ref(reserved),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const RfErrorDetection& self); -void extract(::microstrain::Buffer& serializer, RfErrorDetection& self); +void insert(::microstrain::Serializer& serializer, const RfErrorDetection& self); +void extract(::microstrain::Serializer& serializer, RfErrorDetection& self); ///@} @@ -1802,8 +1802,8 @@ struct BaseStationInfo return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(ecef_pos[0]),std::ref(ecef_pos[1]),std::ref(ecef_pos[2]),std::ref(height),std::ref(station_id),std::ref(indicators),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const BaseStationInfo& self); -void extract(::microstrain::Buffer& serializer, BaseStationInfo& self); +void insert(::microstrain::Serializer& serializer, const BaseStationInfo& self); +void extract(::microstrain::Serializer& serializer, BaseStationInfo& self); ///@} @@ -1941,8 +1941,8 @@ struct RtkCorrectionsStatus return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(epoch_status),std::ref(dongle_status),std::ref(gps_correction_latency),std::ref(glonass_correction_latency),std::ref(galileo_correction_latency),std::ref(beidou_correction_latency),std::ref(reserved),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const RtkCorrectionsStatus& self); -void extract(::microstrain::Buffer& serializer, RtkCorrectionsStatus& self); +void insert(::microstrain::Serializer& serializer, const RtkCorrectionsStatus& self); +void extract(::microstrain::Serializer& serializer, RtkCorrectionsStatus& self); ///@} @@ -2029,8 +2029,8 @@ struct SatelliteStatus return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(gnss_id),std::ref(satellite_id),std::ref(elevation),std::ref(azimuth),std::ref(health),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const SatelliteStatus& self); -void extract(::microstrain::Buffer& serializer, SatelliteStatus& self); +void insert(::microstrain::Serializer& serializer, const SatelliteStatus& self); +void extract(::microstrain::Serializer& serializer, SatelliteStatus& self); ///@} @@ -2163,8 +2163,8 @@ struct Raw return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(receiver_id),std::ref(tracking_channel),std::ref(gnss_id),std::ref(satellite_id),std::ref(signal_id),std::ref(signal_strength),std::ref(quality),std::ref(pseudorange),std::ref(carrier_phase),std::ref(doppler),std::ref(range_uncert),std::ref(phase_uncert),std::ref(doppler_uncert),std::ref(lock_time),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const Raw& self); -void extract(::microstrain::Buffer& serializer, Raw& self); +void insert(::microstrain::Serializer& serializer, const Raw& self); +void extract(::microstrain::Serializer& serializer, Raw& self); ///@} @@ -2260,8 +2260,8 @@ struct GpsEphemeris return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(satellite_id),std::ref(health),std::ref(iodc),std::ref(iode),std::ref(t_oc),std::ref(af0),std::ref(af1),std::ref(af2),std::ref(t_gd),std::ref(ISC_L1CA),std::ref(ISC_L2C),std::ref(t_oe),std::ref(a),std::ref(a_dot),std::ref(mean_anomaly),std::ref(delta_mean_motion),std::ref(delta_mean_motion_dot),std::ref(eccentricity),std::ref(argument_of_perigee),std::ref(omega),std::ref(omega_dot),std::ref(inclination),std::ref(inclination_dot),std::ref(c_ic),std::ref(c_is),std::ref(c_uc),std::ref(c_us),std::ref(c_rc),std::ref(c_rs),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GpsEphemeris& self); -void extract(::microstrain::Buffer& serializer, GpsEphemeris& self); +void insert(::microstrain::Serializer& serializer, const GpsEphemeris& self); +void extract(::microstrain::Serializer& serializer, GpsEphemeris& self); ///@} @@ -2357,8 +2357,8 @@ struct GalileoEphemeris return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(satellite_id),std::ref(health),std::ref(iodc),std::ref(iode),std::ref(t_oc),std::ref(af0),std::ref(af1),std::ref(af2),std::ref(t_gd),std::ref(ISC_L1CA),std::ref(ISC_L2C),std::ref(t_oe),std::ref(a),std::ref(a_dot),std::ref(mean_anomaly),std::ref(delta_mean_motion),std::ref(delta_mean_motion_dot),std::ref(eccentricity),std::ref(argument_of_perigee),std::ref(omega),std::ref(omega_dot),std::ref(inclination),std::ref(inclination_dot),std::ref(c_ic),std::ref(c_is),std::ref(c_uc),std::ref(c_us),std::ref(c_rc),std::ref(c_rs),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GalileoEphemeris& self); -void extract(::microstrain::Buffer& serializer, GalileoEphemeris& self); +void insert(::microstrain::Serializer& serializer, const GalileoEphemeris& self); +void extract(::microstrain::Serializer& serializer, GalileoEphemeris& self); ///@} @@ -2442,8 +2442,8 @@ struct GloEphemeris return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(satellite_id),std::ref(freq_number),std::ref(tk),std::ref(tb),std::ref(sat_type),std::ref(gamma),std::ref(tau_n),std::ref(x[0]),std::ref(x[1]),std::ref(x[2]),std::ref(v[0]),std::ref(v[1]),std::ref(v[2]),std::ref(a[0]),std::ref(a[1]),std::ref(a[2]),std::ref(health),std::ref(P),std::ref(NT),std::ref(delta_tau_n),std::ref(Ft),std::ref(En),std::ref(P1),std::ref(P2),std::ref(P3),std::ref(P4),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GloEphemeris& self); -void extract(::microstrain::Buffer& serializer, GloEphemeris& self); +void insert(::microstrain::Serializer& serializer, const GloEphemeris& self); +void extract(::microstrain::Serializer& serializer, GloEphemeris& self); ///@} @@ -2516,8 +2516,8 @@ struct GpsIonoCorr return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(alpha),std::ref(beta),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GpsIonoCorr& self); -void extract(::microstrain::Buffer& serializer, GpsIonoCorr& self); +void insert(::microstrain::Serializer& serializer, const GpsIonoCorr& self); +void extract(::microstrain::Serializer& serializer, GpsIonoCorr& self); ///@} @@ -2590,8 +2590,8 @@ struct GalileoIonoCorr return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(alpha[0]),std::ref(alpha[1]),std::ref(alpha[2]),std::ref(disturbance_flags),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GalileoIonoCorr& self); -void extract(::microstrain::Buffer& serializer, GalileoIonoCorr& self); +void insert(::microstrain::Serializer& serializer, const GalileoIonoCorr& self); +void extract(::microstrain::Serializer& serializer, GalileoIonoCorr& self); ///@} diff --git a/src/mip/definitions/data_sensor.cpp b/src/mip/definitions/data_sensor.cpp index 40c906b86..b6e231669 100644 --- a/src/mip/definitions/data_sensor.cpp +++ b/src/mip/definitions/data_sensor.cpp @@ -1,7 +1,7 @@ #include "data_sensor.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -29,159 +29,159 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const RawAccel& self) +void insert(::microstrain::Serializer& serializer, const RawAccel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.raw_accel[i]); } -void extract(::microstrain::Buffer& serializer, RawAccel& self) +void extract(::microstrain::Serializer& serializer, RawAccel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.raw_accel[i]); } -void insert(::microstrain::Buffer& serializer, const RawGyro& self) +void insert(::microstrain::Serializer& serializer, const RawGyro& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.raw_gyro[i]); } -void extract(::microstrain::Buffer& serializer, RawGyro& self) +void extract(::microstrain::Serializer& serializer, RawGyro& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.raw_gyro[i]); } -void insert(::microstrain::Buffer& serializer, const RawMag& self) +void insert(::microstrain::Serializer& serializer, const RawMag& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.raw_mag[i]); } -void extract(::microstrain::Buffer& serializer, RawMag& self) +void extract(::microstrain::Serializer& serializer, RawMag& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.raw_mag[i]); } -void insert(::microstrain::Buffer& serializer, const RawPressure& self) +void insert(::microstrain::Serializer& serializer, const RawPressure& self) { insert(serializer, self.raw_pressure); } -void extract(::microstrain::Buffer& serializer, RawPressure& self) +void extract(::microstrain::Serializer& serializer, RawPressure& self) { extract(serializer, self.raw_pressure); } -void insert(::microstrain::Buffer& serializer, const ScaledAccel& self) +void insert(::microstrain::Serializer& serializer, const ScaledAccel& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scaled_accel[i]); } -void extract(::microstrain::Buffer& serializer, ScaledAccel& self) +void extract(::microstrain::Serializer& serializer, ScaledAccel& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scaled_accel[i]); } -void insert(::microstrain::Buffer& serializer, const ScaledGyro& self) +void insert(::microstrain::Serializer& serializer, const ScaledGyro& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scaled_gyro[i]); } -void extract(::microstrain::Buffer& serializer, ScaledGyro& self) +void extract(::microstrain::Serializer& serializer, ScaledGyro& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scaled_gyro[i]); } -void insert(::microstrain::Buffer& serializer, const ScaledMag& self) +void insert(::microstrain::Serializer& serializer, const ScaledMag& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.scaled_mag[i]); } -void extract(::microstrain::Buffer& serializer, ScaledMag& self) +void extract(::microstrain::Serializer& serializer, ScaledMag& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.scaled_mag[i]); } -void insert(::microstrain::Buffer& serializer, const ScaledPressure& self) +void insert(::microstrain::Serializer& serializer, const ScaledPressure& self) { insert(serializer, self.scaled_pressure); } -void extract(::microstrain::Buffer& serializer, ScaledPressure& self) +void extract(::microstrain::Serializer& serializer, ScaledPressure& self) { extract(serializer, self.scaled_pressure); } -void insert(::microstrain::Buffer& serializer, const DeltaTheta& self) +void insert(::microstrain::Serializer& serializer, const DeltaTheta& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.delta_theta[i]); } -void extract(::microstrain::Buffer& serializer, DeltaTheta& self) +void extract(::microstrain::Serializer& serializer, DeltaTheta& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.delta_theta[i]); } -void insert(::microstrain::Buffer& serializer, const DeltaVelocity& self) +void insert(::microstrain::Serializer& serializer, const DeltaVelocity& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.delta_velocity[i]); } -void extract(::microstrain::Buffer& serializer, DeltaVelocity& self) +void extract(::microstrain::Serializer& serializer, DeltaVelocity& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.delta_velocity[i]); } -void insert(::microstrain::Buffer& serializer, const CompOrientationMatrix& self) +void insert(::microstrain::Serializer& serializer, const CompOrientationMatrix& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.m[i]); } -void extract(::microstrain::Buffer& serializer, CompOrientationMatrix& self) +void extract(::microstrain::Serializer& serializer, CompOrientationMatrix& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.m[i]); } -void insert(::microstrain::Buffer& serializer, const CompQuaternion& self) +void insert(::microstrain::Serializer& serializer, const CompQuaternion& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.q[i]); } -void extract(::microstrain::Buffer& serializer, CompQuaternion& self) +void extract(::microstrain::Serializer& serializer, CompQuaternion& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.q[i]); } -void insert(::microstrain::Buffer& serializer, const CompEulerAngles& self) +void insert(::microstrain::Serializer& serializer, const CompEulerAngles& self) { insert(serializer, self.roll); @@ -190,7 +190,7 @@ void insert(::microstrain::Buffer& serializer, const CompEulerAngles& self) insert(serializer, self.yaw); } -void extract(::microstrain::Buffer& serializer, CompEulerAngles& self) +void extract(::microstrain::Serializer& serializer, CompEulerAngles& self) { extract(serializer, self.roll); @@ -200,51 +200,51 @@ void extract(::microstrain::Buffer& serializer, CompEulerAngles& self) } -void insert(::microstrain::Buffer& serializer, const CompOrientationUpdateMatrix& self) +void insert(::microstrain::Serializer& serializer, const CompOrientationUpdateMatrix& self) { for(unsigned int i=0; i < 9; i++) insert(serializer, self.m[i]); } -void extract(::microstrain::Buffer& serializer, CompOrientationUpdateMatrix& self) +void extract(::microstrain::Serializer& serializer, CompOrientationUpdateMatrix& self) { for(unsigned int i=0; i < 9; i++) extract(serializer, self.m[i]); } -void insert(::microstrain::Buffer& serializer, const OrientationRawTemp& self) +void insert(::microstrain::Serializer& serializer, const OrientationRawTemp& self) { for(unsigned int i=0; i < 4; i++) insert(serializer, self.raw_temp[i]); } -void extract(::microstrain::Buffer& serializer, OrientationRawTemp& self) +void extract(::microstrain::Serializer& serializer, OrientationRawTemp& self) { for(unsigned int i=0; i < 4; i++) extract(serializer, self.raw_temp[i]); } -void insert(::microstrain::Buffer& serializer, const InternalTimestamp& self) +void insert(::microstrain::Serializer& serializer, const InternalTimestamp& self) { insert(serializer, self.counts); } -void extract(::microstrain::Buffer& serializer, InternalTimestamp& self) +void extract(::microstrain::Serializer& serializer, InternalTimestamp& self) { extract(serializer, self.counts); } -void insert(::microstrain::Buffer& serializer, const PpsTimestamp& self) +void insert(::microstrain::Serializer& serializer, const PpsTimestamp& self) { insert(serializer, self.seconds); insert(serializer, self.useconds); } -void extract(::microstrain::Buffer& serializer, PpsTimestamp& self) +void extract(::microstrain::Serializer& serializer, PpsTimestamp& self) { extract(serializer, self.seconds); @@ -252,7 +252,7 @@ void extract(::microstrain::Buffer& serializer, PpsTimestamp& self) } -void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self) +void insert(::microstrain::Serializer& serializer, const GpsTimestamp& self) { insert(serializer, self.tow); @@ -261,7 +261,7 @@ void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GpsTimestamp& self) +void extract(::microstrain::Serializer& serializer, GpsTimestamp& self) { extract(serializer, self.tow); @@ -271,7 +271,7 @@ void extract(::microstrain::Buffer& serializer, GpsTimestamp& self) } -void insert(::microstrain::Buffer& serializer, const TemperatureAbs& self) +void insert(::microstrain::Serializer& serializer, const TemperatureAbs& self) { insert(serializer, self.min_temp); @@ -280,7 +280,7 @@ void insert(::microstrain::Buffer& serializer, const TemperatureAbs& self) insert(serializer, self.mean_temp); } -void extract(::microstrain::Buffer& serializer, TemperatureAbs& self) +void extract(::microstrain::Serializer& serializer, TemperatureAbs& self) { extract(serializer, self.min_temp); @@ -290,44 +290,44 @@ void extract(::microstrain::Buffer& serializer, TemperatureAbs& self) } -void insert(::microstrain::Buffer& serializer, const UpVector& self) +void insert(::microstrain::Serializer& serializer, const UpVector& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.up[i]); } -void extract(::microstrain::Buffer& serializer, UpVector& self) +void extract(::microstrain::Serializer& serializer, UpVector& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.up[i]); } -void insert(::microstrain::Buffer& serializer, const NorthVector& self) +void insert(::microstrain::Serializer& serializer, const NorthVector& self) { for(unsigned int i=0; i < 3; i++) insert(serializer, self.north[i]); } -void extract(::microstrain::Buffer& serializer, NorthVector& self) +void extract(::microstrain::Serializer& serializer, NorthVector& self) { for(unsigned int i=0; i < 3; i++) extract(serializer, self.north[i]); } -void insert(::microstrain::Buffer& serializer, const OverrangeStatus& self) +void insert(::microstrain::Serializer& serializer, const OverrangeStatus& self) { insert(serializer, self.status); } -void extract(::microstrain::Buffer& serializer, OverrangeStatus& self) +void extract(::microstrain::Serializer& serializer, OverrangeStatus& self) { extract(serializer, self.status); } -void insert(::microstrain::Buffer& serializer, const OdometerData& self) +void insert(::microstrain::Serializer& serializer, const OdometerData& self) { insert(serializer, self.speed); @@ -336,7 +336,7 @@ void insert(::microstrain::Buffer& serializer, const OdometerData& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, OdometerData& self) +void extract(::microstrain::Serializer& serializer, OdometerData& self) { extract(serializer, self.speed); diff --git a/src/mip/definitions/data_sensor.hpp b/src/mip/definitions/data_sensor.hpp index f64032adf..2dd9cb7e7 100644 --- a/src/mip/definitions/data_sensor.hpp +++ b/src/mip/definitions/data_sensor.hpp @@ -98,8 +98,8 @@ struct RawAccel return std::make_tuple(std::ref(raw_accel[0]),std::ref(raw_accel[1]),std::ref(raw_accel[2])); } }; -void insert(::microstrain::Buffer& serializer, const RawAccel& self); -void extract(::microstrain::Buffer& serializer, RawAccel& self); +void insert(::microstrain::Serializer& serializer, const RawAccel& self); +void extract(::microstrain::Serializer& serializer, RawAccel& self); ///@} @@ -132,8 +132,8 @@ struct RawGyro return std::make_tuple(std::ref(raw_gyro[0]),std::ref(raw_gyro[1]),std::ref(raw_gyro[2])); } }; -void insert(::microstrain::Buffer& serializer, const RawGyro& self); -void extract(::microstrain::Buffer& serializer, RawGyro& self); +void insert(::microstrain::Serializer& serializer, const RawGyro& self); +void extract(::microstrain::Serializer& serializer, RawGyro& self); ///@} @@ -166,8 +166,8 @@ struct RawMag return std::make_tuple(std::ref(raw_mag[0]),std::ref(raw_mag[1]),std::ref(raw_mag[2])); } }; -void insert(::microstrain::Buffer& serializer, const RawMag& self); -void extract(::microstrain::Buffer& serializer, RawMag& self); +void insert(::microstrain::Serializer& serializer, const RawMag& self); +void extract(::microstrain::Serializer& serializer, RawMag& self); ///@} @@ -200,8 +200,8 @@ struct RawPressure return std::make_tuple(std::ref(raw_pressure)); } }; -void insert(::microstrain::Buffer& serializer, const RawPressure& self); -void extract(::microstrain::Buffer& serializer, RawPressure& self); +void insert(::microstrain::Serializer& serializer, const RawPressure& self); +void extract(::microstrain::Serializer& serializer, RawPressure& self); ///@} @@ -234,8 +234,8 @@ struct ScaledAccel return std::make_tuple(std::ref(scaled_accel[0]),std::ref(scaled_accel[1]),std::ref(scaled_accel[2])); } }; -void insert(::microstrain::Buffer& serializer, const ScaledAccel& self); -void extract(::microstrain::Buffer& serializer, ScaledAccel& self); +void insert(::microstrain::Serializer& serializer, const ScaledAccel& self); +void extract(::microstrain::Serializer& serializer, ScaledAccel& self); ///@} @@ -268,8 +268,8 @@ struct ScaledGyro return std::make_tuple(std::ref(scaled_gyro[0]),std::ref(scaled_gyro[1]),std::ref(scaled_gyro[2])); } }; -void insert(::microstrain::Buffer& serializer, const ScaledGyro& self); -void extract(::microstrain::Buffer& serializer, ScaledGyro& self); +void insert(::microstrain::Serializer& serializer, const ScaledGyro& self); +void extract(::microstrain::Serializer& serializer, ScaledGyro& self); ///@} @@ -302,8 +302,8 @@ struct ScaledMag return std::make_tuple(std::ref(scaled_mag[0]),std::ref(scaled_mag[1]),std::ref(scaled_mag[2])); } }; -void insert(::microstrain::Buffer& serializer, const ScaledMag& self); -void extract(::microstrain::Buffer& serializer, ScaledMag& self); +void insert(::microstrain::Serializer& serializer, const ScaledMag& self); +void extract(::microstrain::Serializer& serializer, ScaledMag& self); ///@} @@ -335,8 +335,8 @@ struct ScaledPressure return std::make_tuple(std::ref(scaled_pressure)); } }; -void insert(::microstrain::Buffer& serializer, const ScaledPressure& self); -void extract(::microstrain::Buffer& serializer, ScaledPressure& self); +void insert(::microstrain::Serializer& serializer, const ScaledPressure& self); +void extract(::microstrain::Serializer& serializer, ScaledPressure& self); ///@} @@ -369,8 +369,8 @@ struct DeltaTheta return std::make_tuple(std::ref(delta_theta[0]),std::ref(delta_theta[1]),std::ref(delta_theta[2])); } }; -void insert(::microstrain::Buffer& serializer, const DeltaTheta& self); -void extract(::microstrain::Buffer& serializer, DeltaTheta& self); +void insert(::microstrain::Serializer& serializer, const DeltaTheta& self); +void extract(::microstrain::Serializer& serializer, DeltaTheta& self); ///@} @@ -403,8 +403,8 @@ struct DeltaVelocity return std::make_tuple(std::ref(delta_velocity[0]),std::ref(delta_velocity[1]),std::ref(delta_velocity[2])); } }; -void insert(::microstrain::Buffer& serializer, const DeltaVelocity& self); -void extract(::microstrain::Buffer& serializer, DeltaVelocity& self); +void insert(::microstrain::Serializer& serializer, const DeltaVelocity& self); +void extract(::microstrain::Serializer& serializer, DeltaVelocity& self); ///@} @@ -446,8 +446,8 @@ struct CompOrientationMatrix return std::make_tuple(std::ref(m[0]),std::ref(m[1]),std::ref(m[2]),std::ref(m[3]),std::ref(m[4]),std::ref(m[5]),std::ref(m[6]),std::ref(m[7]),std::ref(m[8])); } }; -void insert(::microstrain::Buffer& serializer, const CompOrientationMatrix& self); -void extract(::microstrain::Buffer& serializer, CompOrientationMatrix& self); +void insert(::microstrain::Serializer& serializer, const CompOrientationMatrix& self); +void extract(::microstrain::Serializer& serializer, CompOrientationMatrix& self); ///@} @@ -487,8 +487,8 @@ struct CompQuaternion return std::make_tuple(std::ref(q[0]),std::ref(q[1]),std::ref(q[2]),std::ref(q[3])); } }; -void insert(::microstrain::Buffer& serializer, const CompQuaternion& self); -void extract(::microstrain::Buffer& serializer, CompQuaternion& self); +void insert(::microstrain::Serializer& serializer, const CompQuaternion& self); +void extract(::microstrain::Serializer& serializer, CompQuaternion& self); ///@} @@ -523,8 +523,8 @@ struct CompEulerAngles return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); } }; -void insert(::microstrain::Buffer& serializer, const CompEulerAngles& self); -void extract(::microstrain::Buffer& serializer, CompEulerAngles& self); +void insert(::microstrain::Serializer& serializer, const CompEulerAngles& self); +void extract(::microstrain::Serializer& serializer, CompEulerAngles& self); ///@} @@ -556,8 +556,8 @@ struct CompOrientationUpdateMatrix return std::make_tuple(std::ref(m[0]),std::ref(m[1]),std::ref(m[2]),std::ref(m[3]),std::ref(m[4]),std::ref(m[5]),std::ref(m[6]),std::ref(m[7]),std::ref(m[8])); } }; -void insert(::microstrain::Buffer& serializer, const CompOrientationUpdateMatrix& self); -void extract(::microstrain::Buffer& serializer, CompOrientationUpdateMatrix& self); +void insert(::microstrain::Serializer& serializer, const CompOrientationUpdateMatrix& self); +void extract(::microstrain::Serializer& serializer, CompOrientationUpdateMatrix& self); ///@} @@ -589,8 +589,8 @@ struct OrientationRawTemp return std::make_tuple(std::ref(raw_temp)); } }; -void insert(::microstrain::Buffer& serializer, const OrientationRawTemp& self); -void extract(::microstrain::Buffer& serializer, OrientationRawTemp& self); +void insert(::microstrain::Serializer& serializer, const OrientationRawTemp& self); +void extract(::microstrain::Serializer& serializer, OrientationRawTemp& self); ///@} @@ -622,8 +622,8 @@ struct InternalTimestamp return std::make_tuple(std::ref(counts)); } }; -void insert(::microstrain::Buffer& serializer, const InternalTimestamp& self); -void extract(::microstrain::Buffer& serializer, InternalTimestamp& self); +void insert(::microstrain::Serializer& serializer, const InternalTimestamp& self); +void extract(::microstrain::Serializer& serializer, InternalTimestamp& self); ///@} @@ -656,8 +656,8 @@ struct PpsTimestamp return std::make_tuple(std::ref(seconds),std::ref(useconds)); } }; -void insert(::microstrain::Buffer& serializer, const PpsTimestamp& self); -void extract(::microstrain::Buffer& serializer, PpsTimestamp& self); +void insert(::microstrain::Serializer& serializer, const PpsTimestamp& self); +void extract(::microstrain::Serializer& serializer, PpsTimestamp& self); ///@} @@ -734,8 +734,8 @@ struct GpsTimestamp return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self); -void extract(::microstrain::Buffer& serializer, GpsTimestamp& self); +void insert(::microstrain::Serializer& serializer, const GpsTimestamp& self); +void extract(::microstrain::Serializer& serializer, GpsTimestamp& self); ///@} @@ -773,8 +773,8 @@ struct TemperatureAbs return std::make_tuple(std::ref(min_temp),std::ref(max_temp),std::ref(mean_temp)); } }; -void insert(::microstrain::Buffer& serializer, const TemperatureAbs& self); -void extract(::microstrain::Buffer& serializer, TemperatureAbs& self); +void insert(::microstrain::Serializer& serializer, const TemperatureAbs& self); +void extract(::microstrain::Serializer& serializer, TemperatureAbs& self); ///@} @@ -812,8 +812,8 @@ struct UpVector return std::make_tuple(std::ref(up[0]),std::ref(up[1]),std::ref(up[2])); } }; -void insert(::microstrain::Buffer& serializer, const UpVector& self); -void extract(::microstrain::Buffer& serializer, UpVector& self); +void insert(::microstrain::Serializer& serializer, const UpVector& self); +void extract(::microstrain::Serializer& serializer, UpVector& self); ///@} @@ -848,8 +848,8 @@ struct NorthVector return std::make_tuple(std::ref(north[0]),std::ref(north[1]),std::ref(north[2])); } }; -void insert(::microstrain::Buffer& serializer, const NorthVector& self); -void extract(::microstrain::Buffer& serializer, NorthVector& self); +void insert(::microstrain::Serializer& serializer, const NorthVector& self); +void extract(::microstrain::Serializer& serializer, NorthVector& self); ///@} @@ -932,8 +932,8 @@ struct OverrangeStatus return std::make_tuple(std::ref(status)); } }; -void insert(::microstrain::Buffer& serializer, const OverrangeStatus& self); -void extract(::microstrain::Buffer& serializer, OverrangeStatus& self); +void insert(::microstrain::Serializer& serializer, const OverrangeStatus& self); +void extract(::microstrain::Serializer& serializer, OverrangeStatus& self); ///@} @@ -966,8 +966,8 @@ struct OdometerData return std::make_tuple(std::ref(speed),std::ref(uncertainty),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const OdometerData& self); -void extract(::microstrain::Buffer& serializer, OdometerData& self); +void insert(::microstrain::Serializer& serializer, const OdometerData& self); +void extract(::microstrain::Serializer& serializer, OdometerData& self); ///@} diff --git a/src/mip/definitions/data_shared.cpp b/src/mip/definitions/data_shared.cpp index c9963b440..8b6097091 100644 --- a/src/mip/definitions/data_shared.cpp +++ b/src/mip/definitions/data_shared.cpp @@ -1,7 +1,7 @@ #include "data_shared.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -29,40 +29,40 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const EventSource& self) +void insert(::microstrain::Serializer& serializer, const EventSource& self) { insert(serializer, self.trigger_id); } -void extract(::microstrain::Buffer& serializer, EventSource& self) +void extract(::microstrain::Serializer& serializer, EventSource& self) { extract(serializer, self.trigger_id); } -void insert(::microstrain::Buffer& serializer, const Ticks& self) +void insert(::microstrain::Serializer& serializer, const Ticks& self) { insert(serializer, self.ticks); } -void extract(::microstrain::Buffer& serializer, Ticks& self) +void extract(::microstrain::Serializer& serializer, Ticks& self) { extract(serializer, self.ticks); } -void insert(::microstrain::Buffer& serializer, const DeltaTicks& self) +void insert(::microstrain::Serializer& serializer, const DeltaTicks& self) { insert(serializer, self.ticks); } -void extract(::microstrain::Buffer& serializer, DeltaTicks& self) +void extract(::microstrain::Serializer& serializer, DeltaTicks& self) { extract(serializer, self.ticks); } -void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self) +void insert(::microstrain::Serializer& serializer, const GpsTimestamp& self) { insert(serializer, self.tow); @@ -71,7 +71,7 @@ void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self) insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, GpsTimestamp& self) +void extract(::microstrain::Serializer& serializer, GpsTimestamp& self) { extract(serializer, self.tow); @@ -81,47 +81,47 @@ void extract(::microstrain::Buffer& serializer, GpsTimestamp& self) } -void insert(::microstrain::Buffer& serializer, const DeltaTime& self) +void insert(::microstrain::Serializer& serializer, const DeltaTime& self) { insert(serializer, self.seconds); } -void extract(::microstrain::Buffer& serializer, DeltaTime& self) +void extract(::microstrain::Serializer& serializer, DeltaTime& self) { extract(serializer, self.seconds); } -void insert(::microstrain::Buffer& serializer, const ReferenceTimestamp& self) +void insert(::microstrain::Serializer& serializer, const ReferenceTimestamp& self) { insert(serializer, self.nanoseconds); } -void extract(::microstrain::Buffer& serializer, ReferenceTimestamp& self) +void extract(::microstrain::Serializer& serializer, ReferenceTimestamp& self) { extract(serializer, self.nanoseconds); } -void insert(::microstrain::Buffer& serializer, const ReferenceTimeDelta& self) +void insert(::microstrain::Serializer& serializer, const ReferenceTimeDelta& self) { insert(serializer, self.dt_nanos); } -void extract(::microstrain::Buffer& serializer, ReferenceTimeDelta& self) +void extract(::microstrain::Serializer& serializer, ReferenceTimeDelta& self) { extract(serializer, self.dt_nanos); } -void insert(::microstrain::Buffer& serializer, const ExternalTimestamp& self) +void insert(::microstrain::Serializer& serializer, const ExternalTimestamp& self) { insert(serializer, self.nanoseconds); insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, ExternalTimestamp& self) +void extract(::microstrain::Serializer& serializer, ExternalTimestamp& self) { extract(serializer, self.nanoseconds); @@ -129,14 +129,14 @@ void extract(::microstrain::Buffer& serializer, ExternalTimestamp& self) } -void insert(::microstrain::Buffer& serializer, const ExternalTimeDelta& self) +void insert(::microstrain::Serializer& serializer, const ExternalTimeDelta& self) { insert(serializer, self.dt_nanos); insert(serializer, self.valid_flags); } -void extract(::microstrain::Buffer& serializer, ExternalTimeDelta& self) +void extract(::microstrain::Serializer& serializer, ExternalTimeDelta& self) { extract(serializer, self.dt_nanos); diff --git a/src/mip/definitions/data_shared.hpp b/src/mip/definitions/data_shared.hpp index 6b217a597..57455f544 100644 --- a/src/mip/definitions/data_shared.hpp +++ b/src/mip/definitions/data_shared.hpp @@ -85,8 +85,8 @@ struct EventSource return std::make_tuple(std::ref(trigger_id)); } }; -void insert(::microstrain::Buffer& serializer, const EventSource& self); -void extract(::microstrain::Buffer& serializer, EventSource& self); +void insert(::microstrain::Serializer& serializer, const EventSource& self); +void extract(::microstrain::Serializer& serializer, EventSource& self); ///@} @@ -121,8 +121,8 @@ struct Ticks return std::make_tuple(std::ref(ticks)); } }; -void insert(::microstrain::Buffer& serializer, const Ticks& self); -void extract(::microstrain::Buffer& serializer, Ticks& self); +void insert(::microstrain::Serializer& serializer, const Ticks& self); +void extract(::microstrain::Serializer& serializer, Ticks& self); ///@} @@ -158,8 +158,8 @@ struct DeltaTicks return std::make_tuple(std::ref(ticks)); } }; -void insert(::microstrain::Buffer& serializer, const DeltaTicks& self); -void extract(::microstrain::Buffer& serializer, DeltaTicks& self); +void insert(::microstrain::Serializer& serializer, const DeltaTicks& self); +void extract(::microstrain::Serializer& serializer, DeltaTicks& self); ///@} @@ -227,8 +227,8 @@ struct GpsTimestamp return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const GpsTimestamp& self); -void extract(::microstrain::Buffer& serializer, GpsTimestamp& self); +void insert(::microstrain::Serializer& serializer, const GpsTimestamp& self); +void extract(::microstrain::Serializer& serializer, GpsTimestamp& self); ///@} @@ -269,8 +269,8 @@ struct DeltaTime return std::make_tuple(std::ref(seconds)); } }; -void insert(::microstrain::Buffer& serializer, const DeltaTime& self); -void extract(::microstrain::Buffer& serializer, DeltaTime& self); +void insert(::microstrain::Serializer& serializer, const DeltaTime& self); +void extract(::microstrain::Serializer& serializer, DeltaTime& self); ///@} @@ -309,8 +309,8 @@ struct ReferenceTimestamp return std::make_tuple(std::ref(nanoseconds)); } }; -void insert(::microstrain::Buffer& serializer, const ReferenceTimestamp& self); -void extract(::microstrain::Buffer& serializer, ReferenceTimestamp& self); +void insert(::microstrain::Serializer& serializer, const ReferenceTimestamp& self); +void extract(::microstrain::Serializer& serializer, ReferenceTimestamp& self); ///@} @@ -351,8 +351,8 @@ struct ReferenceTimeDelta return std::make_tuple(std::ref(dt_nanos)); } }; -void insert(::microstrain::Buffer& serializer, const ReferenceTimeDelta& self); -void extract(::microstrain::Buffer& serializer, ReferenceTimeDelta& self); +void insert(::microstrain::Serializer& serializer, const ReferenceTimeDelta& self); +void extract(::microstrain::Serializer& serializer, ReferenceTimeDelta& self); ///@} @@ -418,8 +418,8 @@ struct ExternalTimestamp return std::make_tuple(std::ref(nanoseconds),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const ExternalTimestamp& self); -void extract(::microstrain::Buffer& serializer, ExternalTimestamp& self); +void insert(::microstrain::Serializer& serializer, const ExternalTimestamp& self); +void extract(::microstrain::Serializer& serializer, ExternalTimestamp& self); ///@} @@ -489,8 +489,8 @@ struct ExternalTimeDelta return std::make_tuple(std::ref(dt_nanos),std::ref(valid_flags)); } }; -void insert(::microstrain::Buffer& serializer, const ExternalTimeDelta& self); -void extract(::microstrain::Buffer& serializer, ExternalTimeDelta& self); +void insert(::microstrain::Serializer& serializer, const ExternalTimeDelta& self); +void extract(::microstrain::Serializer& serializer, ExternalTimeDelta& self); ///@} diff --git a/src/mip/definitions/data_system.cpp b/src/mip/definitions/data_system.cpp index 2de74ac20..08abd531d 100644 --- a/src/mip/definitions/data_system.cpp +++ b/src/mip/definitions/data_system.cpp @@ -1,7 +1,7 @@ #include "data_system.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include "../mip_interface.h" #include @@ -29,27 +29,27 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Buffer& serializer, const BuiltInTest& self) +void insert(::microstrain::Serializer& serializer, const BuiltInTest& self) { for(unsigned int i=0; i < 16; i++) insert(serializer, self.result[i]); } -void extract(::microstrain::Buffer& serializer, BuiltInTest& self) +void extract(::microstrain::Serializer& serializer, BuiltInTest& self) { for(unsigned int i=0; i < 16; i++) extract(serializer, self.result[i]); } -void insert(::microstrain::Buffer& serializer, const TimeSyncStatus& self) +void insert(::microstrain::Serializer& serializer, const TimeSyncStatus& self) { insert(serializer, self.time_sync); insert(serializer, self.last_pps_rcvd); } -void extract(::microstrain::Buffer& serializer, TimeSyncStatus& self) +void extract(::microstrain::Serializer& serializer, TimeSyncStatus& self) { extract(serializer, self.time_sync); @@ -57,25 +57,25 @@ void extract(::microstrain::Buffer& serializer, TimeSyncStatus& self) } -void insert(::microstrain::Buffer& serializer, const GpioState& self) +void insert(::microstrain::Serializer& serializer, const GpioState& self) { insert(serializer, self.states); } -void extract(::microstrain::Buffer& serializer, GpioState& self) +void extract(::microstrain::Serializer& serializer, GpioState& self) { extract(serializer, self.states); } -void insert(::microstrain::Buffer& serializer, const GpioAnalogValue& self) +void insert(::microstrain::Serializer& serializer, const GpioAnalogValue& self) { insert(serializer, self.gpio_id); insert(serializer, self.value); } -void extract(::microstrain::Buffer& serializer, GpioAnalogValue& self) +void extract(::microstrain::Serializer& serializer, GpioAnalogValue& self) { extract(serializer, self.gpio_id); diff --git a/src/mip/definitions/data_system.hpp b/src/mip/definitions/data_system.hpp index cc78e7499..5bb910dde 100644 --- a/src/mip/definitions/data_system.hpp +++ b/src/mip/definitions/data_system.hpp @@ -93,8 +93,8 @@ struct BuiltInTest return std::make_tuple(std::ref(result)); } }; -void insert(::microstrain::Buffer& serializer, const BuiltInTest& self); -void extract(::microstrain::Buffer& serializer, BuiltInTest& self); +void insert(::microstrain::Serializer& serializer, const BuiltInTest& self); +void extract(::microstrain::Serializer& serializer, BuiltInTest& self); ///@} @@ -127,8 +127,8 @@ struct TimeSyncStatus return std::make_tuple(std::ref(time_sync),std::ref(last_pps_rcvd)); } }; -void insert(::microstrain::Buffer& serializer, const TimeSyncStatus& self); -void extract(::microstrain::Buffer& serializer, TimeSyncStatus& self); +void insert(::microstrain::Serializer& serializer, const TimeSyncStatus& self); +void extract(::microstrain::Serializer& serializer, TimeSyncStatus& self); ///@} @@ -178,8 +178,8 @@ struct GpioState return std::make_tuple(std::ref(states)); } }; -void insert(::microstrain::Buffer& serializer, const GpioState& self); -void extract(::microstrain::Buffer& serializer, GpioState& self); +void insert(::microstrain::Serializer& serializer, const GpioState& self); +void extract(::microstrain::Serializer& serializer, GpioState& self); ///@} @@ -213,8 +213,8 @@ struct GpioAnalogValue return std::make_tuple(std::ref(gpio_id),std::ref(value)); } }; -void insert(::microstrain::Buffer& serializer, const GpioAnalogValue& self); -void extract(::microstrain::Buffer& serializer, GpioAnalogValue& self); +void insert(::microstrain::Serializer& serializer, const GpioAnalogValue& self); +void extract(::microstrain::Serializer& serializer, GpioAnalogValue& self); ///@} diff --git a/src/mip/mip_descriptors.hpp b/src/mip/mip_descriptors.hpp index c17e9f72e..c2fd5ebb3 100644 --- a/src/mip/mip_descriptors.hpp +++ b/src/mip/mip_descriptors.hpp @@ -4,7 +4,7 @@ #include "mip_result.hpp" -#include "microstrain/common/buffer.hpp" +#include "microstrain/common/serialization.hpp" #include #include @@ -44,8 +44,8 @@ struct CompositeDescriptor /// template struct Bitfield {}; -template void insert (::microstrain::Buffer& serializer, const Bitfield& bitfield) { insert(serializer, static_cast(bitfield).value); } -template void extract(::microstrain::Buffer& serializer, Bitfield& bitfield) { extract(serializer, static_cast(bitfield).value); } +template void insert (::microstrain::Serializer& serializer, const Bitfield& bitfield) { insert(serializer, static_cast(bitfield).value); } +template void extract(::microstrain::Serializer& serializer, Bitfield& bitfield) { extract(serializer, static_cast(bitfield).value); } enum class FunctionSelector : uint8_t diff --git a/src/mip/mip_packet.h b/src/mip/mip_packet.h index 7ab5ce8e0..771ef47bd 100644 --- a/src/mip/mip_packet.h +++ b/src/mip/mip_packet.h @@ -112,7 +112,7 @@ bool mip_packet_is_data(const mip_packet* packet); ///@} //////////////////////////////////////////////////////////////////////////////// -///@defgroup Serialization Accessors - Functions for serializing a MIP packet. +///@defgroup Serialization Serializers - Functions for serializing a MIP packet. /// ///@{ diff --git a/src/mip/mip_packet.hpp b/src/mip/mip_packet.hpp index 1529e3f5e..3b3896dfc 100644 --- a/src/mip/mip_packet.hpp +++ b/src/mip/mip_packet.hpp @@ -5,7 +5,7 @@ #include "mip_packet.h" #include "mip_offsets.h" -#include +#include #include #include @@ -76,15 +76,15 @@ class PacketRef : public C::mip_packet int remainingSpace() const { return C::mip_packet_remaining_space(this); } ///<@copydoc mip::C::mip_packet_remaining_space bool addField(uint8_t fieldDescriptor, const uint8_t* payload, uint8_t payloadLength) { return C::mip_packet_add_field(this, fieldDescriptor, payload, payloadLength); } ///<@copydoc mip::C::mip_packet_add_field - microstrain::Buffer createField(uint8_t fieldDescriptor, uint8_t length) { uint8_t* ptr; if(C::mip_packet_alloc_field(this, fieldDescriptor, length, &ptr) < 0) length=0; return microstrain::Buffer{ptr, length}; } + microstrain::Serializer createField(uint8_t fieldDescriptor, uint8_t length) { uint8_t * ptr; if(C::mip_packet_alloc_field(this, fieldDescriptor, length, &ptr) < 0) length =0; return microstrain::Serializer{ptr, length}; } //std::tuple createField(uint8_t fieldDescriptor) { uint8_t* ptr; int max_size = C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr); return max_size >= 0 ? std::make_tuple(ptr, max_size) : std::make_tuple(nullptr, 0); } ///<@copydoc mip::C::mip_packet_alloc_field //int finishLastField(uint8_t* payloadPtr, uint8_t newPayloadLength) { return C::mip_packet_realloc_last_field(this, payloadPtr, newPayloadLength); } ///<@copydoc mip::C::mip_packet_realloc_last_field //int cancelLastField(uint8_t* payloadPtr) { return C::mip_packet_cancel_last_field(this, payloadPtr); } ///<@copydoc mip::C::mip_packet_cancel_last_field - class AllocatedField : public microstrain::Buffer + class AllocatedField : public microstrain::Serializer { public: - AllocatedField(mip::PacketRef& packet, uint8_t* buffer, size_t space) : Buffer(buffer, space), m_packet(packet) {} + AllocatedField(mip::PacketRef& packet, uint8_t* buffer, size_t space) : Serializer(buffer, space), m_packet(packet) {} //AllocatedField(const AllocatedField&) = delete; AllocatedField& operator=(const AllocatedField&) = delete; From 216dd65930bb65bfc866a80a9c821b1a50c719d6 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 31 May 2024 17:58:17 -0400 Subject: [PATCH 019/147] WIP ideas for automatic serialization using templates. --- src/mip/mip_serialization.hpp | 90 +++++++++++++++++++++++++++++++++++ 1 file changed, 90 insertions(+) create mode 100644 src/mip/mip_serialization.hpp diff --git a/src/mip/mip_serialization.hpp b/src/mip/mip_serialization.hpp new file mode 100644 index 000000000..a7f45c6eb --- /dev/null +++ b/src/mip/mip_serialization.hpp @@ -0,0 +1,90 @@ +#pragma once + +#include + +#include +#include + + +namespace mip +{ + + + + +template +size_t serialize_parameters_r(const std::tuple& args) +{ + constexpr size_t counter_offset = (StructType::COUNTER_PARAMS >> (2*I)) & 0b11; + constexpr bool is_array = counter_offset != 0; + + // Non-arrays get appended + if constexpr(!is_array) + return serialize_parameters_r(args); + + //const size_t counter_index = +} + + +template +size_t serialize_parameters(std::tuple& args) +{ + +} + + +template +struct Parameter +{ + T& value; +}; + +template +struct ArrayParameter : Parameter +{ + Counter& count; + static constexpr size_t max_count = MAX_SIZE_T; +}; +template +struct ArrayParameter : Parameter +{ + static constexpr size_t max_count = MAX_SIZE_T; +}; + +template +struct UnionConditionalParameter : Parameter +{ + const U& selector; + + bool matches() const { return selector == SELECTED_VALUE_T; } +}; + + + +//template +//void apply(FieldType& field, Action action) +//{ +// auto values = field.as_tuple(); +//} + +} // namespace mip + + +// These functions must be in the microstrain namespace in order to be seen as overloads. +namespace microstrain +{ + +// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. +template +typename std::enable_if::value, size_t>::type // todo: only MIP structs/fields +/*size_t*/ insert(microstrain::Serializer& serializer, const T& value) +{ + //return value.serialize(buffer); + auto values = value.as_tuple(); + + return std::apply([](auto... args){ + return mip::serialize_parameters(args...); + }, values); +} + +} // namespace microstrain From 669ca7cc381ffdbb2855e82645eaf0f324a7f0a4 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 6 Jun 2024 16:58:21 -0400 Subject: [PATCH 020/147] Undo experimental changes breaking the build. --- src/microstrain/common/serialization.hpp | 14 +++++++------- src/mip/definitions/commands_3dm.hpp | 2 +- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/microstrain/common/serialization.hpp b/src/microstrain/common/serialization.hpp index 4fb5645b2..78c3adb74 100644 --- a/src/microstrain/common/serialization.hpp +++ b/src/microstrain/common/serialization.hpp @@ -263,13 +263,13 @@ typename std::enable_if::value, size_t>::type return sizeof(BaseType); } -// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. -template -typename std::enable_if::value, size_t>::type -/*size_t*/ extract(Serializer& buffer, T& value) -{ - return value.deserialize(buffer); -} +// // Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. +// template +// typename std::enable_if::value, size_t>::type +// /*size_t*/ extract(Serializer& buffer, T& value) +// { +// return value.deserialize(buffer); +// } #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template diff --git a/src/mip/definitions/commands_3dm.hpp b/src/mip/definitions/commands_3dm.hpp index 8210f4395..c7685fc1c 100644 --- a/src/mip/definitions/commands_3dm.hpp +++ b/src/mip/definitions/commands_3dm.hpp @@ -518,7 +518,7 @@ struct FilterMessageFormat auto as_tuple() const { - return std::make_tuple(Counter(num_descriptors,descriptors),Array(descriptors,num_descriptors)); + return std::make_tuple(num_descriptors, descriptors); } auto as_tuple() From 1d7b8474aefac6998aa113ed70fb6a1c1b8063c5 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 6 Jun 2024 16:48:32 -0400 Subject: [PATCH 021/147] Rename DeviceInterface to Interface. --- examples/CV7/CV7_example.cpp | 2 +- examples/CV7_INS/CV7_INS_simple_example.cpp | 2 +- .../CV7_INS/CV7_INS_simple_ublox_example.cpp | 2 +- examples/GQ7/GQ7_example.cpp | 2 +- examples/GX5_45/GX5_45_example.cpp | 2 +- examples/device_info.cpp | 2 +- examples/example_utils.cpp | 4 +- examples/example_utils.hpp | 2 +- examples/threading.cpp | 6 +- examples/watch_imu.cpp | 2 +- src/mip/mip_interface.cpp | 2 +- src/mip/mip_interface.hpp | 72 +++++++++---------- 12 files changed, 50 insertions(+), 50 deletions(-) diff --git a/examples/CV7/CV7_example.cpp b/examples/CV7/CV7_example.cpp index 6a8d14019..61d6854f0 100644 --- a/examples/CV7/CV7_example.cpp +++ b/examples/CV7/CV7_example.cpp @@ -86,7 +86,7 @@ int main(int argc, const char* argv[]) return 1; } - std::unique_ptr& device = utils->device; + std::unique_ptr& device = utils->device; // //Ping the device (note: this is good to do to make sure the device is present) diff --git a/examples/CV7_INS/CV7_INS_simple_example.cpp b/examples/CV7_INS/CV7_INS_simple_example.cpp index 1ab4c70db..7d1139a33 100644 --- a/examples/CV7_INS/CV7_INS_simple_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_example.cpp @@ -77,7 +77,7 @@ int main(int argc, const char* argv[]) return 1; } - std::unique_ptr& device = utils->device; + std::unique_ptr& device = utils->device; // //Ping the device (note: this is good to do to make sure the device is present) diff --git a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp index bf46cc57e..d170c84b0 100644 --- a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp @@ -89,7 +89,7 @@ int main(int argc, const char* argv[]) InputArguments input_arguments = parse_input_arguments(argc, argv); std::unique_ptr utils = openFromArgs(input_arguments.mip_device_port_name, input_arguments.mip_device_baudrate, input_arguments.mip_binary_filepath); - std::unique_ptr& device = utils->device; + std::unique_ptr& device = utils->device; // // Open uBlox serial port diff --git a/examples/GQ7/GQ7_example.cpp b/examples/GQ7/GQ7_example.cpp index 84602e25b..88009db9e 100644 --- a/examples/GQ7/GQ7_example.cpp +++ b/examples/GQ7/GQ7_example.cpp @@ -92,7 +92,7 @@ int main(int argc, const char* argv[]) return 1; } - std::unique_ptr& device = utils->device; + std::unique_ptr& device = utils->device; printf("Connecting to and configuring sensor.\n"); // diff --git a/examples/GX5_45/GX5_45_example.cpp b/examples/GX5_45/GX5_45_example.cpp index 9443eb72b..fdb50ad9e 100644 --- a/examples/GX5_45/GX5_45_example.cpp +++ b/examples/GX5_45/GX5_45_example.cpp @@ -92,7 +92,7 @@ int main(int argc, const char* argv[]) return 1; } - std::unique_ptr& device = utils->device; + std::unique_ptr& device = utils->device; printf("Connecting to and configuring sensor.\n"); // diff --git a/examples/device_info.cpp b/examples/device_info.cpp index 740d5656c..4bd9bec5e 100644 --- a/examples/device_info.cpp +++ b/examples/device_info.cpp @@ -15,7 +15,7 @@ int main(int argc, const char* argv[]) try { std::unique_ptr utils = handleCommonArgs(argc, argv); - std::unique_ptr& device = utils->device; + std::unique_ptr& device = utils->device; mip::commands_base::BaseDeviceInfo device_info; diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index 064d045d1..2fbccd36c 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -78,7 +78,7 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, example_utils->connection = std::make_unique(port_or_hostname, port); #endif // MIP_USE_EXTRAS - example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), 1000, 2000); + example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), 1000, 2000); #else // MIP_USE_TCP throw std::runtime_error("This program was compiled without socket support. Recompile with -DMIP_USE_TCP=1"); #endif // MIP_USE_TCP @@ -100,7 +100,7 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, example_utils->connection = std::make_unique(port_or_hostname, baud); #endif // MIP_USE_EXTRAS - example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), mip::C::mip_timeout_from_baudrate(baud), 500); + example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), mip::C::mip_timeout_from_baudrate(baud), 500); #else // MIP_USE_SERIAL throw std::runtime_error("This program was compiled without serial support. Recompile with -DMIP_USE_SERIAL=1.\n"); #endif //MIP_USE_SERIAL diff --git a/examples/example_utils.hpp b/examples/example_utils.hpp index 2b5e2d866..c2d37a311 100644 --- a/examples/example_utils.hpp +++ b/examples/example_utils.hpp @@ -23,7 +23,7 @@ struct ExampleUtils { std::unique_ptr connection; - std::unique_ptr device; + std::unique_ptr device; std::unique_ptr recordedFile; uint8_t buffer[1024]; }; diff --git a/examples/threading.cpp b/examples/threading.cpp index bb294796a..db3497441 100644 --- a/examples/threading.cpp +++ b/examples/threading.cpp @@ -46,7 +46,7 @@ void packet_callback(void*, const mip::PacketRef& packet, mip::Timestamp timesta numSamples = numSamples + 1; } -void device_thread_loop(mip::DeviceInterface* device) +void device_thread_loop(mip::Interface* device) { while(!stop) { @@ -60,7 +60,7 @@ void device_thread_loop(mip::DeviceInterface* device) } } -bool update_device(mip::DeviceInterface& device, mip::Timeout wait_time) +bool update_device(mip::Interface& device, mip::Timeout wait_time) { if( wait_time > 0 ) return device.defaultUpdate(wait_time); @@ -82,7 +82,7 @@ int main(int argc, const char* argv[]) try { std::unique_ptr utils = handleCommonArgs(argc, argv); - std::unique_ptr& device = utils->device; + std::unique_ptr& device = utils->device; // Disable all streaming channels. mip::commands_base::setIdle(*device); diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index 76c116643..82876b744 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -59,7 +59,7 @@ void handleMag(void*, const mip::data_sensor::ScaledMag& data, mip::Timestamp ti } -int run(mip::DeviceInterface& device) +int run(mip::Interface& device) { mip::CmdResult result; diff --git a/src/mip/mip_interface.cpp b/src/mip/mip_interface.cpp index 3c9792334..d5ea8c9c5 100644 --- a/src/mip/mip_interface.cpp +++ b/src/mip/mip_interface.cpp @@ -33,7 +33,7 @@ namespace mip { /// ///@param device Device to configure. /// -void connect_interface(mip::DeviceInterface& device, microstrain::Connection& conn) +void connect_interface(mip::Interface& device, microstrain::Connection& conn) { using microstrain::Connection; diff --git a/src/mip/mip_interface.hpp b/src/mip/mip_interface.hpp index d410eaeac..b7df3e4c5 100644 --- a/src/mip/mip_interface.hpp +++ b/src/mip/mip_interface.hpp @@ -22,9 +22,9 @@ namespace mip ///@addtogroup mip_cpp ///@{ -class DeviceInterface; +class Interface; -void connect_interface(mip::DeviceInterface& dev, microstrain::Connection& conn); +void connect_interface(mip::Interface& dev, microstrain::Connection& conn); @@ -53,7 +53,7 @@ template bool startCommand(C::mip_interface& device, C::mip_pending_c //////////////////////////////////////////////////////////////////////////////// ///@brief Represents a connected MIP device. /// -class DeviceInterface : public C::mip_interface +class Interface : public C::mip_interface { public: // @@ -62,24 +62,24 @@ class DeviceInterface : public C::mip_interface ///@copydoc mip::C::mip_interface_init /// The interface callbacks must be assigned separately (e.g. with Connection::connect_interface()) - DeviceInterface(uint8_t* parseBuffer, size_t parseBufferSize, Timeout parseTimeout, Timeout baseReplyTimeout) + Interface(uint8_t* parseBuffer, size_t parseBufferSize, Timeout parseTimeout, Timeout baseReplyTimeout) { C::mip_interface_init(this, parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout, nullptr, nullptr, &C::mip_interface_default_update, nullptr); } ///@copydoc mip::C::mip_interface_init ///@param connection The connection object used to communicate with the device. This object must exist for the life of the DeviceInterface object - DeviceInterface(microstrain::Connection* connection, uint8_t* parseBuffer, size_t parseBufferSize, Timeout parseTimeout, Timeout baseReplyTimeout) : - DeviceInterface(parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout) + Interface(microstrain::Connection* connection, uint8_t* parseBuffer, size_t parseBufferSize, Timeout parseTimeout, Timeout baseReplyTimeout) : + Interface(parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout) { if(connection) connect_interface(*this, *connection); } - DeviceInterface(const DeviceInterface&) = delete; - DeviceInterface& operator=(const DeviceInterface&) = delete; + Interface(const Interface&) = delete; + Interface& operator=(const Interface&) = delete; - ~DeviceInterface() = default; + ~Interface() = default; // // Callback functions @@ -97,13 +97,13 @@ class DeviceInterface : public C::mip_interface // free/nonmember function callbacks - template + template void setSendFunction(); - template + template void setRecvFunction(); - template + template void setUpdateFunction(); // derived member function callbacks @@ -141,8 +141,8 @@ class DeviceInterface : public C::mip_interface Parser& parser() { return *static_cast(C::mip_interface_parser(this)); } CmdQueue& cmdQueue() { return *static_cast(C::mip_interface_cmd_queue(this)); } - const Parser& parser() const { return const_cast(this)->parser(); } - const CmdQueue& cmdQueue() const { return const_cast(this)->cmdQueue(); } + const Parser& parser() const { return const_cast(this)->parser(); } + const CmdQueue& cmdQueue() const { return const_cast(this)->cmdQueue(); } // // Communications @@ -226,11 +226,11 @@ class DeviceInterface : public C::mip_interface /// ///@tparam Send A compile-time pointer to the callback function. /// -template -void DeviceInterface::setSendFunction() +template +void Interface::setSendFunction() { setSendFunction([](C::mip_interface* device, const uint8_t* data, size_t length){ - return (*Send)(*static_cast(device), data, length); + return (*Send)(*static_cast(device), data, length); }); } @@ -239,11 +239,11 @@ void DeviceInterface::setSendFunction() /// ///@tparam Send A compile-time pointer to the callback function. /// -template -void DeviceInterface::setRecvFunction() +template +void Interface::setRecvFunction() { setRecvFunction([](C::mip_interface* device, uint8_t* buffer, size_t max_length, C::mip_timeout wait_time, size_t* length_out, C::mip_timestamp* timestamp_out){ - return (*Recv)(*static_cast(device), buffer, max_length, wait_time, length_out, timestamp_out); + return (*Recv)(*static_cast(device), buffer, max_length, wait_time, length_out, timestamp_out); }); } @@ -252,11 +252,11 @@ void DeviceInterface::setRecvFunction() /// ///@tparam Send A compile-time pointer to the callback function. /// -template -void DeviceInterface::setUpdateFunction() +template +void Interface::setUpdateFunction() { setUpdateFunction([](C::mip_interface* device, C::mip_timeout wait_time){ - return (*Update)(*static_cast(device), wait_time); + return (*Update)(*static_cast(device), wait_time); }); } @@ -283,7 +283,7 @@ void DeviceInterface::setUpdateFunction() /// template -void DeviceInterface::setSendFunction() +void Interface::setSendFunction() { static_assert(std::is_base_of::value, "Derived must be derived from C::mip_interface."); @@ -304,7 +304,7 @@ void DeviceInterface::setSendFunction() ///@see DeviceInterface::setSendFunction() /// template -void DeviceInterface::setRecvFunction() +void Interface::setRecvFunction() { static_assert(std::is_base_of::value, "Derived must be derived from C::mip_interface."); @@ -325,7 +325,7 @@ void DeviceInterface::setRecvFunction() ///@see DeviceInterface::setSendFunction() /// template -void DeviceInterface::setUpdateFunction() +void Interface::setUpdateFunction() { static_assert(std::is_base_of::value, "Derived must be derived from C::mip_interface."); @@ -381,7 +381,7 @@ template< bool (T::*Recv)(uint8_t*, size_t, Timeout, size_t*, Timestamp*), bool (T::*Update)(Timeout) > -void DeviceInterface::setCallbacks(T* object) +void Interface::setCallbacks(T* object) { auto send = [](C::mip_interface* device, const uint8_t* data, size_t size) { @@ -440,7 +440,7 @@ void DeviceInterface::setCallbacks(T* object) ///@endcode /// template -void DeviceInterface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, void* userData) +void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, void* userData) { auto callback = [](void* context, const C::mip_packet* packet, Timestamp timestamp) { @@ -482,7 +482,7 @@ void DeviceInterface::registerPacketCallback(C::mip_dispatch_handler& handler, u ///@endcode /// template -void DeviceInterface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, Object* object) +void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, Object* object) { auto callback = [](void* pointer, const mip::C::mip_packet* packet, Timestamp timestamp) { @@ -525,7 +525,7 @@ void DeviceInterface::registerPacketCallback(C::mip_dispatch_handler& handler, u ///@endcode /// template -void DeviceInterface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, void* userData) +void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, void* userData) { auto callback = [](void* context, const C::mip_field* field, Timestamp timestamp) { @@ -567,7 +567,7 @@ void DeviceInterface::registerFieldCallback(C::mip_dispatch_handler& handler, ui ///@endcode /// template -void DeviceInterface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, Object* object) +void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, Object* object) { auto callback = [](void* pointer, const C::mip_field* field, Timestamp timestamp) { @@ -614,7 +614,7 @@ void DeviceInterface::registerFieldCallback(C::mip_dispatch_handler& handler, ui ///@endcode /// template -void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, void* userData, uint8_t descriptorSet) +void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* userData, uint8_t descriptorSet) { assert(descriptorSet != 0x00); if(descriptorSet == 0x00) @@ -673,7 +673,7 @@ void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, voi ///@endcode /// template -void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, void* userData, uint8_t descriptorSet) +void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* userData, uint8_t descriptorSet) { assert(descriptorSet != 0x00); if(descriptorSet == 0x00) @@ -733,7 +733,7 @@ void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, voi ///@endcode /// template -void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, Object* object, uint8_t descriptorSet) +void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* object, uint8_t descriptorSet) { assert(descriptorSet != 0x00); if(descriptorSet == 0x00) @@ -794,7 +794,7 @@ void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, Obj ///@endcode /// template -void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, Object* object, uint8_t descriptorSet) +void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* object, uint8_t descriptorSet) { assert(descriptorSet != 0x00); if(descriptorSet == 0x00) @@ -820,7 +820,7 @@ void DeviceInterface::registerDataCallback(C::mip_dispatch_handler& handler, Obj template -void DeviceInterface::registerExtractor(C::mip_dispatch_handler& handler, DataField* field, uint8_t descriptorSet) +void Interface::registerExtractor(C::mip_dispatch_handler& handler, DataField* field, uint8_t descriptorSet) { auto callback = [](void* pointer, const C::mip_field* field, Timestamp timestamp) { From 30cfe6367c51f79064b6becc2bfb46812200ac4b Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 6 Jun 2024 17:04:01 -0400 Subject: [PATCH 022/147] Rename mip_packet to mip_packet_view. --- examples/watch_imu.c | 2 +- src/microstrain/common/serialization.h | 2 +- src/mip/mip_cmdqueue.c | 4 +- src/mip/mip_cmdqueue.h | 2 +- src/mip/mip_cmdqueue.hpp | 2 +- src/mip/mip_dispatch.c | 4 +- src/mip/mip_dispatch.h | 4 +- src/mip/mip_field.c | 8 ++-- src/mip/mip_field.h | 4 +- src/mip/mip_interface.c | 10 ++--- src/mip/mip_interface.h | 8 ++-- src/mip/mip_interface.hpp | 8 ++-- src/mip/mip_packet.c | 44 ++++++++++----------- src/mip/mip_packet.h | 54 +++++++++++++------------- src/mip/mip_packet.hpp | 8 ++-- src/mip/mip_parser.c | 4 +- src/mip/mip_parser.h | 4 +- src/mip/mip_parser.hpp | 2 +- test/mip/test_mip_fields.c | 2 +- test/mip/test_mip_packet_builder.c | 8 ++-- test/mip/test_mip_parser.c | 2 +- test/mip/test_mip_random.c | 6 +-- 22 files changed, 96 insertions(+), 96 deletions(-) diff --git a/examples/watch_imu.c b/examples/watch_imu.c index baac4a14e..0c20db681 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -50,7 +50,7 @@ void customLog(void* user, microstrain_log_level level, const char* fmt, va_list } } -void handlePacket(void* unused, const mip_packet* packet, mip_timestamp timestamp) +void handlePacket(void* unused, const mip_packet_view* packet, mip_timestamp timestamp) { (void)unused; diff --git a/src/microstrain/common/serialization.h b/src/microstrain/common/serialization.h index 7a8f8e4c7..576113875 100644 --- a/src/microstrain/common/serialization.h +++ b/src/microstrain/common/serialization.h @@ -153,7 +153,7 @@ void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* coun class Buffer : public C::microstrain_serializer { public: - // Buffer(C::mip_packet& packet, uint8_t newFieldDescriptor) { C::microstrain_serializer_init_new_field(this, &packet, newFieldDescriptor); } + // Buffer(C::mip_packet_view& packet, uint8_t newFieldDescriptor) { C::microstrain_serializer_init_new_field(this, &packet, newFieldDescriptor); } Buffer(uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_insertion(this, buffer, size); this->_offset = offset; } Buffer(const uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_extraction(this, const_cast(buffer), size); this->_offset = offset; } diff --git a/src/mip/mip_cmdqueue.c b/src/mip/mip_cmdqueue.c index 24874891d..e93a0cdab 100644 --- a/src/mip/mip_cmdqueue.c +++ b/src/mip/mip_cmdqueue.c @@ -265,7 +265,7 @@ void mip_cmd_queue_dequeue(mip_cmd_queue* queue, mip_pending_cmd* cmd) /// not updated). The caller should set pending->_status to this value /// after doing any additional processing requiring the pending struct. /// -static enum mip_cmd_result process_fields_for_pending_cmd(mip_pending_cmd* pending, const mip_packet* packet, mip_timeout base_timeout, mip_timestamp timestamp) +static enum mip_cmd_result process_fields_for_pending_cmd(mip_pending_cmd* pending, const mip_packet_view* packet, mip_timeout base_timeout, mip_timestamp timestamp) { assert( pending->_status != MIP_STATUS_NONE ); // pending->_status must be set to MIP_STATUS_PENDING in mip_cmd_queue_enqueue to get here. assert( !mip_cmd_result_is_finished(pending->_status) ); // Command shouldn't be finished yet - make sure the queue is processed properly. @@ -372,7 +372,7 @@ static enum mip_cmd_result process_fields_for_pending_cmd(mip_pending_cmd* pendi ///@param packet The received MIP packet. Assumed to be valid. ///@param timestamp The time the packet was received /// -void mip_cmd_queue_process_packet(mip_cmd_queue* queue, const mip_packet* packet, mip_timestamp timestamp) +void mip_cmd_queue_process_packet(mip_cmd_queue* queue, const mip_packet_view* packet, mip_timestamp timestamp) { // Check if the packet is a command descriptor set. const uint8_t descriptor_set = mip_packet_descriptor_set(packet); diff --git a/src/mip/mip_cmdqueue.h b/src/mip/mip_cmdqueue.h index 868e735ec..aec5e14f0 100644 --- a/src/mip/mip_cmdqueue.h +++ b/src/mip/mip_cmdqueue.h @@ -116,7 +116,7 @@ void mip_cmd_queue_update(mip_cmd_queue* queue, mip_timestamp timestamp); void mip_cmd_queue_set_base_reply_timeout(mip_cmd_queue* queue, mip_timeout timeout); mip_timeout mip_cmd_queue_base_reply_timeout(const mip_cmd_queue* queue); -void mip_cmd_queue_process_packet(mip_cmd_queue* queue, const mip_packet* packet, mip_timestamp timestamp); +void mip_cmd_queue_process_packet(mip_cmd_queue* queue, const mip_packet_view* packet, mip_timestamp timestamp); #ifdef MIP_ENABLE_DIAGNOSTICS diff --git a/src/mip/mip_cmdqueue.hpp b/src/mip/mip_cmdqueue.hpp index a2eac8d64..67c16c06d 100644 --- a/src/mip/mip_cmdqueue.hpp +++ b/src/mip/mip_cmdqueue.hpp @@ -34,7 +34,7 @@ struct CmdQueue : public C::mip_cmd_queue void setBaseReplyTimeout(Timeout timeout) { C::mip_cmd_queue_set_base_reply_timeout(this, timeout); } Timeout baseReplyTimeout() const { return C::mip_cmd_queue_base_reply_timeout(this); } - void processPacket(const C::mip_packet& packet, Timestamp timestamp) { C::mip_cmd_queue_process_packet(this, &packet, timestamp); } + void processPacket(const C::mip_packet_view& packet, Timestamp timestamp) { C::mip_cmd_queue_process_packet(this, &packet, timestamp); } }; static_assert(sizeof(CmdQueue) == sizeof(C::mip_cmd_queue), "CmdQueue must not have additional data members."); diff --git a/src/mip/mip_dispatch.c b/src/mip/mip_dispatch.c index 251e1770e..18b03c995 100644 --- a/src/mip/mip_dispatch.c +++ b/src/mip/mip_dispatch.c @@ -267,7 +267,7 @@ static bool mip_dispatch_is_descriptor_set_match(uint8_t desc_set, uint8_t handl ///@param timestamp Packet parse time. ///@param post If true, this is called after field iteration. Otherwise before. /// -static void mip_dispatcher_call_packet_callbacks(mip_dispatcher* self, const mip_packet* packet, mip_timestamp timestamp, bool post) +static void mip_dispatcher_call_packet_callbacks(mip_dispatcher* self, const mip_packet_view* packet, mip_timestamp timestamp, bool post) { const uint8_t descriptor_set = mip_packet_descriptor_set(packet); @@ -348,7 +348,7 @@ static void mip_dispatcher_call_field_callbacks(mip_dispatcher* self, const mip_ ///@param timestamp /// The approximate parse time of the packet. /// -void mip_dispatcher_dispatch_packet(mip_dispatcher* self, const mip_packet* packet, mip_timestamp timestamp) +void mip_dispatcher_dispatch_packet(mip_dispatcher* self, const mip_packet_view* packet, mip_timestamp timestamp) { mip_dispatcher_call_packet_callbacks(self, packet, timestamp, false); diff --git a/src/mip/mip_dispatch.h b/src/mip/mip_dispatch.h index 9e60ae6cb..19f526473 100644 --- a/src/mip/mip_dispatch.h +++ b/src/mip/mip_dispatch.h @@ -36,7 +36,7 @@ extern "C" { ///@param packet The MIP packet triggering this callback. ///@param timestamp The approximate parse time of the packet. /// -typedef void (*mip_dispatch_packet_callback)(void *context, const mip_packet *packet, mip_timestamp timestamp); +typedef void (*mip_dispatch_packet_callback)(void *context, const mip_packet_view *packet, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// ///@brief Signature for field-level callbacks. @@ -130,7 +130,7 @@ void mip_dispatcher_add_handler(mip_dispatcher *self, mip_dispatch_handler *hand void mip_dispatcher_remove_handler(mip_dispatcher *self, mip_dispatch_handler *handler); void mip_dispatcher_remove_all_handlers(mip_dispatcher *self); -void mip_dispatcher_dispatch_packet(mip_dispatcher *self, const mip_packet *packet, mip_timestamp timestamp); +void mip_dispatcher_dispatch_packet(mip_dispatcher *self, const mip_packet_view *packet, mip_timestamp timestamp); ///@} ///@} diff --git a/src/mip/mip_field.c b/src/mip/mip_field.c index cbc6b2d25..c83cd9fe6 100644 --- a/src/mip/mip_field.c +++ b/src/mip/mip_field.c @@ -163,7 +163,7 @@ mip_field mip_field_from_header_ptr(const uint8_t* header, uint8_t total_length, /// ///@returns A mip_field struct with the first field from the packet. /// -mip_field mip_field_first_from_packet(const mip_packet* packet) +mip_field mip_field_first_from_packet(const mip_packet_view* packet) { return mip_field_from_header_ptr( mip_packet_payload(packet), mip_packet_payload_length(packet), mip_packet_descriptor_set(packet) ); } @@ -226,7 +226,7 @@ bool mip_field_next(mip_field* field) /// } ///@endcode /// -bool mip_field_next_in_packet(mip_field* field, const mip_packet* packet) +bool mip_field_next_in_packet(mip_field* field, const mip_packet_view* packet) { if( field->_descriptor_set != MIP_INVALID_DESCRIPTOR_SET ) *field = mip_field_next_after(field); @@ -252,7 +252,7 @@ bool mip_field_next_in_packet(mip_field* field, const mip_packet* packet) ///@param field_descriptor /// Field descriptor of the new field. /// -void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor) +void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor) { assert(packet); @@ -275,7 +275,7 @@ void microstrain_serializer_init_new_field(microstrain_serializer* serializer, m ///@param serializer Must be created from microstrain_serializer_init_new_field. ///@param packet Must be the original packet. /// -void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet* packet) +void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet_view* packet) { assert(packet); diff --git a/src/mip/mip_field.h b/src/mip/mip_field.h index d7cf2d618..1b590c3d9 100644 --- a/src/mip/mip_field.h +++ b/src/mip/mip_field.h @@ -104,11 +104,11 @@ void mip_field_init_empty(mip_field* field); mip_field mip_field_from_header_ptr(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set); -mip_field mip_field_first_from_packet(const mip_packet* packet); +mip_field mip_field_first_from_packet(const mip_packet_view* packet); mip_field mip_field_next_after(const mip_field* field); bool mip_field_next(mip_field* field); -bool mip_field_next_in_packet(mip_field* field, const mip_packet* packet); +bool mip_field_next_in_packet(mip_field* field, const mip_packet_view* packet); // bool mip_field_is_at_end(const struct mip_field* field); diff --git a/src/mip/mip_interface.c b/src/mip/mip_interface.c index 5b4876308..05d0a39ce 100644 --- a/src/mip/mip_interface.c +++ b/src/mip/mip_interface.c @@ -483,7 +483,7 @@ void mip_interface_process_unparsed_packets(mip_interface* device) ///@param timestamp /// timestamp_type of the received MIP packet. /// -void mip_interface_receive_packet(mip_interface* device, const mip_packet* packet, mip_timestamp timestamp) +void mip_interface_receive_packet(mip_interface* device, const mip_packet_view* packet, mip_timestamp timestamp) { mip_cmd_queue_process_packet(&device->_queue, packet, timestamp); mip_dispatcher_dispatch_packet(&device->_dispatcher, packet, timestamp); @@ -498,7 +498,7 @@ void mip_interface_receive_packet(mip_interface* device, const mip_packet* packe /// ///@returns True /// -bool mip_interface_parse_callback(void* device, const mip_packet* packet, mip_timestamp timestamp) +bool mip_interface_parse_callback(void* device, const mip_packet_view* packet, mip_timestamp timestamp) { mip_interface_receive_packet(device, packet, timestamp); @@ -602,7 +602,7 @@ enum mip_cmd_result mip_interface_run_command_with_response(mip_interface* devic uint8_t buffer[MIP_PACKET_LENGTH_MAX]; - mip_packet packet; + mip_packet_view packet; mip_packet_create(&packet, buffer, sizeof(buffer), descriptor_set); mip_packet_add_field(&packet, cmd_descriptor, cmd_data, cmd_length); mip_packet_finalize(&packet); @@ -629,7 +629,7 @@ enum mip_cmd_result mip_interface_run_command_with_response(mip_interface* devic ///@param cmd /// The command status tracker. No lifetime requirement. /// -enum mip_cmd_result mip_interface_run_command_packet(mip_interface* device, const mip_packet* packet, mip_pending_cmd* cmd) +enum mip_cmd_result mip_interface_run_command_packet(mip_interface* device, const mip_packet_view* packet, mip_pending_cmd* cmd) { if( !mip_interface_start_command_packet(device, packet, cmd) ) return MIP_STATUS_ERROR; @@ -650,7 +650,7 @@ enum mip_cmd_result mip_interface_run_command_packet(mip_interface* device, cons ///@returns False on error sending the packet. No cleanup is necessary and cmd /// can be destroyed immediately afterward in this case. /// -bool mip_interface_start_command_packet(mip_interface* device, const mip_packet* packet, mip_pending_cmd* cmd) +bool mip_interface_start_command_packet(mip_interface* device, const mip_packet_view* packet, mip_pending_cmd* cmd) { mip_cmd_queue_enqueue(mip_interface_cmd_queue(device), cmd); diff --git a/src/mip/mip_interface.h b/src/mip/mip_interface.h index c3d2868ed..2a2eec7fb 100644 --- a/src/mip/mip_interface.h +++ b/src/mip/mip_interface.h @@ -72,8 +72,8 @@ bool mip_interface_update(mip_interface* device, mip_timeout wait_time); bool mip_interface_default_update(mip_interface* device, mip_timeout wait_time); size_t mip_interface_receive_bytes(mip_interface* device, const uint8_t* data, size_t length, mip_timestamp timestamp); void mip_interface_process_unparsed_packets(mip_interface* device); -bool mip_interface_parse_callback(void* device, const mip_packet* packet, mip_timestamp timestamp); -void mip_interface_receive_packet(mip_interface* device, const mip_packet* packet, mip_timestamp timestamp); +bool mip_interface_parse_callback(void* device, const mip_packet_view* packet, mip_timestamp timestamp); +void mip_interface_receive_packet(mip_interface* device, const mip_packet_view* packet, mip_timestamp timestamp); // // Commands @@ -82,9 +82,9 @@ void mip_interface_receive_packet(mip_interface* device, const mip_packet* packe enum mip_cmd_result mip_interface_wait_for_reply(mip_interface* device, mip_pending_cmd* cmd); enum mip_cmd_result mip_interface_run_command(mip_interface* device, uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length); enum mip_cmd_result mip_interface_run_command_with_response(mip_interface* device, uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length, uint8_t response_descriptor, uint8_t* response_data, uint8_t* response_length_inout); -enum mip_cmd_result mip_interface_run_command_packet(mip_interface* device, const mip_packet* packet, mip_pending_cmd* cmd); +enum mip_cmd_result mip_interface_run_command_packet(mip_interface* device, const mip_packet_view* packet, mip_pending_cmd* cmd); -bool mip_interface_start_command_packet(mip_interface* device, const mip_packet* packet, mip_pending_cmd* cmd); +bool mip_interface_start_command_packet(mip_interface* device, const mip_packet_view* packet, mip_pending_cmd* cmd); // // Data Callbacks diff --git a/src/mip/mip_interface.hpp b/src/mip/mip_interface.hpp index b7df3e4c5..861d240c7 100644 --- a/src/mip/mip_interface.hpp +++ b/src/mip/mip_interface.hpp @@ -149,13 +149,13 @@ class Interface : public C::mip_interface // bool sendToDevice(const uint8_t* data, size_t length) { return C::mip_interface_send_to_device(this, data, length); } - bool sendToDevice(const C::mip_packet& packet) { return sendToDevice(C::mip_packet_pointer(&packet), C::mip_packet_total_length(&packet)); } + bool sendToDevice(const C::mip_packet_view& packet) { return sendToDevice(C::mip_packet_pointer(&packet), C::mip_packet_total_length(&packet)); } bool recvFromDevice(uint8_t* buffer, size_t max_length, Timeout wait_time, size_t* length_out, Timestamp* timestamp) { return C::mip_interface_recv_from_device(this, buffer, max_length, wait_time, length_out, timestamp); } bool update(Timeout wait_time=0) { return C::mip_interface_update(this, wait_time); } bool defaultUpdate(Timeout wait_time=0) { return C::mip_interface_default_update(this, wait_time); } size_t receiveBytes(const uint8_t* data, size_t length, Timestamp timestamp) { return C::mip_interface_receive_bytes(this, data, length, timestamp); } - void receivePacket(const C::mip_packet& packet, Timestamp timestamp) { C::mip_interface_receive_packet(this, &packet, timestamp); } + void receivePacket(const C::mip_packet_view& packet, Timestamp timestamp) { C::mip_interface_receive_packet(this, &packet, timestamp); } void processUnparsedPackets() { C::mip_interface_process_unparsed_packets(this); } CmdResult waitForReply(C::mip_pending_cmd& cmd) { return C::mip_interface_wait_for_reply(this, &cmd); } @@ -442,7 +442,7 @@ void Interface::setCallbacks(T* object) template void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, void* userData) { - auto callback = [](void* context, const C::mip_packet* packet, Timestamp timestamp) + auto callback = [](void* context, const C::mip_packet_view* packet, Timestamp timestamp) { Callback(context, PacketRef(*packet), timestamp); }; @@ -484,7 +484,7 @@ void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t template void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, Object* object) { - auto callback = [](void* pointer, const mip::C::mip_packet* packet, Timestamp timestamp) + auto callback = [](void* pointer, const mip::C::mip_packet_view* packet, Timestamp timestamp) { Object* obj = static_cast(pointer); (obj->*Callback)(PacketRef(*packet), timestamp); diff --git a/src/mip/mip_packet.c b/src/mip/mip_packet.c index 631065a71..2d38cc353 100644 --- a/src/mip/mip_packet.c +++ b/src/mip/mip_packet.c @@ -35,7 +35,7 @@ /// MIP_PACKET_LENGTH_MIN bytes, calling the accessor functions is undefined /// behavior. /// -void mip_packet_from_buffer(mip_packet* packet, uint8_t* buffer, size_t length) +void mip_packet_from_buffer(mip_packet_view* packet, uint8_t* buffer, size_t length) { assert(buffer != NULL); @@ -61,7 +61,7 @@ void mip_packet_from_buffer(mip_packet* packet, uint8_t* buffer, size_t length) ///@param descriptor_set /// The MIP descriptor set for the packet. /// -void mip_packet_create(mip_packet* packet, uint8_t* buffer, size_t buffer_size, uint8_t descriptor_set) +void mip_packet_create(mip_packet_view* packet, uint8_t* buffer, size_t buffer_size, uint8_t descriptor_set) { mip_packet_from_buffer(packet, buffer, buffer_size); @@ -86,7 +86,7 @@ void mip_packet_create(mip_packet* packet, uint8_t* buffer, size_t buffer_size, //////////////////////////////////////////////////////////////////////////////// ///@brief Returns the MIP descriptor set for this packet. /// -uint8_t mip_packet_descriptor_set(const mip_packet* packet) +uint8_t mip_packet_descriptor_set(const mip_packet_view* packet) { return packet->_buffer[MIP_INDEX_DESCSET]; } @@ -94,7 +94,7 @@ uint8_t mip_packet_descriptor_set(const mip_packet* packet) //////////////////////////////////////////////////////////////////////////////// ///@brief Returns the length of the payload (MIP fields). /// -uint8_t mip_packet_payload_length(const mip_packet* packet) +uint8_t mip_packet_payload_length(const mip_packet_view* packet) { return packet->_buffer[MIP_INDEX_LENGTH]; } @@ -104,7 +104,7 @@ uint8_t mip_packet_payload_length(const mip_packet* packet) /// ///@returns The length of the packet. Always at least MIP_PACKET_LENGTH_MIN. /// -uint_least16_t mip_packet_total_length(const mip_packet* packet) +uint_least16_t mip_packet_total_length(const mip_packet_view* packet) { return mip_packet_payload_length(packet) + MIP_PACKET_LENGTH_MIN; } @@ -112,7 +112,7 @@ uint_least16_t mip_packet_total_length(const mip_packet* packet) //////////////////////////////////////////////////////////////////////////////// ///@brief Returns a writable pointer to the data buffer. /// -uint8_t* mip_packet_buffer(mip_packet* packet) +uint8_t* mip_packet_buffer(mip_packet_view* packet) { return packet->_buffer; } @@ -120,7 +120,7 @@ uint8_t* mip_packet_buffer(mip_packet* packet) //////////////////////////////////////////////////////////////////////////////// ///@brief Returns a pointer to the data buffer containing the packet. /// -const uint8_t* mip_packet_pointer(const mip_packet* packet) +const uint8_t* mip_packet_pointer(const mip_packet_view* packet) { return packet->_buffer; } @@ -128,7 +128,7 @@ const uint8_t* mip_packet_pointer(const mip_packet* packet) //////////////////////////////////////////////////////////////////////////////// ///@brief Returns a pointer to the packet's payload (the first field). /// -const uint8_t* mip_packet_payload(const mip_packet* packet) +const uint8_t* mip_packet_payload(const mip_packet_view* packet) { return packet->_buffer + MIP_INDEX_PAYLOAD; } @@ -139,7 +139,7 @@ const uint8_t* mip_packet_payload(const mip_packet* packet) /// This function does not compute the checksum. To do so, use /// mip_packet_compute_checksum(). /// -uint16_t mip_packet_checksum_value(const mip_packet* packet) +uint16_t mip_packet_checksum_value(const mip_packet_view* packet) { const uint_least16_t index = mip_packet_total_length(packet) - MIP_CHECKSUM_LENGTH; @@ -151,7 +151,7 @@ uint16_t mip_packet_checksum_value(const mip_packet* packet) /// ///@returns The computed checksum value. /// -uint16_t mip_packet_compute_checksum(const mip_packet* packet) +uint16_t mip_packet_compute_checksum(const mip_packet_view* packet) { uint8_t a = 0; uint8_t b = 0; @@ -178,7 +178,7 @@ uint16_t mip_packet_compute_checksum(const mip_packet* packet) /// used to access it (to do so is undefined behavior). This should never occur /// in normal circumstances. /// -bool mip_packet_is_sane(const mip_packet* packet) +bool mip_packet_is_sane(const mip_packet_view* packet) { return packet->_buffer && (packet->_buffer_length >= MIP_PACKET_LENGTH_MIN) && (packet->_buffer_length >= mip_packet_payload_length(packet)+MIP_PACKET_LENGTH_MIN); } @@ -191,7 +191,7 @@ bool mip_packet_is_sane(const mip_packet* packet) /// * The descriptor set is not 0x00, and /// * The checksum is valid. /// -bool mip_packet_is_valid(const mip_packet* packet) +bool mip_packet_is_valid(const mip_packet_view* packet) { if( !mip_packet_is_sane(packet) || (mip_packet_descriptor_set(packet) == 0x00) ) return false; @@ -209,7 +209,7 @@ bool mip_packet_is_valid(const mip_packet* packet) /// ///@returns true if the packet has a payload length of 0. /// -bool mip_packet_is_empty(const mip_packet* packet) +bool mip_packet_is_empty(const mip_packet_view* packet) { if( !mip_packet_is_sane(packet) ) return true; @@ -223,7 +223,7 @@ bool mip_packet_is_empty(const mip_packet* packet) /// ///@note This is the BUFFER SIZE and not the packet length. /// -uint_least16_t mip_packet_buffer_size(const mip_packet* packet) +uint_least16_t mip_packet_buffer_size(const mip_packet_view* packet) { return packet->_buffer_length; } @@ -237,7 +237,7 @@ uint_least16_t mip_packet_buffer_size(const mip_packet* packet) /// buffer capacity. Such packets are not 'sane' (mip_packet_is_sane) /// and can only be produced by manipulating the buffered data directly. /// -int mip_packet_remaining_space(const mip_packet* packet) +int mip_packet_remaining_space(const mip_packet_view* packet) { return mip_packet_buffer_size(packet) - mip_packet_total_length(packet); } @@ -250,7 +250,7 @@ int mip_packet_remaining_space(const mip_packet* packet) ///@returns true if the packet contains data. ///@returns false if it contains commands or replies. /// -bool mip_packet_is_data(const mip_packet* packet) +bool mip_packet_is_data(const mip_packet_view* packet) { return mip_is_data_descriptor_set(mip_packet_descriptor_set(packet)); } @@ -288,7 +288,7 @@ bool mip_packet_is_data(const mip_packet* packet) /// ///@returns true if the field was added, or false if there was not enough space. /// -bool mip_packet_add_field(mip_packet* packet, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) +bool mip_packet_add_field(mip_packet_view* packet, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) { uint8_t* payload_buffer; int remaining = mip_packet_alloc_field(packet, field_descriptor, payload_length, &payload_buffer); @@ -330,7 +330,7 @@ bool mip_packet_add_field(mip_packet* packet, uint8_t field_descriptor, const ui /// is negative, the field could not be allocated and the payload must /// not be written. /// -int mip_packet_alloc_field(mip_packet* packet, uint8_t field_descriptor, uint8_t payload_length, uint8_t** const payload_ptr_out) +int mip_packet_alloc_field(mip_packet_view* packet, uint8_t field_descriptor, uint8_t payload_length, uint8_t** const payload_ptr_out) { assert(payload_ptr_out != NULL); assert( payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX ); @@ -377,7 +377,7 @@ int mip_packet_alloc_field(mip_packet* packet, uint8_t field_descriptor, uint8_t ///@returns The space remaining in the packet after changing the field size. /// This will be negative if the new length did not fit. /// -int mip_packet_realloc_last_field(mip_packet* packet, uint8_t* payload_ptr, uint8_t new_payload_length) +int mip_packet_realloc_last_field(mip_packet_view* packet, uint8_t* payload_ptr, uint8_t new_payload_length) { assert(payload_ptr != NULL); assert( new_payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX ); @@ -413,7 +413,7 @@ int mip_packet_realloc_last_field(mip_packet* packet, uint8_t* payload_ptr, uint /// ///@returns The remaining space in the packet after removing the field. /// -int mip_packet_cancel_last_field(mip_packet* packet, uint8_t* payload_ptr) +int mip_packet_cancel_last_field(mip_packet_view* packet, uint8_t* payload_ptr) { assert(payload_ptr != NULL); @@ -442,7 +442,7 @@ int mip_packet_cancel_last_field(mip_packet* packet, uint8_t* payload_ptr) /// Total Length ///~~~ /// -void mip_packet_finalize(mip_packet* packet) +void mip_packet_finalize(mip_packet_view* packet) { uint16_t checksum = mip_packet_compute_checksum(packet); uint_least16_t length = mip_packet_total_length(packet) - MIP_CHECKSUM_LENGTH; @@ -460,7 +460,7 @@ void mip_packet_finalize(mip_packet* packet) ///@param packet ///@param descriptor_set New descriptor set. /// -void mip_packet_reset(mip_packet* packet, uint8_t descriptor_set) +void mip_packet_reset(mip_packet_view* packet, uint8_t descriptor_set) { mip_packet_create(packet, mip_packet_buffer(packet), mip_packet_buffer_size(packet), descriptor_set); } diff --git a/src/mip/mip_packet.h b/src/mip/mip_packet.h index 771ef47bd..5d4e2a3cd 100644 --- a/src/mip/mip_packet.h +++ b/src/mip/mip_packet.h @@ -27,7 +27,7 @@ struct microstrain_serializer; /// ///@brief Functions for handling MIP packets. /// -/// A MIP Packet is represented by the mip_packet struct. +/// A MIP Packet is represented by the mip_packet_view struct. /// ///~~~ /// +-------+-------+------+------+------------+-----/ /----+------------+---- @@ -47,11 +47,11 @@ struct microstrain_serializer; /// considered an internal implementation detail. Avoid accessing them directly /// as they are subject to change in future versions of this software. /// -typedef struct mip_packet +typedef struct mip_packet_view { uint8_t* _buffer; ///<@private Pointer to the packet data. uint_least16_t _buffer_length; ///<@private Length of the buffer (NOT the packet length!). -} mip_packet; +} mip_packet_view; //////////////////////////////////////////////////////////////////////////////// @@ -64,16 +64,16 @@ typedef struct mip_packet /// ///@{ -void mip_packet_create(mip_packet* packet, uint8_t* buffer, size_t buffer_size, uint8_t descriptor_set); +void mip_packet_create(mip_packet_view* packet, uint8_t* buffer, size_t buffer_size, uint8_t descriptor_set); -bool mip_packet_add_field(mip_packet* packet, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length); -int mip_packet_alloc_field(mip_packet* packet, uint8_t field_descriptor, uint8_t payload_length, uint8_t** payload_ptr_out); -int mip_packet_realloc_last_field(mip_packet* packet, uint8_t* payload_ptr, uint8_t new_payload_length); -int mip_packet_cancel_last_field(mip_packet* packet, uint8_t* payload_ptr); +bool mip_packet_add_field(mip_packet_view* packet, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length); +int mip_packet_alloc_field(mip_packet_view* packet, uint8_t field_descriptor, uint8_t payload_length, uint8_t** payload_ptr_out); +int mip_packet_realloc_last_field(mip_packet_view* packet, uint8_t* payload_ptr, uint8_t new_payload_length); +int mip_packet_cancel_last_field(mip_packet_view* packet, uint8_t* payload_ptr); -void mip_packet_finalize(mip_packet* packet); +void mip_packet_finalize(mip_packet_view* packet); -void mip_packet_reset(mip_packet* packet, uint8_t descriptor_set); +void mip_packet_reset(mip_packet_view* packet, uint8_t descriptor_set); ///@} //////////////////////////////////////////////////////////////////////////////// @@ -89,26 +89,26 @@ void mip_packet_reset(mip_packet* packet, uint8_t descriptor_set); /// ///@{ -void mip_packet_from_buffer(mip_packet* packet, uint8_t* buffer, size_t length); +void mip_packet_from_buffer(mip_packet_view* packet, uint8_t* buffer, size_t length); -uint8_t mip_packet_descriptor_set(const mip_packet* packet); -uint_least16_t mip_packet_total_length(const mip_packet* packet); -uint8_t mip_packet_payload_length(const mip_packet* packet); -uint8_t* mip_packet_buffer(mip_packet* packet); -const uint8_t* mip_packet_pointer(const mip_packet* packet); -const uint8_t* mip_packet_payload(const mip_packet* packet); -uint16_t mip_packet_checksum_value(const mip_packet* packet); -uint16_t mip_packet_compute_checksum(const mip_packet* packet); +uint8_t mip_packet_descriptor_set(const mip_packet_view* packet); +uint_least16_t mip_packet_total_length(const mip_packet_view* packet); +uint8_t mip_packet_payload_length(const mip_packet_view* packet); +uint8_t* mip_packet_buffer(mip_packet_view* packet); +const uint8_t* mip_packet_pointer(const mip_packet_view* packet); +const uint8_t* mip_packet_payload(const mip_packet_view* packet); +uint16_t mip_packet_checksum_value(const mip_packet_view* packet); +uint16_t mip_packet_compute_checksum(const mip_packet_view* packet); -bool mip_packet_is_sane(const mip_packet* packet); -bool mip_packet_is_valid(const mip_packet* packet); -bool mip_packet_is_empty(const mip_packet* packet); +bool mip_packet_is_sane(const mip_packet_view* packet); +bool mip_packet_is_valid(const mip_packet_view* packet); +bool mip_packet_is_empty(const mip_packet_view* packet); -uint_least16_t mip_packet_buffer_size(const mip_packet* packet); -int mip_packet_remaining_space(const mip_packet* packet); +uint_least16_t mip_packet_buffer_size(const mip_packet_view* packet); +int mip_packet_remaining_space(const mip_packet_view* packet); -bool mip_packet_is_data(const mip_packet* packet); +bool mip_packet_is_data(const mip_packet_view* packet); ///@} //////////////////////////////////////////////////////////////////////////////// @@ -116,8 +116,8 @@ bool mip_packet_is_data(const mip_packet* packet); /// ///@{ -//void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet* packet, uint8_t field_descriptor); -//void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet* packet); +//void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor); +//void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet_view* packet); ///@} ///@} diff --git a/src/mip/mip_packet.hpp b/src/mip/mip_packet.hpp index 3b3896dfc..86049629f 100644 --- a/src/mip/mip_packet.hpp +++ b/src/mip/mip_packet.hpp @@ -21,7 +21,7 @@ namespace mip //////////////////////////////////////////////////////////////////////////////// ///@brief C++ class representing a MIP PacketRef. /// -/// This is a thin wrapper around the mip_packet C structure. Like the C +/// This is a thin wrapper around the mip_packet_view C structure. Like the C /// version, it does not contain or own the data buffer. Any of the C functions /// can be used with the C++ packet class because it inherits from the C struct. /// @@ -32,7 +32,7 @@ namespace mip /// for(Field field : packet) { ... } ///@endcode /// -class PacketRef : public C::mip_packet +class PacketRef : public C::mip_packet_view { public: static constexpr size_t PAYLOAD_LENGTH_MAX = C::MIP_PACKET_PAYLOAD_LENGTH_MAX; @@ -47,9 +47,9 @@ class PacketRef : public C::mip_packet ///@copydoc mip_packet_from_buffer PacketRef(uint8_t* buffer, size_t length) { C::mip_packet_from_buffer(this, buffer, length); } /// Constructs a C++ %PacketRef class from the base C object. - PacketRef(const C::mip_packet* other) { std::memcpy(static_cast(this), other, sizeof(*this)); } + PacketRef(const C::mip_packet_view* other) { std::memcpy(static_cast(this), other, sizeof(*this)); } /// Constructs a C++ %PacketRef class from the base C object. - PacketRef(const C::mip_packet& other) { std::memcpy(static_cast(this), &other, sizeof(*this)); } + PacketRef(const C::mip_packet_view& other) { std::memcpy(static_cast(this), &other, sizeof(*this)); } // diff --git a/src/mip/mip_parser.c b/src/mip/mip_parser.c index d6192347e..a04404718 100644 --- a/src/mip/mip_parser.c +++ b/src/mip/mip_parser.c @@ -136,7 +136,7 @@ size_t mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer, size_t MIP_DIAG_INC(parser->_diag_bytes_read, count); - mip_packet packet; + mip_packet_view packet; while( mip_parser_parse_one_packet_from_ring(parser, &packet, timestamp) ) { num_packets++; @@ -179,7 +179,7 @@ size_t mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer, size_t ///@returns true if a packet was found, false if more data is required. If false, /// the packet is not initialized. /// -bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet* packet_out, mip_timestamp timestamp) +bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet_view* packet_out, mip_timestamp timestamp) { // Parse packets while there is sufficient data in the ring buffer. while( byte_ring_count(&parser->_ring) >= parser->_expected_length ) diff --git a/src/mip/mip_parser.h b/src/mip/mip_parser.h index 059b38043..b25c21f74 100644 --- a/src/mip/mip_parser.h +++ b/src/mip/mip_parser.h @@ -42,7 +42,7 @@ extern "C" { ///@param user A user-specified pointer which will be given the callback_object parameter which was previously passed to mip_parser_init. ///@param packet A pointer to the MIP packet. Do not store this pointer as it will be invalidated after the callback returns. ///@param timestamp The approximate time the packet was parsed. -typedef bool (*mip_packet_callback)(void* user, const mip_packet* packet, mip_timestamp timestamp); +typedef bool (*mip_packet_callback)(void* user, const mip_packet_view* packet, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// @@ -80,7 +80,7 @@ typedef struct mip_parser void mip_parser_init(mip_parser* parser, uint8_t* buffer, size_t buffer_size, mip_packet_callback callback, void* callback_object, mip_timestamp timeout); -bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet* packet_out, mip_timestamp timestamp); +bool mip_parser_parse_one_packet_from_ring(mip_parser* parser, mip_packet_view* packet_out, mip_timestamp timestamp); size_t mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer, size_t input_count, mip_timestamp timestamp, unsigned int max_packets); void mip_parser_reset(mip_parser* parser); diff --git a/src/mip/mip_parser.hpp b/src/mip/mip_parser.hpp index a2656b117..6c860b16c 100644 --- a/src/mip/mip_parser.hpp +++ b/src/mip/mip_parser.hpp @@ -66,7 +66,7 @@ class Parser : public C::mip_parser template void Parser::setCallback(T& object) { - C::mip_packet_callback callback = [](void* obj, const C::mip_packet* pkt, Timestamp timestamp)->bool + C::mip_packet_callback callback = [](void* obj, const C::mip_packet_view* pkt, Timestamp timestamp)->bool { return (static_cast(obj)->*Callback)(PacketRef(pkt), timestamp); }; diff --git a/test/mip/test_mip_fields.c b/test/mip/test_mip_fields.c index 156c7a4be..a2d729d96 100644 --- a/test/mip/test_mip_fields.c +++ b/test/mip/test_mip_fields.c @@ -8,7 +8,7 @@ uint8_t packet_buffer[MIP_PACKET_LENGTH_MAX]; -struct mip_packet packet; +struct mip_packet_view packet; struct mip_field fields[MIP_PACKET_PAYLOAD_LENGTH_MAX / MIP_FIELD_LENGTH_MIN]; unsigned int num_fields = 0; diff --git a/test/mip/test_mip_packet_builder.c b/test/mip/test_mip_packet_builder.c index 5c92747c5..1370804b7 100644 --- a/test/mip/test_mip_packet_builder.c +++ b/test/mip/test_mip_packet_builder.c @@ -62,7 +62,7 @@ bool check_equal(int a, int b, const char* fmt, ...) void test_init() { - struct mip_packet packet; + struct mip_packet_view packet; mip_packet_from_buffer(&packet, buffer, sizeof(buffer)); check(packet._buffer == buffer && packet._buffer_length == sizeof(buffer)-EXTRA, "mip_packet_init is broken"); @@ -70,7 +70,7 @@ void test_init() void test_create() { - struct mip_packet packet; + struct mip_packet_view packet; uint8_t descriptors[] = {0x80, 0x01, 0x0C}; @@ -85,7 +85,7 @@ void test_create() void test_add_fields() { - struct mip_packet packet; + struct mip_packet_view packet; mip_packet_create(&packet, buffer, sizeof(buffer), 0x80); @@ -140,7 +140,7 @@ void test_add_fields() void test_short_buffer() { - struct mip_packet packet; + struct mip_packet_view packet; mip_packet_create(&packet, buffer, MIP_PACKET_LENGTH_MIN+4, 0x80); diff --git a/test/mip/test_mip_parser.c b/test/mip/test_mip_parser.c index 7636f5482..6002bc203 100644 --- a/test/mip/test_mip_parser.c +++ b/test/mip/test_mip_parser.c @@ -16,7 +16,7 @@ unsigned int num_errors = 0; size_t bytesRead = 0; size_t bytes_parsed = 0; -bool handle_packet(void* p, const struct mip_packet* packet, mip_timestamp t) +bool handle_packet(void* p, const struct mip_packet_view* packet, mip_timestamp t) { (void)t; diff --git a/test/mip/test_mip_random.c b/test/mip/test_mip_random.c index 26bf944ad..dea2cf3b2 100644 --- a/test/mip/test_mip_random.c +++ b/test/mip/test_mip_random.c @@ -16,7 +16,7 @@ size_t parsed_packet_length = 0; mip_timestamp parsed_packet_timestamp = 0; -void print_packet(FILE* out, const struct mip_packet* packet) +void print_packet(FILE* out, const struct mip_packet_view* packet) { size_t size = mip_packet_total_length(packet); const uint8_t* ptr = mip_packet_pointer(packet); @@ -29,7 +29,7 @@ void print_packet(FILE* out, const struct mip_packet* packet) } -bool handle_packet(void* p, const struct mip_packet* packet, mip_timestamp timestamp) +bool handle_packet(void* p, const struct mip_packet_view* packet, mip_timestamp timestamp) { (void)p; @@ -55,7 +55,7 @@ int main(int argc, const char* argv[]) uint8_t desc_set = (rand() % 255) + 1; // Random descriptor set. uint8_t buffer[MIP_PACKET_LENGTH_MAX]; - struct mip_packet packet; + struct mip_packet_view packet; mip_packet_create(&packet, buffer, sizeof(buffer), desc_set); for(unsigned int f=0; ; f++) From 926e7a49cf50ccd6acfa66e0052d53816cdb9329 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 6 Jun 2024 17:06:08 -0400 Subject: [PATCH 023/147] Rename PacketRef to PacketView. --- examples/threading.cpp | 2 +- examples/watch_imu.cpp | 2 +- src/mip/mip_interface.hpp | 12 ++++----- src/mip/mip_packet.hpp | 40 ++++++++++++++--------------- src/mip/mip_parser.hpp | 8 +++--- test/mip/mip_parser_performance.cpp | 2 +- test/mip/test_mip.cpp | 4 +-- 7 files changed, 35 insertions(+), 35 deletions(-) diff --git a/examples/threading.cpp b/examples/threading.cpp index db3497441..7a9288193 100644 --- a/examples/threading.cpp +++ b/examples/threading.cpp @@ -41,7 +41,7 @@ unsigned int display_progress() return count; } -void packet_callback(void*, const mip::PacketRef& packet, mip::Timestamp timestamp) +void packet_callback(void*, const mip::PacketView& packet, mip::Timestamp timestamp) { numSamples = numSamples + 1; } diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index 82876b744..2a196cd2a 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -19,7 +19,7 @@ mip::data_sensor::ScaledAccel scaled_accel; -void handlePacket(void*, const mip::PacketRef& packet, mip::Timestamp timestamp) +void handlePacket(void*, const mip::PacketView& packet, mip::Timestamp timestamp) { // if(packet.descriptorSet() != mip::MIP_SENSOR_DATA_DESC_SET) // return; diff --git a/src/mip/mip_interface.hpp b/src/mip/mip_interface.hpp index 861d240c7..ce1e52863 100644 --- a/src/mip/mip_interface.hpp +++ b/src/mip/mip_interface.hpp @@ -168,10 +168,10 @@ class Interface : public C::mip_interface void registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, C::mip_dispatch_field_callback callback, void* userData) { C::mip_interface_register_field_callback(this, &handler, descriptorSet, fieldDescriptor, callback, userData); } - template + template void registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, void* userData=nullptr); - template + template void registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, Object* object); @@ -439,12 +439,12 @@ void Interface::setCallbacks(T* object) /// ///@endcode /// -template +template void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, void* userData) { auto callback = [](void* context, const C::mip_packet_view* packet, Timestamp timestamp) { - Callback(context, PacketRef(*packet), timestamp); + Callback(context, PacketView(*packet), timestamp); }; registerPacketCallback(handler, descriptorSet, afterFields, callback, userData); @@ -481,13 +481,13 @@ void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t /// }; ///@endcode /// -template +template void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, Object* object) { auto callback = [](void* pointer, const mip::C::mip_packet_view* packet, Timestamp timestamp) { Object* obj = static_cast(pointer); - (obj->*Callback)(PacketRef(*packet), timestamp); + (obj->*Callback)(PacketView(*packet), timestamp); }; registerPacketCallback(handler, descriptorSet, afterFields, callback, object); diff --git a/src/mip/mip_packet.hpp b/src/mip/mip_packet.hpp index 86049629f..12a42098a 100644 --- a/src/mip/mip_packet.hpp +++ b/src/mip/mip_packet.hpp @@ -19,7 +19,7 @@ namespace mip //////////////////////////////////////////////////////////////////////////////// -///@brief C++ class representing a MIP PacketRef. +///@brief C++ class representing a view of a MIP packet. /// /// This is a thin wrapper around the mip_packet_view C structure. Like the C /// version, it does not contain or own the data buffer. Any of the C functions @@ -32,7 +32,7 @@ namespace mip /// for(Field field : packet) { ... } ///@endcode /// -class PacketRef : public C::mip_packet_view +class PacketView : public C::mip_packet_view { public: static constexpr size_t PAYLOAD_LENGTH_MAX = C::MIP_PACKET_PAYLOAD_LENGTH_MAX; @@ -43,13 +43,13 @@ class PacketRef : public C::mip_packet_view public: ///@copydoc mip::C::mip_packet_create - PacketRef(uint8_t* buffer, size_t bufferSize, uint8_t descriptorSet) { C::mip_packet_create(this, buffer, bufferSize, descriptorSet); } + PacketView(uint8_t* buffer, size_t bufferSize, uint8_t descriptorSet) { C::mip_packet_create(this, buffer, bufferSize, descriptorSet); } ///@copydoc mip_packet_from_buffer - PacketRef(uint8_t* buffer, size_t length) { C::mip_packet_from_buffer(this, buffer, length); } + PacketView(uint8_t* buffer, size_t length) { C::mip_packet_from_buffer(this, buffer, length); } /// Constructs a C++ %PacketRef class from the base C object. - PacketRef(const C::mip_packet_view* other) { std::memcpy(static_cast(this), other, sizeof(*this)); } + PacketView(const C::mip_packet_view* other) { std::memcpy(static_cast(this), other, sizeof(*this)); } /// Constructs a C++ %PacketRef class from the base C object. - PacketRef(const C::mip_packet_view& other) { std::memcpy(static_cast(this), &other, sizeof(*this)); } + PacketView(const C::mip_packet_view& other) { std::memcpy(static_cast(this), &other, sizeof(*this)); } // @@ -84,7 +84,7 @@ class PacketRef : public C::mip_packet_view class AllocatedField : public microstrain::Serializer { public: - AllocatedField(mip::PacketRef& packet, uint8_t* buffer, size_t space) : Serializer(buffer, space), m_packet(packet) {} + AllocatedField(mip::PacketView& packet, uint8_t* buffer, size_t space) : Serializer(buffer, space), m_packet(packet) {} //AllocatedField(const AllocatedField&) = delete; AllocatedField& operator=(const AllocatedField&) = delete; @@ -104,7 +104,7 @@ class PacketRef : public C::mip_packet_view } private: - PacketRef& m_packet; + PacketView& m_packet; }; AllocatedField createField(uint8_t fieldDescriptor) { uint8_t* ptr; size_t max_size = std::max(0, C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr)); return {*this, ptr, max_size}; } @@ -182,11 +182,11 @@ class PacketRef : public C::mip_packet_view ///@returns A PacketRef object containing the field. /// template - static PacketRef createFromField(uint8_t* buffer, size_t bufferSize, const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) + static PacketView createFromField(uint8_t* buffer, size_t bufferSize, const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) { if( fieldDescriptor == INVALID_FIELD_DESCRIPTOR ) fieldDescriptor = FieldType::FIELD_DESCRIPTOR; - PacketRef packet(buffer, bufferSize, FieldType::DESCRIPTOR_SET); + PacketView packet(buffer, bufferSize, FieldType::DESCRIPTOR_SET); packet.addField(field, fieldDescriptor); packet.finalize(); return packet; @@ -241,22 +241,22 @@ class PacketRef : public C::mip_packet_view ///@brief A mip packet with a self-contained buffer (useful with std::vector). /// template -class SizedPacketBuf : public PacketRef +class SizedPacketBuf : public PacketView { public: - SizedPacketBuf(uint8_t descriptorSet=INVALID_DESCRIPTOR_SET) : PacketRef(mData, sizeof(mData), descriptorSet) {} + SizedPacketBuf(uint8_t descriptorSet=INVALID_DESCRIPTOR_SET) : PacketView(mData, sizeof(mData), descriptorSet) {} ///@brief Creates a PacketBuf by copying existing data. /// - explicit SizedPacketBuf(const uint8_t* data, size_t length) : PacketRef(mData, sizeof(mData)) { copyFrom(data, length); } - explicit SizedPacketBuf(const PacketRef& packet) : PacketRef(mData, sizeof(mData)) { copyFrom(packet); } + explicit SizedPacketBuf(const uint8_t* data, size_t length) : PacketView(mData, sizeof(mData)) { copyFrom(data, length); } + explicit SizedPacketBuf(const PacketView& packet) : PacketView(mData, sizeof(mData)) { copyFrom(packet); } ///@brief Copy constructor - SizedPacketBuf(const SizedPacketBuf& other) : PacketRef(mData, sizeof(mData)) { copyFrom(other); } + SizedPacketBuf(const SizedPacketBuf& other) : PacketView(mData, sizeof(mData)) { copyFrom(other); } ///@brief Copy constructor (required to put packets into std::vector in some cases). template - explicit SizedPacketBuf(const SizedPacketBuf& other) : PacketRef(mData, sizeof(mData)) { copyFrom(other); }; + explicit SizedPacketBuf(const SizedPacketBuf& other) : PacketView(mData, sizeof(mData)) { copyFrom(other); }; ///@brief Copy assignment operator SizedPacketBuf& operator=(const SizedPacketBuf& other) { copyFrom(other); return *this; } @@ -273,16 +273,16 @@ class SizedPacketBuf : public PacketRef ///@param fieldDescriptor If specified (not INVALID_FIELD_DESCRIPTOR), overrides the field descriptor. /// template - SizedPacketBuf(const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) : PacketRef(mData, sizeof(mData)) { createFromField(mData, sizeof(mData), field, fieldDescriptor); } + SizedPacketBuf(const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) : PacketView(mData, sizeof(mData)) { createFromField(mData, sizeof(mData), field, fieldDescriptor); } ///@brief Explicitly obtains a reference to the packet data. /// - PacketRef ref() { return *this; } + PacketView ref() { return *this; } ///@brief Explicitly obtains a const reference to the packet data. /// - const PacketRef& ref() const { return *this; } + const PacketView& ref() const { return *this; } ///@brief Returns a pointer to the underlying buffer. /// This is technically the same as PacketRef::pointer but is writable. @@ -299,7 +299,7 @@ class SizedPacketBuf : public PacketRef /// ///@param packet A "sane" (isSane()) mip packet. /// - void copyFrom(const PacketRef& packet) { assert(packet.isSane()); copyFrom(packet.pointer(), packet.totalLength()); } + void copyFrom(const PacketView& packet) { assert(packet.isSane()); copyFrom(packet.pointer(), packet.totalLength()); } ///@brief Copies this packet to an external buffer. /// diff --git a/src/mip/mip_parser.hpp b/src/mip/mip_parser.hpp index 6c860b16c..a59efe1f1 100644 --- a/src/mip/mip_parser.hpp +++ b/src/mip/mip_parser.hpp @@ -22,11 +22,11 @@ class Parser : public C::mip_parser ///@copydoc mip::C::mip_parser_init Parser(uint8_t* buffer, size_t bufferSize, C::mip_packet_callback callback, void* callbackObject, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, callback, callbackObject, timeout); } ///@copydoc mip::C::mip_parser_init - Parser(uint8_t* buffer, size_t bufferSize, bool (*callback)(void*,const PacketRef*,Timestamp), void* callbackObject, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, (C::mip_packet_callback)callback, callbackObject, timeout); } + Parser(uint8_t* buffer, size_t bufferSize, bool (*callback)(void*,const PacketView*,Timestamp), void* callbackObject, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, (C::mip_packet_callback)callback, callbackObject, timeout); } Parser(uint8_t* buffer, size_t bufferSize, Timeout timeout) { C::mip_parser_init(this, buffer, bufferSize, nullptr, nullptr, timeout); } - template + template void setCallback(T& object); ///@copydoc mip::C::mip_parser_reset @@ -63,12 +63,12 @@ class Parser : public C::mip_parser ///@param object /// Instance of T to call the callback. /// -template +template void Parser::setCallback(T& object) { C::mip_packet_callback callback = [](void* obj, const C::mip_packet_view* pkt, Timestamp timestamp)->bool { - return (static_cast(obj)->*Callback)(PacketRef(pkt), timestamp); + return (static_cast(obj)->*Callback)(PacketView(pkt), timestamp); }; C::mip_parser_set_callback(this, callback, &object); diff --git a/test/mip/mip_parser_performance.cpp b/test/mip/mip_parser_performance.cpp index bb5e80a1a..fb1138e85 100644 --- a/test/mip/mip_parser_performance.cpp +++ b/test/mip/mip_parser_performance.cpp @@ -122,7 +122,7 @@ struct ChunkStats ChunkStats chunked_test(const Test& test, size_t chunk_size) { - auto callback = +[](void* v, const mip::PacketRef* p, mip::Timestamp) + auto callback = +[](void* v, const mip::PacketView* p, mip::Timestamp) { *static_cast(v) += 1; return true; diff --git a/test/mip/test_mip.cpp b/test/mip/test_mip.cpp index 84aeb0e40..4933c0d94 100644 --- a/test/mip/test_mip.cpp +++ b/test/mip/test_mip.cpp @@ -23,7 +23,7 @@ int main(int argc, const char* argv[]) { srand(0); - auto callback = [](void*, const PacketRef* parsedPacket, Timestamp timestamp)->bool + auto callback = [](void*, const PacketView* parsedPacket, Timestamp timestamp)->bool { unsigned int parsedFields = 0; bool error = false; @@ -78,7 +78,7 @@ int main(int argc, const char* argv[]) for(unsigned int i=0; i Date: Thu, 6 Jun 2024 17:07:23 -0400 Subject: [PATCH 024/147] Rename mip_field to mip_field_view. --- examples/CV7/CV7_example.c | 4 +- examples/watch_imu.c | 8 +-- src/mip/definitions/data_filter.c | 114 +++++++++++++++--------------- src/mip/definitions/data_filter.h | 114 +++++++++++++++--------------- src/mip/definitions/data_gnss.c | 54 +++++++------- src/mip/definitions/data_gnss.h | 54 +++++++------- src/mip/definitions/data_sensor.c | 46 ++++++------ src/mip/definitions/data_sensor.h | 46 ++++++------ src/mip/definitions/data_shared.c | 18 ++--- src/mip/definitions/data_shared.h | 18 ++--- src/mip/definitions/data_system.c | 8 +-- src/mip/definitions/data_system.h | 8 +-- src/mip/mip_cmdqueue.c | 4 +- src/mip/mip_dispatch.c | 4 +- src/mip/mip_dispatch.h | 4 +- src/mip/mip_field.c | 28 ++++---- src/mip/mip_field.h | 28 ++++---- src/mip/mip_field.hpp | 6 +- src/mip/mip_interface.hpp | 14 ++-- test/mip/test_mip_fields.c | 4 +- 20 files changed, 292 insertions(+), 292 deletions(-) diff --git a/examples/CV7/CV7_example.c b/examples/CV7/CV7_example.c index 96a55f03f..0836fc467 100644 --- a/examples/CV7/CV7_example.c +++ b/examples/CV7/CV7_example.c @@ -81,7 +81,7 @@ int usage(const char* argv0); void exit_gracefully(const char *message); bool should_exit(); -void handle_filter_event_source(void* user, const mip_field* field, mip_timestamp timestamp); +void handle_filter_event_source(void* user, const mip_field_view* field, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// @@ -355,7 +355,7 @@ int main(int argc, const char* argv[]) // Filter Event Source Field Handler //////////////////////////////////////////////////////////////////////////////// -void handle_filter_event_source(void* user, const mip_field* field, mip_timestamp timestamp) +void handle_filter_event_source(void* user, const mip_field_view* field, mip_timestamp timestamp) { mip_shared_event_source_data data; diff --git a/examples/watch_imu.c b/examples/watch_imu.c index 0c20db681..e236214ab 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -56,7 +56,7 @@ void handlePacket(void* unused, const mip_packet_view* packet, mip_timestamp tim printf("\nGot packet with descriptor set 0x%02X:", mip_packet_descriptor_set(packet)); - mip_field field; + mip_field_view field; mip_field_init_empty(&field); while( mip_field_next_in_packet(&field, packet) ) { @@ -65,7 +65,7 @@ void handlePacket(void* unused, const mip_packet_view* packet, mip_timestamp tim printf("\n"); } -void handleAccel(void* user, const mip_field* field, mip_timestamp timestamp) +void handleAccel(void* user, const mip_field_view* field, mip_timestamp timestamp) { (void)user; mip_sensor_scaled_accel_data data; @@ -82,7 +82,7 @@ void handleAccel(void* user, const mip_field* field, mip_timestamp timestamp) } } -void handleGyro(void* user, const mip_field* field, mip_timestamp timestamp) +void handleGyro(void* user, const mip_field_view* field, mip_timestamp timestamp) { (void)user; mip_sensor_scaled_gyro_data data; @@ -91,7 +91,7 @@ void handleGyro(void* user, const mip_field* field, mip_timestamp timestamp) printf("Gyro Data: %f, %f, %f\n", data.scaled_gyro[0], data.scaled_gyro[1], data.scaled_gyro[2]); } -void handleMag(void* user, const mip_field* field, mip_timestamp timestamp) +void handleMag(void* user, const mip_field_view* field, mip_timestamp timestamp) { (void)user; mip_sensor_scaled_mag_data data; diff --git a/src/mip/definitions/data_filter.c b/src/mip/definitions/data_filter.c index 9d7334c69..411495637 100644 --- a/src/mip/definitions/data_filter.c +++ b/src/mip/definitions/data_filter.c @@ -115,7 +115,7 @@ void extract_mip_filter_position_llh_data(microstrain_serializer* serializer, mi microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_position_llh_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_position_llh_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_position_llh_data* self = ptr; @@ -147,7 +147,7 @@ void extract_mip_filter_velocity_ned_data(microstrain_serializer* serializer, mi microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_velocity_ned_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_velocity_ned_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_velocity_ned_data* self = ptr; @@ -173,7 +173,7 @@ void extract_mip_filter_attitude_quaternion_data(microstrain_serializer* seriali microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_attitude_quaternion_data* self = ptr; @@ -199,7 +199,7 @@ void extract_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, mi microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_attitude_dcm_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_attitude_dcm_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_attitude_dcm_data* self = ptr; @@ -231,7 +231,7 @@ void extract_mip_filter_euler_angles_data(microstrain_serializer* serializer, mi microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_euler_angles_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_euler_angles_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_euler_angles_data* self = ptr; @@ -257,7 +257,7 @@ void extract_mip_filter_gyro_bias_data(microstrain_serializer* serializer, mip_f microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_gyro_bias_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_gyro_bias_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_gyro_bias_data* self = ptr; @@ -283,7 +283,7 @@ void extract_mip_filter_accel_bias_data(microstrain_serializer* serializer, mip_ microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_accel_bias_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_accel_bias_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_accel_bias_data* self = ptr; @@ -315,7 +315,7 @@ void extract_mip_filter_position_llh_uncertainty_data(microstrain_serializer* se microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_position_llh_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_position_llh_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_position_llh_uncertainty_data* self = ptr; @@ -347,7 +347,7 @@ void extract_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* se microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_velocity_ned_uncertainty_data* self = ptr; @@ -379,7 +379,7 @@ void extract_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* se microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_euler_angles_uncertainty_data* self = ptr; @@ -405,7 +405,7 @@ void extract_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* seria microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_gyro_bias_uncertainty_data* self = ptr; @@ -431,7 +431,7 @@ void extract_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* seri microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_accel_bias_uncertainty_data* self = ptr; @@ -459,7 +459,7 @@ void extract_mip_filter_timestamp_data(microstrain_serializer* serializer, mip_f microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_timestamp_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_timestamp_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_timestamp_data* self = ptr; @@ -487,7 +487,7 @@ void extract_mip_filter_status_data(microstrain_serializer* serializer, mip_filt extract_mip_filter_status_flags(serializer, &self->status_flags); } -bool extract_mip_filter_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_status_data* self = ptr; @@ -513,7 +513,7 @@ void extract_mip_filter_linear_accel_data(microstrain_serializer* serializer, mi microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_linear_accel_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_linear_accel_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_linear_accel_data* self = ptr; @@ -539,7 +539,7 @@ void extract_mip_filter_gravity_vector_data(microstrain_serializer* serializer, microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_gravity_vector_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_gravity_vector_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_gravity_vector_data* self = ptr; @@ -565,7 +565,7 @@ void extract_mip_filter_comp_accel_data(microstrain_serializer* serializer, mip_ microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_comp_accel_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_comp_accel_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_comp_accel_data* self = ptr; @@ -591,7 +591,7 @@ void extract_mip_filter_comp_angular_rate_data(microstrain_serializer* serialize microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_comp_angular_rate_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_comp_angular_rate_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_comp_angular_rate_data* self = ptr; @@ -617,7 +617,7 @@ void extract_mip_filter_quaternion_attitude_uncertainty_data(microstrain_seriali microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_quaternion_attitude_uncertainty_data* self = ptr; @@ -641,7 +641,7 @@ void extract_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serialize microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_wgs84_gravity_mag_data* self = ptr; @@ -673,7 +673,7 @@ void extract_mip_filter_heading_update_state_data(microstrain_serializer* serial microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_heading_update_state_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_heading_update_state_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_heading_update_state_data* self = ptr; @@ -724,7 +724,7 @@ void extract_mip_filter_magnetic_model_data(microstrain_serializer* serializer, microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_magnetic_model_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_magnetic_model_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_magnetic_model_data* self = ptr; @@ -750,7 +750,7 @@ void extract_mip_filter_accel_scale_factor_data(microstrain_serializer* serializ microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_accel_scale_factor_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_accel_scale_factor_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_accel_scale_factor_data* self = ptr; @@ -776,7 +776,7 @@ void extract_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializ microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_accel_scale_factor_uncertainty_data* self = ptr; @@ -802,7 +802,7 @@ void extract_mip_filter_gyro_scale_factor_data(microstrain_serializer* serialize microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_gyro_scale_factor_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_gyro_scale_factor_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_gyro_scale_factor_data* self = ptr; @@ -828,7 +828,7 @@ void extract_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serialize microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_gyro_scale_factor_uncertainty_data* self = ptr; @@ -854,7 +854,7 @@ void extract_mip_filter_mag_bias_data(microstrain_serializer* serializer, mip_fi microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_mag_bias_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_mag_bias_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_mag_bias_data* self = ptr; @@ -880,7 +880,7 @@ void extract_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serial microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_mag_bias_uncertainty_data* self = ptr; @@ -920,7 +920,7 @@ void extract_mip_filter_standard_atmosphere_data(microstrain_serializer* seriali microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_standard_atmosphere_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_standard_atmosphere_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_standard_atmosphere_data* self = ptr; @@ -944,7 +944,7 @@ void extract_mip_filter_pressure_altitude_data(microstrain_serializer* serialize microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_pressure_altitude_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_pressure_altitude_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_pressure_altitude_data* self = ptr; @@ -968,7 +968,7 @@ void extract_mip_filter_density_altitude_data(microstrain_serializer* serializer microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_density_altitude_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_density_altitude_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_density_altitude_data* self = ptr; @@ -994,7 +994,7 @@ void extract_mip_filter_antenna_offset_correction_data(microstrain_serializer* s microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_antenna_offset_correction_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_antenna_offset_correction_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_antenna_offset_correction_data* self = ptr; @@ -1020,7 +1020,7 @@ void extract_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_s microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_antenna_offset_correction_uncertainty_data* self = ptr; @@ -1050,7 +1050,7 @@ void extract_mip_filter_multi_antenna_offset_correction_data(microstrain_seriali microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_multi_antenna_offset_correction_data* self = ptr; @@ -1080,7 +1080,7 @@ void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(microst microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_multi_antenna_offset_correction_uncertainty_data* self = ptr; @@ -1106,7 +1106,7 @@ void extract_mip_filter_magnetometer_offset_data(microstrain_serializer* seriali microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_magnetometer_offset_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_magnetometer_offset_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_magnetometer_offset_data* self = ptr; @@ -1132,7 +1132,7 @@ void extract_mip_filter_magnetometer_matrix_data(microstrain_serializer* seriali microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_magnetometer_matrix_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_magnetometer_matrix_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_magnetometer_matrix_data* self = ptr; @@ -1158,7 +1158,7 @@ void extract_mip_filter_magnetometer_offset_uncertainty_data(microstrain_seriali microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_magnetometer_offset_uncertainty_data* self = ptr; @@ -1184,7 +1184,7 @@ void extract_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_seriali microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_magnetometer_matrix_uncertainty_data* self = ptr; @@ -1210,7 +1210,7 @@ void extract_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializ microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_magnetometer_covariance_matrix_data* self = ptr; @@ -1236,7 +1236,7 @@ void extract_mip_filter_magnetometer_residual_vector_data(microstrain_serializer microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_magnetometer_residual_vector_data* self = ptr; @@ -1268,7 +1268,7 @@ void extract_mip_filter_clock_correction_data(microstrain_serializer* serializer microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_clock_correction_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_clock_correction_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_clock_correction_data* self = ptr; @@ -1300,7 +1300,7 @@ void extract_mip_filter_clock_correction_uncertainty_data(microstrain_serializer microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_clock_correction_uncertainty_data* self = ptr; @@ -1334,7 +1334,7 @@ void extract_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* seriali microstrain_extract_u8(serializer, &self->reserved[i]); } -bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_gnss_pos_aid_status_data* self = ptr; @@ -1364,7 +1364,7 @@ void extract_mip_filter_gnss_att_aid_status_data(microstrain_serializer* seriali microstrain_extract_u8(serializer, &self->reserved[i]); } -bool extract_mip_filter_gnss_att_aid_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_gnss_att_aid_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_gnss_att_aid_status_data* self = ptr; @@ -1394,7 +1394,7 @@ void extract_mip_filter_head_aid_status_data(microstrain_serializer* serializer, microstrain_extract_float(serializer, &self->reserved[i]); } -bool extract_mip_filter_head_aid_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_head_aid_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_head_aid_status_data* self = ptr; @@ -1431,7 +1431,7 @@ void extract_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, mip microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_rel_pos_ned_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_rel_pos_ned_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_rel_pos_ned_data* self = ptr; @@ -1457,7 +1457,7 @@ void extract_mip_filter_ecef_pos_data(microstrain_serializer* serializer, mip_fi microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_ecef_pos_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_ecef_pos_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_ecef_pos_data* self = ptr; @@ -1483,7 +1483,7 @@ void extract_mip_filter_ecef_vel_data(microstrain_serializer* serializer, mip_fi microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_ecef_vel_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_ecef_vel_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_ecef_vel_data* self = ptr; @@ -1509,7 +1509,7 @@ void extract_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serial microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_ecef_pos_uncertainty_data* self = ptr; @@ -1535,7 +1535,7 @@ void extract_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serial microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_ecef_vel_uncertainty_data* self = ptr; @@ -1567,7 +1567,7 @@ void extract_mip_filter_aiding_measurement_summary_data(microstrain_serializer* extract_mip_filter_measurement_indicator(serializer, &self->indicator); } -bool extract_mip_filter_aiding_measurement_summary_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_aiding_measurement_summary_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_aiding_measurement_summary_data* self = ptr; @@ -1591,7 +1591,7 @@ void extract_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_odometer_scale_factor_error_data* self = ptr; @@ -1615,7 +1615,7 @@ void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_odometer_scale_factor_error_uncertainty_data* self = ptr; @@ -1655,7 +1655,7 @@ void extract_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* se microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_gnss_dual_antenna_status_data* self = ptr; @@ -1709,7 +1709,7 @@ void extract_mip_filter_aiding_frame_config_error_data(microstrain_serializer* s microstrain_extract_float(serializer, &self->attitude[i]); } -bool extract_mip_filter_aiding_frame_config_error_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_aiding_frame_config_error_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_aiding_frame_config_error_data* self = ptr; @@ -1741,7 +1741,7 @@ void extract_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_s microstrain_extract_float(serializer, &self->attitude_unc[i]); } -bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_aiding_frame_config_error_uncertainty_data* self = ptr; diff --git a/src/mip/definitions/data_filter.h b/src/mip/definitions/data_filter.h index 532b361d9..5b3fab150 100644 --- a/src/mip/definitions/data_filter.h +++ b/src/mip/definitions/data_filter.h @@ -234,7 +234,7 @@ struct mip_filter_position_llh_data typedef struct mip_filter_position_llh_data mip_filter_position_llh_data; void insert_mip_filter_position_llh_data(microstrain_serializer* serializer, const mip_filter_position_llh_data* self); void extract_mip_filter_position_llh_data(microstrain_serializer* serializer, mip_filter_position_llh_data* self); -bool extract_mip_filter_position_llh_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_position_llh_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -256,7 +256,7 @@ struct mip_filter_velocity_ned_data typedef struct mip_filter_velocity_ned_data mip_filter_velocity_ned_data; void insert_mip_filter_velocity_ned_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_data* self); void extract_mip_filter_velocity_ned_data(microstrain_serializer* serializer, mip_filter_velocity_ned_data* self); -bool extract_mip_filter_velocity_ned_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_velocity_ned_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -284,7 +284,7 @@ struct mip_filter_attitude_quaternion_data typedef struct mip_filter_attitude_quaternion_data mip_filter_attitude_quaternion_data; void insert_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, const mip_filter_attitude_quaternion_data* self); void extract_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, mip_filter_attitude_quaternion_data* self); -bool extract_mip_filter_attitude_quaternion_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_attitude_quaternion_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -314,7 +314,7 @@ struct mip_filter_attitude_dcm_data typedef struct mip_filter_attitude_dcm_data mip_filter_attitude_dcm_data; void insert_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, const mip_filter_attitude_dcm_data* self); void extract_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, mip_filter_attitude_dcm_data* self); -bool extract_mip_filter_attitude_dcm_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_attitude_dcm_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -337,7 +337,7 @@ struct mip_filter_euler_angles_data typedef struct mip_filter_euler_angles_data mip_filter_euler_angles_data; void insert_mip_filter_euler_angles_data(microstrain_serializer* serializer, const mip_filter_euler_angles_data* self); void extract_mip_filter_euler_angles_data(microstrain_serializer* serializer, mip_filter_euler_angles_data* self); -bool extract_mip_filter_euler_angles_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_euler_angles_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -357,7 +357,7 @@ struct mip_filter_gyro_bias_data typedef struct mip_filter_gyro_bias_data mip_filter_gyro_bias_data; void insert_mip_filter_gyro_bias_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_data* self); void extract_mip_filter_gyro_bias_data(microstrain_serializer* serializer, mip_filter_gyro_bias_data* self); -bool extract_mip_filter_gyro_bias_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_gyro_bias_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -377,7 +377,7 @@ struct mip_filter_accel_bias_data typedef struct mip_filter_accel_bias_data mip_filter_accel_bias_data; void insert_mip_filter_accel_bias_data(microstrain_serializer* serializer, const mip_filter_accel_bias_data* self); void extract_mip_filter_accel_bias_data(microstrain_serializer* serializer, mip_filter_accel_bias_data* self); -bool extract_mip_filter_accel_bias_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_accel_bias_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -399,7 +399,7 @@ struct mip_filter_position_llh_uncertainty_data typedef struct mip_filter_position_llh_uncertainty_data mip_filter_position_llh_uncertainty_data; void insert_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self); void extract_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, mip_filter_position_llh_uncertainty_data* self); -bool extract_mip_filter_position_llh_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_position_llh_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -421,7 +421,7 @@ struct mip_filter_velocity_ned_uncertainty_data typedef struct mip_filter_velocity_ned_uncertainty_data mip_filter_velocity_ned_uncertainty_data; void insert_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self); void extract_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self); -bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -444,7 +444,7 @@ struct mip_filter_euler_angles_uncertainty_data typedef struct mip_filter_euler_angles_uncertainty_data mip_filter_euler_angles_uncertainty_data; void insert_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self); void extract_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self); -bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -464,7 +464,7 @@ struct mip_filter_gyro_bias_uncertainty_data typedef struct mip_filter_gyro_bias_uncertainty_data mip_filter_gyro_bias_uncertainty_data; void insert_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self); void extract_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self); -bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -484,7 +484,7 @@ struct mip_filter_accel_bias_uncertainty_data typedef struct mip_filter_accel_bias_uncertainty_data mip_filter_accel_bias_uncertainty_data; void insert_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self); void extract_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self); -bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -511,7 +511,7 @@ struct mip_filter_timestamp_data typedef struct mip_filter_timestamp_data mip_filter_timestamp_data; void insert_mip_filter_timestamp_data(microstrain_serializer* serializer, const mip_filter_timestamp_data* self); void extract_mip_filter_timestamp_data(microstrain_serializer* serializer, mip_filter_timestamp_data* self); -bool extract_mip_filter_timestamp_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -532,7 +532,7 @@ struct mip_filter_status_data typedef struct mip_filter_status_data mip_filter_status_data; void insert_mip_filter_status_data(microstrain_serializer* serializer, const mip_filter_status_data* self); void extract_mip_filter_status_data(microstrain_serializer* serializer, mip_filter_status_data* self); -bool extract_mip_filter_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_status_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -553,7 +553,7 @@ struct mip_filter_linear_accel_data typedef struct mip_filter_linear_accel_data mip_filter_linear_accel_data; void insert_mip_filter_linear_accel_data(microstrain_serializer* serializer, const mip_filter_linear_accel_data* self); void extract_mip_filter_linear_accel_data(microstrain_serializer* serializer, mip_filter_linear_accel_data* self); -bool extract_mip_filter_linear_accel_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_linear_accel_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -573,7 +573,7 @@ struct mip_filter_gravity_vector_data typedef struct mip_filter_gravity_vector_data mip_filter_gravity_vector_data; void insert_mip_filter_gravity_vector_data(microstrain_serializer* serializer, const mip_filter_gravity_vector_data* self); void extract_mip_filter_gravity_vector_data(microstrain_serializer* serializer, mip_filter_gravity_vector_data* self); -bool extract_mip_filter_gravity_vector_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_gravity_vector_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -593,7 +593,7 @@ struct mip_filter_comp_accel_data typedef struct mip_filter_comp_accel_data mip_filter_comp_accel_data; void insert_mip_filter_comp_accel_data(microstrain_serializer* serializer, const mip_filter_comp_accel_data* self); void extract_mip_filter_comp_accel_data(microstrain_serializer* serializer, mip_filter_comp_accel_data* self); -bool extract_mip_filter_comp_accel_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_comp_accel_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -613,7 +613,7 @@ struct mip_filter_comp_angular_rate_data typedef struct mip_filter_comp_angular_rate_data mip_filter_comp_angular_rate_data; void insert_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, const mip_filter_comp_angular_rate_data* self); void extract_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, mip_filter_comp_angular_rate_data* self); -bool extract_mip_filter_comp_angular_rate_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_comp_angular_rate_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -633,7 +633,7 @@ struct mip_filter_quaternion_attitude_uncertainty_data typedef struct mip_filter_quaternion_attitude_uncertainty_data mip_filter_quaternion_attitude_uncertainty_data; void insert_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self); void extract_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self); -bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -653,7 +653,7 @@ struct mip_filter_wgs84_gravity_mag_data typedef struct mip_filter_wgs84_gravity_mag_data mip_filter_wgs84_gravity_mag_data; void insert_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self); void extract_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self); -bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -685,7 +685,7 @@ struct mip_filter_heading_update_state_data typedef struct mip_filter_heading_update_state_data mip_filter_heading_update_state_data; void insert_mip_filter_heading_update_state_data(microstrain_serializer* serializer, const mip_filter_heading_update_state_data* self); void extract_mip_filter_heading_update_state_data(microstrain_serializer* serializer, mip_filter_heading_update_state_data* self); -bool extract_mip_filter_heading_update_state_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_heading_update_state_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self); void extract_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self); @@ -713,7 +713,7 @@ struct mip_filter_magnetic_model_data typedef struct mip_filter_magnetic_model_data mip_filter_magnetic_model_data; void insert_mip_filter_magnetic_model_data(microstrain_serializer* serializer, const mip_filter_magnetic_model_data* self); void extract_mip_filter_magnetic_model_data(microstrain_serializer* serializer, mip_filter_magnetic_model_data* self); -bool extract_mip_filter_magnetic_model_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_magnetic_model_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -733,7 +733,7 @@ struct mip_filter_accel_scale_factor_data typedef struct mip_filter_accel_scale_factor_data mip_filter_accel_scale_factor_data; void insert_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_data* self); void extract_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_data* self); -bool extract_mip_filter_accel_scale_factor_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_accel_scale_factor_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -753,7 +753,7 @@ struct mip_filter_accel_scale_factor_uncertainty_data typedef struct mip_filter_accel_scale_factor_uncertainty_data mip_filter_accel_scale_factor_uncertainty_data; void insert_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self); void extract_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self); -bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -773,7 +773,7 @@ struct mip_filter_gyro_scale_factor_data typedef struct mip_filter_gyro_scale_factor_data mip_filter_gyro_scale_factor_data; void insert_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_data* self); void extract_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_data* self); -bool extract_mip_filter_gyro_scale_factor_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_gyro_scale_factor_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -793,7 +793,7 @@ struct mip_filter_gyro_scale_factor_uncertainty_data typedef struct mip_filter_gyro_scale_factor_uncertainty_data mip_filter_gyro_scale_factor_uncertainty_data; void insert_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self); void extract_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self); -bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -813,7 +813,7 @@ struct mip_filter_mag_bias_data typedef struct mip_filter_mag_bias_data mip_filter_mag_bias_data; void insert_mip_filter_mag_bias_data(microstrain_serializer* serializer, const mip_filter_mag_bias_data* self); void extract_mip_filter_mag_bias_data(microstrain_serializer* serializer, mip_filter_mag_bias_data* self); -bool extract_mip_filter_mag_bias_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_mag_bias_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -833,7 +833,7 @@ struct mip_filter_mag_bias_uncertainty_data typedef struct mip_filter_mag_bias_uncertainty_data mip_filter_mag_bias_uncertainty_data; void insert_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self); void extract_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self); -bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -859,7 +859,7 @@ struct mip_filter_standard_atmosphere_data typedef struct mip_filter_standard_atmosphere_data mip_filter_standard_atmosphere_data; void insert_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, const mip_filter_standard_atmosphere_data* self); void extract_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, mip_filter_standard_atmosphere_data* self); -bool extract_mip_filter_standard_atmosphere_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_standard_atmosphere_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -883,7 +883,7 @@ struct mip_filter_pressure_altitude_data typedef struct mip_filter_pressure_altitude_data mip_filter_pressure_altitude_data; void insert_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, const mip_filter_pressure_altitude_data* self); void extract_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, mip_filter_pressure_altitude_data* self); -bool extract_mip_filter_pressure_altitude_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_pressure_altitude_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -902,7 +902,7 @@ struct mip_filter_density_altitude_data typedef struct mip_filter_density_altitude_data mip_filter_density_altitude_data; void insert_mip_filter_density_altitude_data(microstrain_serializer* serializer, const mip_filter_density_altitude_data* self); void extract_mip_filter_density_altitude_data(microstrain_serializer* serializer, mip_filter_density_altitude_data* self); -bool extract_mip_filter_density_altitude_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_density_altitude_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -924,7 +924,7 @@ struct mip_filter_antenna_offset_correction_data typedef struct mip_filter_antenna_offset_correction_data mip_filter_antenna_offset_correction_data; void insert_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_data* self); void extract_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_data* self); -bool extract_mip_filter_antenna_offset_correction_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_antenna_offset_correction_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -944,7 +944,7 @@ struct mip_filter_antenna_offset_correction_uncertainty_data typedef struct mip_filter_antenna_offset_correction_uncertainty_data mip_filter_antenna_offset_correction_uncertainty_data; void insert_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self); void extract_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self); -bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -967,7 +967,7 @@ struct mip_filter_multi_antenna_offset_correction_data typedef struct mip_filter_multi_antenna_offset_correction_data mip_filter_multi_antenna_offset_correction_data; void insert_mip_filter_multi_antenna_offset_correction_data(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_data* self); void extract_mip_filter_multi_antenna_offset_correction_data(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_data* self); -bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -988,7 +988,7 @@ struct mip_filter_multi_antenna_offset_correction_uncertainty_data typedef struct mip_filter_multi_antenna_offset_correction_uncertainty_data mip_filter_multi_antenna_offset_correction_uncertainty_data; void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_uncertainty_data* self); void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_uncertainty_data* self); -bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1010,7 +1010,7 @@ struct mip_filter_magnetometer_offset_data typedef struct mip_filter_magnetometer_offset_data mip_filter_magnetometer_offset_data; void insert_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_data* self); void extract_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_data* self); -bool extract_mip_filter_magnetometer_offset_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_magnetometer_offset_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1032,7 +1032,7 @@ struct mip_filter_magnetometer_matrix_data typedef struct mip_filter_magnetometer_matrix_data mip_filter_magnetometer_matrix_data; void insert_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_data* self); void extract_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_data* self); -bool extract_mip_filter_magnetometer_matrix_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_magnetometer_matrix_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1052,7 +1052,7 @@ struct mip_filter_magnetometer_offset_uncertainty_data typedef struct mip_filter_magnetometer_offset_uncertainty_data mip_filter_magnetometer_offset_uncertainty_data; void insert_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self); void extract_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self); -bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1072,7 +1072,7 @@ struct mip_filter_magnetometer_matrix_uncertainty_data typedef struct mip_filter_magnetometer_matrix_uncertainty_data mip_filter_magnetometer_matrix_uncertainty_data; void insert_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self); void extract_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self); -bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1091,7 +1091,7 @@ struct mip_filter_magnetometer_covariance_matrix_data typedef struct mip_filter_magnetometer_covariance_matrix_data mip_filter_magnetometer_covariance_matrix_data; void insert_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self); void extract_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self); -bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1111,7 +1111,7 @@ struct mip_filter_magnetometer_residual_vector_data typedef struct mip_filter_magnetometer_residual_vector_data mip_filter_magnetometer_residual_vector_data; void insert_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self); void extract_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self); -bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1133,7 +1133,7 @@ struct mip_filter_clock_correction_data typedef struct mip_filter_clock_correction_data mip_filter_clock_correction_data; void insert_mip_filter_clock_correction_data(microstrain_serializer* serializer, const mip_filter_clock_correction_data* self); void extract_mip_filter_clock_correction_data(microstrain_serializer* serializer, mip_filter_clock_correction_data* self); -bool extract_mip_filter_clock_correction_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_clock_correction_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1155,7 +1155,7 @@ struct mip_filter_clock_correction_uncertainty_data typedef struct mip_filter_clock_correction_uncertainty_data mip_filter_clock_correction_uncertainty_data; void insert_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self); void extract_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self); -bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1177,7 +1177,7 @@ struct mip_filter_gnss_pos_aid_status_data typedef struct mip_filter_gnss_pos_aid_status_data mip_filter_gnss_pos_aid_status_data; void insert_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self); void extract_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self); -bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1198,7 +1198,7 @@ struct mip_filter_gnss_att_aid_status_data typedef struct mip_filter_gnss_att_aid_status_data mip_filter_gnss_att_aid_status_data; void insert_mip_filter_gnss_att_aid_status_data(microstrain_serializer* serializer, const mip_filter_gnss_att_aid_status_data* self); void extract_mip_filter_gnss_att_aid_status_data(microstrain_serializer* serializer, mip_filter_gnss_att_aid_status_data* self); -bool extract_mip_filter_gnss_att_aid_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_gnss_att_aid_status_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1223,7 +1223,7 @@ struct mip_filter_head_aid_status_data typedef struct mip_filter_head_aid_status_data mip_filter_head_aid_status_data; void insert_mip_filter_head_aid_status_data(microstrain_serializer* serializer, const mip_filter_head_aid_status_data* self); void extract_mip_filter_head_aid_status_data(microstrain_serializer* serializer, mip_filter_head_aid_status_data* self); -bool extract_mip_filter_head_aid_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_head_aid_status_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self); void extract_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self); @@ -1246,7 +1246,7 @@ struct mip_filter_rel_pos_ned_data typedef struct mip_filter_rel_pos_ned_data mip_filter_rel_pos_ned_data; void insert_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, const mip_filter_rel_pos_ned_data* self); void extract_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, mip_filter_rel_pos_ned_data* self); -bool extract_mip_filter_rel_pos_ned_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_rel_pos_ned_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1266,7 +1266,7 @@ struct mip_filter_ecef_pos_data typedef struct mip_filter_ecef_pos_data mip_filter_ecef_pos_data; void insert_mip_filter_ecef_pos_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_data* self); void extract_mip_filter_ecef_pos_data(microstrain_serializer* serializer, mip_filter_ecef_pos_data* self); -bool extract_mip_filter_ecef_pos_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_ecef_pos_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1286,7 +1286,7 @@ struct mip_filter_ecef_vel_data typedef struct mip_filter_ecef_vel_data mip_filter_ecef_vel_data; void insert_mip_filter_ecef_vel_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_data* self); void extract_mip_filter_ecef_vel_data(microstrain_serializer* serializer, mip_filter_ecef_vel_data* self); -bool extract_mip_filter_ecef_vel_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_ecef_vel_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1306,7 +1306,7 @@ struct mip_filter_ecef_pos_uncertainty_data typedef struct mip_filter_ecef_pos_uncertainty_data mip_filter_ecef_pos_uncertainty_data; void insert_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self); void extract_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self); -bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1326,7 +1326,7 @@ struct mip_filter_ecef_vel_uncertainty_data typedef struct mip_filter_ecef_vel_uncertainty_data mip_filter_ecef_vel_uncertainty_data; void insert_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self); void extract_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self); -bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1348,7 +1348,7 @@ struct mip_filter_aiding_measurement_summary_data typedef struct mip_filter_aiding_measurement_summary_data mip_filter_aiding_measurement_summary_data; void insert_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self); void extract_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, mip_filter_aiding_measurement_summary_data* self); -bool extract_mip_filter_aiding_measurement_summary_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_aiding_measurement_summary_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1368,7 +1368,7 @@ struct mip_filter_odometer_scale_factor_error_data typedef struct mip_filter_odometer_scale_factor_error_data mip_filter_odometer_scale_factor_error_data; void insert_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self); void extract_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self); -bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1388,7 +1388,7 @@ struct mip_filter_odometer_scale_factor_error_uncertainty_data typedef struct mip_filter_odometer_scale_factor_error_uncertainty_data mip_filter_odometer_scale_factor_error_uncertainty_data; void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self); void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self); -bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1424,7 +1424,7 @@ struct mip_filter_gnss_dual_antenna_status_data typedef struct mip_filter_gnss_dual_antenna_status_data mip_filter_gnss_dual_antenna_status_data; void insert_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self); void extract_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self); -bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self); void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self); @@ -1453,7 +1453,7 @@ struct mip_filter_aiding_frame_config_error_data typedef struct mip_filter_aiding_frame_config_error_data mip_filter_aiding_frame_config_error_data; void insert_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self); void extract_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_data* self); -bool extract_mip_filter_aiding_frame_config_error_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_aiding_frame_config_error_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -1476,7 +1476,7 @@ struct mip_filter_aiding_frame_config_error_uncertainty_data typedef struct mip_filter_aiding_frame_config_error_uncertainty_data mip_filter_aiding_frame_config_error_uncertainty_data; void insert_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_uncertainty_data* self); void extract_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self); -bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); ///@} diff --git a/src/mip/definitions/data_gnss.c b/src/mip/definitions/data_gnss.c index 90dfadc6c..72162ba2b 100644 --- a/src/mip/definitions/data_gnss.c +++ b/src/mip/definitions/data_gnss.c @@ -94,7 +94,7 @@ void extract_mip_gnss_pos_llh_data(microstrain_serializer* serializer, mip_gnss_ extract_mip_gnss_pos_llh_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_pos_llh_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_pos_llh_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_pos_llh_data* self = ptr; @@ -135,7 +135,7 @@ void extract_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, mip_gnss extract_mip_gnss_pos_ecef_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_pos_ecef_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_pos_ecef_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_pos_ecef_data* self = ptr; @@ -192,7 +192,7 @@ void extract_mip_gnss_vel_ned_data(microstrain_serializer* serializer, mip_gnss_ extract_mip_gnss_vel_ned_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_vel_ned_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_vel_ned_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_vel_ned_data* self = ptr; @@ -233,7 +233,7 @@ void extract_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, mip_gnss extract_mip_gnss_vel_ecef_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_vel_ecef_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_vel_ecef_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_vel_ecef_data* self = ptr; @@ -292,7 +292,7 @@ void extract_mip_gnss_dop_data(microstrain_serializer* serializer, mip_gnss_dop_ extract_mip_gnss_dop_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_dop_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_dop_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_dop_data* self = ptr; @@ -351,7 +351,7 @@ void extract_mip_gnss_utc_time_data(microstrain_serializer* serializer, mip_gnss extract_mip_gnss_utc_time_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_utc_time_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_utc_time_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_utc_time_data* self = ptr; @@ -390,7 +390,7 @@ void extract_mip_gnss_gps_time_data(microstrain_serializer* serializer, mip_gnss extract_mip_gnss_gps_time_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_gps_time_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_gps_time_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_gps_time_data* self = ptr; @@ -433,7 +433,7 @@ void extract_mip_gnss_clock_info_data(microstrain_serializer* serializer, mip_gn extract_mip_gnss_clock_info_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_clock_info_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_clock_info_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_clock_info_data* self = ptr; @@ -476,7 +476,7 @@ void extract_mip_gnss_fix_info_data(microstrain_serializer* serializer, mip_gnss extract_mip_gnss_fix_info_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_fix_info_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_fix_info_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_fix_info_data* self = ptr; @@ -553,7 +553,7 @@ void extract_mip_gnss_sv_info_data(microstrain_serializer* serializer, mip_gnss_ extract_mip_gnss_sv_info_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_sv_info_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_sv_info_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_sv_info_data* self = ptr; @@ -607,7 +607,7 @@ void extract_mip_gnss_hw_status_data(microstrain_serializer* serializer, mip_gns extract_mip_gnss_hw_status_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_hw_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_hw_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_hw_status_data* self = ptr; @@ -687,7 +687,7 @@ void extract_mip_gnss_dgps_info_data(microstrain_serializer* serializer, mip_gns extract_mip_gnss_dgps_info_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_dgps_info_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_dgps_info_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_dgps_info_data* self = ptr; @@ -734,7 +734,7 @@ void extract_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, mip_ extract_mip_gnss_dgps_channel_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_dgps_channel_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_dgps_channel_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_dgps_channel_data* self = ptr; @@ -781,7 +781,7 @@ void extract_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, mip_ extract_mip_gnss_clock_info_2_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_clock_info_2_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_clock_info_2_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_clock_info_2_data* self = ptr; @@ -816,7 +816,7 @@ void extract_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, extract_mip_gnss_gps_leap_seconds_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_gps_leap_seconds_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_gps_leap_seconds_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_gps_leap_seconds_data* self = ptr; @@ -871,7 +871,7 @@ void extract_mip_gnss_sbas_info_data(microstrain_serializer* serializer, mip_gns extract_mip_gnss_sbas_info_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_sbas_info_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_sbas_info_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_sbas_info_data* self = ptr; @@ -949,7 +949,7 @@ void extract_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, m extract_mip_gnss_sbas_correction_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_sbas_correction_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_sbas_correction_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_sbas_correction_data* self = ptr; @@ -998,7 +998,7 @@ void extract_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer extract_mip_gnss_rf_error_detection_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_rf_error_detection_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_rf_error_detection_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_rf_error_detection_data* self = ptr; @@ -1088,7 +1088,7 @@ void extract_mip_gnss_base_station_info_data(microstrain_serializer* serializer, extract_mip_gnss_base_station_info_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_base_station_info_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_base_station_info_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_base_station_info_data* self = ptr; @@ -1168,7 +1168,7 @@ void extract_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serial extract_mip_gnss_rtk_corrections_status_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_rtk_corrections_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_rtk_corrections_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_rtk_corrections_status_data* self = ptr; @@ -1246,7 +1246,7 @@ void extract_mip_gnss_satellite_status_data(microstrain_serializer* serializer, extract_mip_gnss_satellite_status_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_satellite_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_satellite_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_satellite_status_data* self = ptr; @@ -1349,7 +1349,7 @@ void extract_mip_gnss_raw_data(microstrain_serializer* serializer, mip_gnss_raw_ extract_mip_gnss_raw_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_raw_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_raw_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_raw_data* self = ptr; @@ -1523,7 +1523,7 @@ void extract_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, mip extract_mip_gnss_gps_ephemeris_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_gps_ephemeris_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_gps_ephemeris_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_gps_ephemeris_data* self = ptr; @@ -1686,7 +1686,7 @@ void extract_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, extract_mip_gnss_galileo_ephemeris_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_galileo_ephemeris_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_galileo_ephemeris_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_galileo_ephemeris_data* self = ptr; @@ -1819,7 +1819,7 @@ void extract_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, mip extract_mip_gnss_glo_ephemeris_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_glo_ephemeris_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_glo_ephemeris_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_glo_ephemeris_data* self = ptr; @@ -1870,7 +1870,7 @@ void extract_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, mip extract_mip_gnss_gps_iono_corr_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_gps_iono_corr_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_gps_iono_corr_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_gps_iono_corr_data* self = ptr; @@ -1919,7 +1919,7 @@ void extract_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, extract_mip_gnss_galileo_iono_corr_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_gnss_galileo_iono_corr_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_gnss_galileo_iono_corr_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_gnss_galileo_iono_corr_data* self = ptr; diff --git a/src/mip/definitions/data_gnss.h b/src/mip/definitions/data_gnss.h index 6e5613e20..b240b6d5f 100644 --- a/src/mip/definitions/data_gnss.h +++ b/src/mip/definitions/data_gnss.h @@ -202,7 +202,7 @@ struct mip_gnss_pos_llh_data typedef struct mip_gnss_pos_llh_data mip_gnss_pos_llh_data; void insert_mip_gnss_pos_llh_data(microstrain_serializer* serializer, const mip_gnss_pos_llh_data* self); void extract_mip_gnss_pos_llh_data(microstrain_serializer* serializer, mip_gnss_pos_llh_data* self); -bool extract_mip_gnss_pos_llh_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_pos_llh_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self); void extract_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self); @@ -233,7 +233,7 @@ struct mip_gnss_pos_ecef_data typedef struct mip_gnss_pos_ecef_data mip_gnss_pos_ecef_data; void insert_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data* self); void extract_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, mip_gnss_pos_ecef_data* self); -bool extract_mip_gnss_pos_ecef_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_pos_ecef_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self); void extract_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self); @@ -272,7 +272,7 @@ struct mip_gnss_vel_ned_data typedef struct mip_gnss_vel_ned_data mip_gnss_vel_ned_data; void insert_mip_gnss_vel_ned_data(microstrain_serializer* serializer, const mip_gnss_vel_ned_data* self); void extract_mip_gnss_vel_ned_data(microstrain_serializer* serializer, mip_gnss_vel_ned_data* self); -bool extract_mip_gnss_vel_ned_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_vel_ned_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self); void extract_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self); @@ -303,7 +303,7 @@ struct mip_gnss_vel_ecef_data typedef struct mip_gnss_vel_ecef_data mip_gnss_vel_ecef_data; void insert_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data* self); void extract_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, mip_gnss_vel_ecef_data* self); -bool extract_mip_gnss_vel_ecef_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_vel_ecef_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self); void extract_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self); @@ -344,7 +344,7 @@ struct mip_gnss_dop_data typedef struct mip_gnss_dop_data mip_gnss_dop_data; void insert_mip_gnss_dop_data(microstrain_serializer* serializer, const mip_gnss_dop_data* self); void extract_mip_gnss_dop_data(microstrain_serializer* serializer, mip_gnss_dop_data* self); -bool extract_mip_gnss_dop_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_dop_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self); void extract_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self); @@ -380,7 +380,7 @@ struct mip_gnss_utc_time_data typedef struct mip_gnss_utc_time_data mip_gnss_utc_time_data; void insert_mip_gnss_utc_time_data(microstrain_serializer* serializer, const mip_gnss_utc_time_data* self); void extract_mip_gnss_utc_time_data(microstrain_serializer* serializer, mip_gnss_utc_time_data* self); -bool extract_mip_gnss_utc_time_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_utc_time_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self); void extract_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self); @@ -411,7 +411,7 @@ struct mip_gnss_gps_time_data typedef struct mip_gnss_gps_time_data mip_gnss_gps_time_data; void insert_mip_gnss_gps_time_data(microstrain_serializer* serializer, const mip_gnss_gps_time_data* self); void extract_mip_gnss_gps_time_data(microstrain_serializer* serializer, mip_gnss_gps_time_data* self); -bool extract_mip_gnss_gps_time_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_gps_time_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self); void extract_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self); @@ -444,7 +444,7 @@ struct mip_gnss_clock_info_data typedef struct mip_gnss_clock_info_data mip_gnss_clock_info_data; void insert_mip_gnss_clock_info_data(microstrain_serializer* serializer, const mip_gnss_clock_info_data* self); void extract_mip_gnss_clock_info_data(microstrain_serializer* serializer, mip_gnss_clock_info_data* self); -bool extract_mip_gnss_clock_info_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_clock_info_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self); void extract_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self); @@ -493,7 +493,7 @@ struct mip_gnss_fix_info_data typedef struct mip_gnss_fix_info_data mip_gnss_fix_info_data; void insert_mip_gnss_fix_info_data(microstrain_serializer* serializer, const mip_gnss_fix_info_data* self); void extract_mip_gnss_fix_info_data(microstrain_serializer* serializer, mip_gnss_fix_info_data* self); -bool extract_mip_gnss_fix_info_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_fix_info_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self); void extract_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self); @@ -546,7 +546,7 @@ struct mip_gnss_sv_info_data typedef struct mip_gnss_sv_info_data mip_gnss_sv_info_data; void insert_mip_gnss_sv_info_data(microstrain_serializer* serializer, const mip_gnss_sv_info_data* self); void extract_mip_gnss_sv_info_data(microstrain_serializer* serializer, mip_gnss_sv_info_data* self); -bool extract_mip_gnss_sv_info_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_sv_info_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self); void extract_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self); @@ -599,7 +599,7 @@ struct mip_gnss_hw_status_data typedef struct mip_gnss_hw_status_data mip_gnss_hw_status_data; void insert_mip_gnss_hw_status_data(microstrain_serializer* serializer, const mip_gnss_hw_status_data* self); void extract_mip_gnss_hw_status_data(microstrain_serializer* serializer, mip_gnss_hw_status_data* self); -bool extract_mip_gnss_hw_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_hw_status_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self); void extract_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self); @@ -655,7 +655,7 @@ struct mip_gnss_dgps_info_data typedef struct mip_gnss_dgps_info_data mip_gnss_dgps_info_data; void insert_mip_gnss_dgps_info_data(microstrain_serializer* serializer, const mip_gnss_dgps_info_data* self); void extract_mip_gnss_dgps_info_data(microstrain_serializer* serializer, mip_gnss_dgps_info_data* self); -bool extract_mip_gnss_dgps_info_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_dgps_info_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self); void extract_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self); @@ -692,7 +692,7 @@ struct mip_gnss_dgps_channel_data typedef struct mip_gnss_dgps_channel_data mip_gnss_dgps_channel_data; void insert_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data* self); void extract_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, mip_gnss_dgps_channel_data* self); -bool extract_mip_gnss_dgps_channel_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_dgps_channel_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self); void extract_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self); @@ -729,7 +729,7 @@ struct mip_gnss_clock_info_2_data typedef struct mip_gnss_clock_info_2_data mip_gnss_clock_info_2_data; void insert_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data* self); void extract_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, mip_gnss_clock_info_2_data* self); -bool extract_mip_gnss_clock_info_2_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_clock_info_2_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self); void extract_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self); @@ -757,7 +757,7 @@ struct mip_gnss_gps_leap_seconds_data typedef struct mip_gnss_gps_leap_seconds_data mip_gnss_gps_leap_seconds_data; void insert_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self); void extract_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data* self); -bool extract_mip_gnss_gps_leap_seconds_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_gps_leap_seconds_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self); void extract_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self); @@ -804,7 +804,7 @@ struct mip_gnss_sbas_info_data typedef struct mip_gnss_sbas_info_data mip_gnss_sbas_info_data; void insert_mip_gnss_sbas_info_data(microstrain_serializer* serializer, const mip_gnss_sbas_info_data* self); void extract_mip_gnss_sbas_info_data(microstrain_serializer* serializer, mip_gnss_sbas_info_data* self); -bool extract_mip_gnss_sbas_info_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_sbas_info_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self); void extract_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self); @@ -868,7 +868,7 @@ struct mip_gnss_sbas_correction_data typedef struct mip_gnss_sbas_correction_data mip_gnss_sbas_correction_data; void insert_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data* self); void extract_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, mip_gnss_sbas_correction_data* self); -bool extract_mip_gnss_sbas_correction_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_sbas_correction_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self); void extract_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self); @@ -920,7 +920,7 @@ struct mip_gnss_rf_error_detection_data typedef struct mip_gnss_rf_error_detection_data mip_gnss_rf_error_detection_data; void insert_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data* self); void extract_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data* self); -bool extract_mip_gnss_rf_error_detection_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_rf_error_detection_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self); void extract_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self); @@ -983,7 +983,7 @@ struct mip_gnss_base_station_info_data typedef struct mip_gnss_base_station_info_data mip_gnss_base_station_info_data; void insert_mip_gnss_base_station_info_data(microstrain_serializer* serializer, const mip_gnss_base_station_info_data* self); void extract_mip_gnss_base_station_info_data(microstrain_serializer* serializer, mip_gnss_base_station_info_data* self); -bool extract_mip_gnss_base_station_info_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_base_station_info_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self); void extract_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self); @@ -1042,7 +1042,7 @@ struct mip_gnss_rtk_corrections_status_data typedef struct mip_gnss_rtk_corrections_status_data mip_gnss_rtk_corrections_status_data; void insert_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self); void extract_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data* self); -bool extract_mip_gnss_rtk_corrections_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_rtk_corrections_status_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self); void extract_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self); @@ -1088,7 +1088,7 @@ struct mip_gnss_satellite_status_data typedef struct mip_gnss_satellite_status_data mip_gnss_satellite_status_data; void insert_mip_gnss_satellite_status_data(microstrain_serializer* serializer, const mip_gnss_satellite_status_data* self); void extract_mip_gnss_satellite_status_data(microstrain_serializer* serializer, mip_gnss_satellite_status_data* self); -bool extract_mip_gnss_satellite_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_satellite_status_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self); void extract_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self); @@ -1157,7 +1157,7 @@ struct mip_gnss_raw_data typedef struct mip_gnss_raw_data mip_gnss_raw_data; void insert_mip_gnss_raw_data(microstrain_serializer* serializer, const mip_gnss_raw_data* self); void extract_mip_gnss_raw_data(microstrain_serializer* serializer, mip_gnss_raw_data* self); -bool extract_mip_gnss_raw_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_raw_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self); void extract_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self); @@ -1222,7 +1222,7 @@ struct mip_gnss_gps_ephemeris_data typedef struct mip_gnss_gps_ephemeris_data mip_gnss_gps_ephemeris_data; void insert_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data* self); void extract_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data* self); -bool extract_mip_gnss_gps_ephemeris_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_gps_ephemeris_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self); void extract_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self); @@ -1284,7 +1284,7 @@ struct mip_gnss_galileo_ephemeris_data typedef struct mip_gnss_galileo_ephemeris_data mip_gnss_galileo_ephemeris_data; void insert_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self); void extract_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data* self); -bool extract_mip_gnss_galileo_ephemeris_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_galileo_ephemeris_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self); void extract_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self); @@ -1336,7 +1336,7 @@ struct mip_gnss_glo_ephemeris_data typedef struct mip_gnss_glo_ephemeris_data mip_gnss_glo_ephemeris_data; void insert_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data* self); void extract_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data* self); -bool extract_mip_gnss_glo_ephemeris_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_glo_ephemeris_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self); void extract_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self); @@ -1371,7 +1371,7 @@ struct mip_gnss_gps_iono_corr_data typedef struct mip_gnss_gps_iono_corr_data mip_gnss_gps_iono_corr_data; void insert_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data* self); void extract_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data* self); -bool extract_mip_gnss_gps_iono_corr_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_gps_iono_corr_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self); void extract_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self); @@ -1406,7 +1406,7 @@ struct mip_gnss_galileo_iono_corr_data typedef struct mip_gnss_galileo_iono_corr_data mip_gnss_galileo_iono_corr_data; void insert_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self); void extract_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data* self); -bool extract_mip_gnss_galileo_iono_corr_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_gnss_galileo_iono_corr_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self); void extract_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self); diff --git a/src/mip/definitions/data_sensor.c b/src/mip/definitions/data_sensor.c index 9f35292c3..c910d2d05 100644 --- a/src/mip/definitions/data_sensor.c +++ b/src/mip/definitions/data_sensor.c @@ -39,7 +39,7 @@ void extract_mip_sensor_raw_accel_data(microstrain_serializer* serializer, mip_s microstrain_extract_float(serializer, &self->raw_accel[i]); } -bool extract_mip_sensor_raw_accel_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_raw_accel_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_raw_accel_data* self = ptr; @@ -61,7 +61,7 @@ void extract_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, mip_se microstrain_extract_float(serializer, &self->raw_gyro[i]); } -bool extract_mip_sensor_raw_gyro_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_raw_gyro_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_raw_gyro_data* self = ptr; @@ -83,7 +83,7 @@ void extract_mip_sensor_raw_mag_data(microstrain_serializer* serializer, mip_sen microstrain_extract_float(serializer, &self->raw_mag[i]); } -bool extract_mip_sensor_raw_mag_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_raw_mag_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_raw_mag_data* self = ptr; @@ -103,7 +103,7 @@ void extract_mip_sensor_raw_pressure_data(microstrain_serializer* serializer, mi microstrain_extract_float(serializer, &self->raw_pressure); } -bool extract_mip_sensor_raw_pressure_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_raw_pressure_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_raw_pressure_data* self = ptr; @@ -125,7 +125,7 @@ void extract_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, mi microstrain_extract_float(serializer, &self->scaled_accel[i]); } -bool extract_mip_sensor_scaled_accel_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_scaled_accel_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_scaled_accel_data* self = ptr; @@ -147,7 +147,7 @@ void extract_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, mip microstrain_extract_float(serializer, &self->scaled_gyro[i]); } -bool extract_mip_sensor_scaled_gyro_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_scaled_gyro_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_scaled_gyro_data* self = ptr; @@ -169,7 +169,7 @@ void extract_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, mip_ microstrain_extract_float(serializer, &self->scaled_mag[i]); } -bool extract_mip_sensor_scaled_mag_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_scaled_mag_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_scaled_mag_data* self = ptr; @@ -189,7 +189,7 @@ void extract_mip_sensor_scaled_pressure_data(microstrain_serializer* serializer, microstrain_extract_float(serializer, &self->scaled_pressure); } -bool extract_mip_sensor_scaled_pressure_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_scaled_pressure_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_scaled_pressure_data* self = ptr; @@ -211,7 +211,7 @@ void extract_mip_sensor_delta_theta_data(microstrain_serializer* serializer, mip microstrain_extract_float(serializer, &self->delta_theta[i]); } -bool extract_mip_sensor_delta_theta_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_delta_theta_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_delta_theta_data* self = ptr; @@ -233,7 +233,7 @@ void extract_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, microstrain_extract_float(serializer, &self->delta_velocity[i]); } -bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_delta_velocity_data* self = ptr; @@ -255,7 +255,7 @@ void extract_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* ser microstrain_extract_float(serializer, &self->m[i]); } -bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_comp_orientation_matrix_data* self = ptr; @@ -277,7 +277,7 @@ void extract_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, microstrain_extract_float(serializer, &self->q[i]); } -bool extract_mip_sensor_comp_quaternion_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_comp_quaternion_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_comp_quaternion_data* self = ptr; @@ -305,7 +305,7 @@ void extract_mip_sensor_comp_euler_angles_data(microstrain_serializer* serialize microstrain_extract_float(serializer, &self->yaw); } -bool extract_mip_sensor_comp_euler_angles_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_comp_euler_angles_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_comp_euler_angles_data* self = ptr; @@ -327,7 +327,7 @@ void extract_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializ microstrain_extract_float(serializer, &self->m[i]); } -bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_comp_orientation_update_matrix_data* self = ptr; @@ -349,7 +349,7 @@ void extract_mip_sensor_orientation_raw_temp_data(microstrain_serializer* serial microstrain_extract_u16(serializer, &self->raw_temp[i]); } -bool extract_mip_sensor_orientation_raw_temp_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_orientation_raw_temp_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_orientation_raw_temp_data* self = ptr; @@ -369,7 +369,7 @@ void extract_mip_sensor_internal_timestamp_data(microstrain_serializer* serializ microstrain_extract_u32(serializer, &self->counts); } -bool extract_mip_sensor_internal_timestamp_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_internal_timestamp_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_internal_timestamp_data* self = ptr; @@ -393,7 +393,7 @@ void extract_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, m microstrain_extract_u32(serializer, &self->useconds); } -bool extract_mip_sensor_pps_timestamp_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_pps_timestamp_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_pps_timestamp_data* self = ptr; @@ -421,7 +421,7 @@ void extract_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, m extract_mip_sensor_gps_timestamp_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_sensor_gps_timestamp_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_gps_timestamp_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_gps_timestamp_data* self = ptr; @@ -460,7 +460,7 @@ void extract_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, microstrain_extract_float(serializer, &self->mean_temp); } -bool extract_mip_sensor_temperature_abs_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_temperature_abs_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_temperature_abs_data* self = ptr; @@ -482,7 +482,7 @@ void extract_mip_sensor_up_vector_data(microstrain_serializer* serializer, mip_s microstrain_extract_float(serializer, &self->up[i]); } -bool extract_mip_sensor_up_vector_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_up_vector_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_up_vector_data* self = ptr; @@ -504,7 +504,7 @@ void extract_mip_sensor_north_vector_data(microstrain_serializer* serializer, mi microstrain_extract_float(serializer, &self->north[i]); } -bool extract_mip_sensor_north_vector_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_north_vector_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_north_vector_data* self = ptr; @@ -524,7 +524,7 @@ void extract_mip_sensor_overrange_status_data(microstrain_serializer* serializer extract_mip_sensor_overrange_status_data_status(serializer, &self->status); } -bool extract_mip_sensor_overrange_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_overrange_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_overrange_status_data* self = ptr; @@ -563,7 +563,7 @@ void extract_mip_sensor_odometer_data_data(microstrain_serializer* serializer, m microstrain_extract_u16(serializer, &self->valid_flags); } -bool extract_mip_sensor_odometer_data_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_sensor_odometer_data_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_odometer_data_data* self = ptr; diff --git a/src/mip/definitions/data_sensor.h b/src/mip/definitions/data_sensor.h index 9cbfe03e3..af5afdea8 100644 --- a/src/mip/definitions/data_sensor.h +++ b/src/mip/definitions/data_sensor.h @@ -86,7 +86,7 @@ struct mip_sensor_raw_accel_data typedef struct mip_sensor_raw_accel_data mip_sensor_raw_accel_data; void insert_mip_sensor_raw_accel_data(microstrain_serializer* serializer, const mip_sensor_raw_accel_data* self); void extract_mip_sensor_raw_accel_data(microstrain_serializer* serializer, mip_sensor_raw_accel_data* self); -bool extract_mip_sensor_raw_accel_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_raw_accel_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -106,7 +106,7 @@ struct mip_sensor_raw_gyro_data typedef struct mip_sensor_raw_gyro_data mip_sensor_raw_gyro_data; void insert_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, const mip_sensor_raw_gyro_data* self); void extract_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, mip_sensor_raw_gyro_data* self); -bool extract_mip_sensor_raw_gyro_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_raw_gyro_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -126,7 +126,7 @@ struct mip_sensor_raw_mag_data typedef struct mip_sensor_raw_mag_data mip_sensor_raw_mag_data; void insert_mip_sensor_raw_mag_data(microstrain_serializer* serializer, const mip_sensor_raw_mag_data* self); void extract_mip_sensor_raw_mag_data(microstrain_serializer* serializer, mip_sensor_raw_mag_data* self); -bool extract_mip_sensor_raw_mag_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_raw_mag_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -146,7 +146,7 @@ struct mip_sensor_raw_pressure_data typedef struct mip_sensor_raw_pressure_data mip_sensor_raw_pressure_data; void insert_mip_sensor_raw_pressure_data(microstrain_serializer* serializer, const mip_sensor_raw_pressure_data* self); void extract_mip_sensor_raw_pressure_data(microstrain_serializer* serializer, mip_sensor_raw_pressure_data* self); -bool extract_mip_sensor_raw_pressure_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_raw_pressure_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -166,7 +166,7 @@ struct mip_sensor_scaled_accel_data typedef struct mip_sensor_scaled_accel_data mip_sensor_scaled_accel_data; void insert_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, const mip_sensor_scaled_accel_data* self); void extract_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, mip_sensor_scaled_accel_data* self); -bool extract_mip_sensor_scaled_accel_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_scaled_accel_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -186,7 +186,7 @@ struct mip_sensor_scaled_gyro_data typedef struct mip_sensor_scaled_gyro_data mip_sensor_scaled_gyro_data; void insert_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, const mip_sensor_scaled_gyro_data* self); void extract_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, mip_sensor_scaled_gyro_data* self); -bool extract_mip_sensor_scaled_gyro_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_scaled_gyro_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -206,7 +206,7 @@ struct mip_sensor_scaled_mag_data typedef struct mip_sensor_scaled_mag_data mip_sensor_scaled_mag_data; void insert_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, const mip_sensor_scaled_mag_data* self); void extract_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, mip_sensor_scaled_mag_data* self); -bool extract_mip_sensor_scaled_mag_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_scaled_mag_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -225,7 +225,7 @@ struct mip_sensor_scaled_pressure_data typedef struct mip_sensor_scaled_pressure_data mip_sensor_scaled_pressure_data; void insert_mip_sensor_scaled_pressure_data(microstrain_serializer* serializer, const mip_sensor_scaled_pressure_data* self); void extract_mip_sensor_scaled_pressure_data(microstrain_serializer* serializer, mip_sensor_scaled_pressure_data* self); -bool extract_mip_sensor_scaled_pressure_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_scaled_pressure_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -245,7 +245,7 @@ struct mip_sensor_delta_theta_data typedef struct mip_sensor_delta_theta_data mip_sensor_delta_theta_data; void insert_mip_sensor_delta_theta_data(microstrain_serializer* serializer, const mip_sensor_delta_theta_data* self); void extract_mip_sensor_delta_theta_data(microstrain_serializer* serializer, mip_sensor_delta_theta_data* self); -bool extract_mip_sensor_delta_theta_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_delta_theta_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -265,7 +265,7 @@ struct mip_sensor_delta_velocity_data typedef struct mip_sensor_delta_velocity_data mip_sensor_delta_velocity_data; void insert_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, const mip_sensor_delta_velocity_data* self); void extract_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, mip_sensor_delta_velocity_data* self); -bool extract_mip_sensor_delta_velocity_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_delta_velocity_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -294,7 +294,7 @@ struct mip_sensor_comp_orientation_matrix_data typedef struct mip_sensor_comp_orientation_matrix_data mip_sensor_comp_orientation_matrix_data; void insert_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self); void extract_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self); -bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -321,7 +321,7 @@ struct mip_sensor_comp_quaternion_data typedef struct mip_sensor_comp_quaternion_data mip_sensor_comp_quaternion_data; void insert_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, const mip_sensor_comp_quaternion_data* self); void extract_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, mip_sensor_comp_quaternion_data* self); -bool extract_mip_sensor_comp_quaternion_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_comp_quaternion_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -343,7 +343,7 @@ struct mip_sensor_comp_euler_angles_data typedef struct mip_sensor_comp_euler_angles_data mip_sensor_comp_euler_angles_data; void insert_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, const mip_sensor_comp_euler_angles_data* self); void extract_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, mip_sensor_comp_euler_angles_data* self); -bool extract_mip_sensor_comp_euler_angles_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_comp_euler_angles_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -362,7 +362,7 @@ struct mip_sensor_comp_orientation_update_matrix_data typedef struct mip_sensor_comp_orientation_update_matrix_data mip_sensor_comp_orientation_update_matrix_data; void insert_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self); void extract_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self); -bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -381,7 +381,7 @@ struct mip_sensor_orientation_raw_temp_data typedef struct mip_sensor_orientation_raw_temp_data mip_sensor_orientation_raw_temp_data; void insert_mip_sensor_orientation_raw_temp_data(microstrain_serializer* serializer, const mip_sensor_orientation_raw_temp_data* self); void extract_mip_sensor_orientation_raw_temp_data(microstrain_serializer* serializer, mip_sensor_orientation_raw_temp_data* self); -bool extract_mip_sensor_orientation_raw_temp_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_orientation_raw_temp_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -400,7 +400,7 @@ struct mip_sensor_internal_timestamp_data typedef struct mip_sensor_internal_timestamp_data mip_sensor_internal_timestamp_data; void insert_mip_sensor_internal_timestamp_data(microstrain_serializer* serializer, const mip_sensor_internal_timestamp_data* self); void extract_mip_sensor_internal_timestamp_data(microstrain_serializer* serializer, mip_sensor_internal_timestamp_data* self); -bool extract_mip_sensor_internal_timestamp_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_internal_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -420,7 +420,7 @@ struct mip_sensor_pps_timestamp_data typedef struct mip_sensor_pps_timestamp_data mip_sensor_pps_timestamp_data; void insert_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_pps_timestamp_data* self); void extract_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, mip_sensor_pps_timestamp_data* self); -bool extract_mip_sensor_pps_timestamp_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_pps_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -456,7 +456,7 @@ struct mip_sensor_gps_timestamp_data typedef struct mip_sensor_gps_timestamp_data mip_sensor_gps_timestamp_data; void insert_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data* self); void extract_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data* self); -bool extract_mip_sensor_gps_timestamp_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_gps_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self); void extract_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self); @@ -484,7 +484,7 @@ struct mip_sensor_temperature_abs_data typedef struct mip_sensor_temperature_abs_data mip_sensor_temperature_abs_data; void insert_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, const mip_sensor_temperature_abs_data* self); void extract_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, mip_sensor_temperature_abs_data* self); -bool extract_mip_sensor_temperature_abs_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_temperature_abs_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -509,7 +509,7 @@ struct mip_sensor_up_vector_data typedef struct mip_sensor_up_vector_data mip_sensor_up_vector_data; void insert_mip_sensor_up_vector_data(microstrain_serializer* serializer, const mip_sensor_up_vector_data* self); void extract_mip_sensor_up_vector_data(microstrain_serializer* serializer, mip_sensor_up_vector_data* self); -bool extract_mip_sensor_up_vector_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_up_vector_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -531,7 +531,7 @@ struct mip_sensor_north_vector_data typedef struct mip_sensor_north_vector_data mip_sensor_north_vector_data; void insert_mip_sensor_north_vector_data(microstrain_serializer* serializer, const mip_sensor_north_vector_data* self); void extract_mip_sensor_north_vector_data(microstrain_serializer* serializer, mip_sensor_north_vector_data* self); -bool extract_mip_sensor_north_vector_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_north_vector_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -563,7 +563,7 @@ struct mip_sensor_overrange_status_data typedef struct mip_sensor_overrange_status_data mip_sensor_overrange_status_data; void insert_mip_sensor_overrange_status_data(microstrain_serializer* serializer, const mip_sensor_overrange_status_data* self); void extract_mip_sensor_overrange_status_data(microstrain_serializer* serializer, mip_sensor_overrange_status_data* self); -bool extract_mip_sensor_overrange_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_overrange_status_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self); void extract_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self); @@ -586,7 +586,7 @@ struct mip_sensor_odometer_data_data typedef struct mip_sensor_odometer_data_data mip_sensor_odometer_data_data; void insert_mip_sensor_odometer_data_data(microstrain_serializer* serializer, const mip_sensor_odometer_data_data* self); void extract_mip_sensor_odometer_data_data(microstrain_serializer* serializer, mip_sensor_odometer_data_data* self); -bool extract_mip_sensor_odometer_data_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_sensor_odometer_data_data_from_field(const struct mip_field_view* field, void* ptr); ///@} diff --git a/src/mip/definitions/data_shared.c b/src/mip/definitions/data_shared.c index 1171de07a..b01dcdd2d 100644 --- a/src/mip/definitions/data_shared.c +++ b/src/mip/definitions/data_shared.c @@ -37,7 +37,7 @@ void extract_mip_shared_event_source_data(microstrain_serializer* serializer, mi microstrain_extract_u8(serializer, &self->trigger_id); } -bool extract_mip_shared_event_source_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_shared_event_source_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_shared_event_source_data* self = ptr; @@ -57,7 +57,7 @@ void extract_mip_shared_ticks_data(microstrain_serializer* serializer, mip_share microstrain_extract_u32(serializer, &self->ticks); } -bool extract_mip_shared_ticks_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_shared_ticks_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_shared_ticks_data* self = ptr; @@ -77,7 +77,7 @@ void extract_mip_shared_delta_ticks_data(microstrain_serializer* serializer, mip microstrain_extract_u32(serializer, &self->ticks); } -bool extract_mip_shared_delta_ticks_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_shared_delta_ticks_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_shared_delta_ticks_data* self = ptr; @@ -105,7 +105,7 @@ void extract_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, m extract_mip_shared_gps_timestamp_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_shared_gps_timestamp_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_shared_gps_timestamp_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_shared_gps_timestamp_data* self = ptr; @@ -136,7 +136,7 @@ void extract_mip_shared_delta_time_data(microstrain_serializer* serializer, mip_ microstrain_extract_double(serializer, &self->seconds); } -bool extract_mip_shared_delta_time_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_shared_delta_time_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_shared_delta_time_data* self = ptr; @@ -156,7 +156,7 @@ void extract_mip_shared_reference_timestamp_data(microstrain_serializer* seriali microstrain_extract_u64(serializer, &self->nanoseconds); } -bool extract_mip_shared_reference_timestamp_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_shared_reference_timestamp_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_shared_reference_timestamp_data* self = ptr; @@ -176,7 +176,7 @@ void extract_mip_shared_reference_time_delta_data(microstrain_serializer* serial microstrain_extract_u64(serializer, &self->dt_nanos); } -bool extract_mip_shared_reference_time_delta_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_shared_reference_time_delta_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_shared_reference_time_delta_data* self = ptr; @@ -200,7 +200,7 @@ void extract_mip_shared_external_timestamp_data(microstrain_serializer* serializ extract_mip_shared_external_timestamp_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_shared_external_timestamp_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_shared_external_timestamp_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_shared_external_timestamp_data* self = ptr; @@ -235,7 +235,7 @@ void extract_mip_shared_external_time_delta_data(microstrain_serializer* seriali extract_mip_shared_external_time_delta_data_valid_flags(serializer, &self->valid_flags); } -bool extract_mip_shared_external_time_delta_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_shared_external_time_delta_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_shared_external_time_delta_data* self = ptr; diff --git a/src/mip/definitions/data_shared.h b/src/mip/definitions/data_shared.h index a597d80da..70f6ef6d3 100644 --- a/src/mip/definitions/data_shared.h +++ b/src/mip/definitions/data_shared.h @@ -73,7 +73,7 @@ struct mip_shared_event_source_data typedef struct mip_shared_event_source_data mip_shared_event_source_data; void insert_mip_shared_event_source_data(microstrain_serializer* serializer, const mip_shared_event_source_data* self); void extract_mip_shared_event_source_data(microstrain_serializer* serializer, mip_shared_event_source_data* self); -bool extract_mip_shared_event_source_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_shared_event_source_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -95,7 +95,7 @@ struct mip_shared_ticks_data typedef struct mip_shared_ticks_data mip_shared_ticks_data; void insert_mip_shared_ticks_data(microstrain_serializer* serializer, const mip_shared_ticks_data* self); void extract_mip_shared_ticks_data(microstrain_serializer* serializer, mip_shared_ticks_data* self); -bool extract_mip_shared_ticks_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_shared_ticks_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -118,7 +118,7 @@ struct mip_shared_delta_ticks_data typedef struct mip_shared_delta_ticks_data mip_shared_delta_ticks_data; void insert_mip_shared_delta_ticks_data(microstrain_serializer* serializer, const mip_shared_delta_ticks_data* self); void extract_mip_shared_delta_ticks_data(microstrain_serializer* serializer, mip_shared_delta_ticks_data* self); -bool extract_mip_shared_delta_ticks_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_shared_delta_ticks_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -149,7 +149,7 @@ struct mip_shared_gps_timestamp_data typedef struct mip_shared_gps_timestamp_data mip_shared_gps_timestamp_data; void insert_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data* self); void extract_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, mip_shared_gps_timestamp_data* self); -bool extract_mip_shared_gps_timestamp_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_shared_gps_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self); void extract_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self); @@ -180,7 +180,7 @@ struct mip_shared_delta_time_data typedef struct mip_shared_delta_time_data mip_shared_delta_time_data; void insert_mip_shared_delta_time_data(microstrain_serializer* serializer, const mip_shared_delta_time_data* self); void extract_mip_shared_delta_time_data(microstrain_serializer* serializer, mip_shared_delta_time_data* self); -bool extract_mip_shared_delta_time_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_shared_delta_time_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -206,7 +206,7 @@ struct mip_shared_reference_timestamp_data typedef struct mip_shared_reference_timestamp_data mip_shared_reference_timestamp_data; void insert_mip_shared_reference_timestamp_data(microstrain_serializer* serializer, const mip_shared_reference_timestamp_data* self); void extract_mip_shared_reference_timestamp_data(microstrain_serializer* serializer, mip_shared_reference_timestamp_data* self); -bool extract_mip_shared_reference_timestamp_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_shared_reference_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -234,7 +234,7 @@ struct mip_shared_reference_time_delta_data typedef struct mip_shared_reference_time_delta_data mip_shared_reference_time_delta_data; void insert_mip_shared_reference_time_delta_data(microstrain_serializer* serializer, const mip_shared_reference_time_delta_data* self); void extract_mip_shared_reference_time_delta_data(microstrain_serializer* serializer, mip_shared_reference_time_delta_data* self); -bool extract_mip_shared_reference_time_delta_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_shared_reference_time_delta_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -267,7 +267,7 @@ struct mip_shared_external_timestamp_data typedef struct mip_shared_external_timestamp_data mip_shared_external_timestamp_data; void insert_mip_shared_external_timestamp_data(microstrain_serializer* serializer, const mip_shared_external_timestamp_data* self); void extract_mip_shared_external_timestamp_data(microstrain_serializer* serializer, mip_shared_external_timestamp_data* self); -bool extract_mip_shared_external_timestamp_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_shared_external_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self); void extract_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self); @@ -307,7 +307,7 @@ struct mip_shared_external_time_delta_data typedef struct mip_shared_external_time_delta_data mip_shared_external_time_delta_data; void insert_mip_shared_external_time_delta_data(microstrain_serializer* serializer, const mip_shared_external_time_delta_data* self); void extract_mip_shared_external_time_delta_data(microstrain_serializer* serializer, mip_shared_external_time_delta_data* self); -bool extract_mip_shared_external_time_delta_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_shared_external_time_delta_data_from_field(const struct mip_field_view* field, void* ptr); void insert_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self); void extract_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self); diff --git a/src/mip/definitions/data_system.c b/src/mip/definitions/data_system.c index b37350e0a..c77f45ba4 100644 --- a/src/mip/definitions/data_system.c +++ b/src/mip/definitions/data_system.c @@ -39,7 +39,7 @@ void extract_mip_system_built_in_test_data(microstrain_serializer* serializer, m microstrain_extract_u8(serializer, &self->result[i]); } -bool extract_mip_system_built_in_test_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_system_built_in_test_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_system_built_in_test_data* self = ptr; @@ -63,7 +63,7 @@ void extract_mip_system_time_sync_status_data(microstrain_serializer* serializer microstrain_extract_u8(serializer, &self->last_pps_rcvd); } -bool extract_mip_system_time_sync_status_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_system_time_sync_status_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_system_time_sync_status_data* self = ptr; @@ -83,7 +83,7 @@ void extract_mip_system_gpio_state_data(microstrain_serializer* serializer, mip_ microstrain_extract_u8(serializer, &self->states); } -bool extract_mip_system_gpio_state_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_system_gpio_state_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_system_gpio_state_data* self = ptr; @@ -107,7 +107,7 @@ void extract_mip_system_gpio_analog_value_data(microstrain_serializer* serialize microstrain_extract_float(serializer, &self->value); } -bool extract_mip_system_gpio_analog_value_data_from_field(const mip_field* field, void* ptr) +bool extract_mip_system_gpio_analog_value_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_system_gpio_analog_value_data* self = ptr; diff --git a/src/mip/definitions/data_system.h b/src/mip/definitions/data_system.h index c854837bd..2edc33f8e 100644 --- a/src/mip/definitions/data_system.h +++ b/src/mip/definitions/data_system.h @@ -81,7 +81,7 @@ struct mip_system_built_in_test_data typedef struct mip_system_built_in_test_data mip_system_built_in_test_data; void insert_mip_system_built_in_test_data(microstrain_serializer* serializer, const mip_system_built_in_test_data* self); void extract_mip_system_built_in_test_data(microstrain_serializer* serializer, mip_system_built_in_test_data* self); -bool extract_mip_system_built_in_test_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_system_built_in_test_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -101,7 +101,7 @@ struct mip_system_time_sync_status_data typedef struct mip_system_time_sync_status_data mip_system_time_sync_status_data; void insert_mip_system_time_sync_status_data(microstrain_serializer* serializer, const mip_system_time_sync_status_data* self); void extract_mip_system_time_sync_status_data(microstrain_serializer* serializer, mip_system_time_sync_status_data* self); -bool extract_mip_system_time_sync_status_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_system_time_sync_status_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -138,7 +138,7 @@ struct mip_system_gpio_state_data typedef struct mip_system_gpio_state_data mip_system_gpio_state_data; void insert_mip_system_gpio_state_data(microstrain_serializer* serializer, const mip_system_gpio_state_data* self); void extract_mip_system_gpio_state_data(microstrain_serializer* serializer, mip_system_gpio_state_data* self); -bool extract_mip_system_gpio_state_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_system_gpio_state_data_from_field(const struct mip_field_view* field, void* ptr); ///@} @@ -159,7 +159,7 @@ struct mip_system_gpio_analog_value_data typedef struct mip_system_gpio_analog_value_data mip_system_gpio_analog_value_data; void insert_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, const mip_system_gpio_analog_value_data* self); void extract_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, mip_system_gpio_analog_value_data* self); -bool extract_mip_system_gpio_analog_value_data_from_field(const struct mip_field* field, void* ptr); +bool extract_mip_system_gpio_analog_value_data_from_field(const struct mip_field_view* field, void* ptr); ///@} diff --git a/src/mip/mip_cmdqueue.c b/src/mip/mip_cmdqueue.c index e93a0cdab..8f1adcc76 100644 --- a/src/mip/mip_cmdqueue.c +++ b/src/mip/mip_cmdqueue.c @@ -283,7 +283,7 @@ static enum mip_cmd_result process_fields_for_pending_cmd(mip_pending_cmd* pendi if( mip_packet_descriptor_set(packet) == pending->_descriptor_set ) { - mip_field field = {0}; + mip_field_view field = {0}; while( mip_field_next_in_packet(&field, packet) ) { // Not an ack/nack reply field, skip it. @@ -306,7 +306,7 @@ static enum mip_cmd_result process_fields_for_pending_cmd(mip_pending_cmd* pendi // Descriptor matches! uint8_t response_length = 0; - mip_field response_field; + mip_field_view response_field; // If the command was ACK'd, check if response data is expected. if( pending->_response_descriptor != 0x00 && ack_code == MIP_ACK_OK ) diff --git a/src/mip/mip_dispatch.c b/src/mip/mip_dispatch.c index 18b03c995..0d3ba1d26 100644 --- a/src/mip/mip_dispatch.c +++ b/src/mip/mip_dispatch.c @@ -312,7 +312,7 @@ static bool mip_dispatch_is_descriptor_match(uint8_t desc_set, uint8_t field_des ///@param field Valid MIP field. ///@param timestamp Packet parse time. /// -static void mip_dispatcher_call_field_callbacks(mip_dispatcher* self, const mip_field* field, mip_timestamp timestamp) +static void mip_dispatcher_call_field_callbacks(mip_dispatcher* self, const mip_field_view* field, mip_timestamp timestamp) { const uint8_t descriptor_set = mip_field_descriptor_set(field); const uint8_t field_descriptor = mip_field_field_descriptor(field); @@ -352,7 +352,7 @@ void mip_dispatcher_dispatch_packet(mip_dispatcher* self, const mip_packet_view* { mip_dispatcher_call_packet_callbacks(self, packet, timestamp, false); - mip_field field; + mip_field_view field; mip_field_init_empty(&field); while( mip_field_next_in_packet(&field, packet) ) { diff --git a/src/mip/mip_dispatch.h b/src/mip/mip_dispatch.h index 19f526473..37fe6978c 100644 --- a/src/mip/mip_dispatch.h +++ b/src/mip/mip_dispatch.h @@ -45,7 +45,7 @@ typedef void (*mip_dispatch_packet_callback)(void *context, const mip_packet_vie ///@param field The MIP field triggering this callback. ///@param timestamp The approximate parse time of the packet. /// -typedef void (*mip_dispatch_field_callback )(void *context, const mip_field *field, mip_timestamp timestamp); +typedef void (*mip_dispatch_field_callback )(void *context, const mip_field_view *field, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// ///@brief Signature for extraction callbacks. @@ -53,7 +53,7 @@ typedef void (*mip_dispatch_field_callback )(void *context, const mip_field *fie ///@param field A valid mip_field. ///@param ptr A pointer to the destination field structure. /// -typedef bool (*mip_dispatch_extractor)(const mip_field *field, void *ptr); +typedef bool (*mip_dispatch_extractor)(const mip_field_view *field, void *ptr); enum { diff --git a/src/mip/mip_field.c b/src/mip/mip_field.c index c83cd9fe6..95c13bcfa 100644 --- a/src/mip/mip_field.c +++ b/src/mip/mip_field.c @@ -27,7 +27,7 @@ /// ///@returns A %mip_field initialized with the specified values. /// -void mip_field_init(mip_field* field, uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) +void mip_field_init(mip_field_view* field, uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) { assert( payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX ); if( payload_length > MIP_FIELD_PAYLOAD_LENGTH_MAX ) @@ -43,7 +43,7 @@ void mip_field_init(mip_field* field, uint8_t descriptor_set, uint8_t field_desc //////////////////////////////////////////////////////////////////////////////// ///@brief Returns the descriptor set of the packet containing this field._ /// -uint8_t mip_field_descriptor_set(const mip_field* field) +uint8_t mip_field_descriptor_set(const mip_field_view* field) { return field->_descriptor_set; } @@ -51,7 +51,7 @@ uint8_t mip_field_descriptor_set(const mip_field* field) //////////////////////////////////////////////////////////////////////////////// ///@brief Returns the field descriptor. /// -uint8_t mip_field_field_descriptor(const mip_field* field) +uint8_t mip_field_field_descriptor(const mip_field_view* field) { return field->_field_descriptor; } @@ -59,7 +59,7 @@ uint8_t mip_field_field_descriptor(const mip_field* field) //////////////////////////////////////////////////////////////////////////////// ///@brief Returns the length of the payload. /// -uint8_t mip_field_payload_length(const mip_field* field) +uint8_t mip_field_payload_length(const mip_field_view* field) { assert(field->_payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX); @@ -69,7 +69,7 @@ uint8_t mip_field_payload_length(const mip_field* field) //////////////////////////////////////////////////////////////////////////////// ///@brief Returns the payload pointer for the field data. /// -const uint8_t* mip_field_payload(const mip_field* field) +const uint8_t* mip_field_payload(const mip_field_view* field) { return field->_payload; } @@ -77,7 +77,7 @@ const uint8_t* mip_field_payload(const mip_field* field) //////////////////////////////////////////////////////////////////////////////// ///@brief Returns true if the field has a valid field descriptor. /// -bool mip_field_is_valid(const mip_field* field) +bool mip_field_is_valid(const mip_field_view* field) { return field->_field_descriptor != MIP_INVALID_FIELD_DESCRIPTOR; } @@ -92,7 +92,7 @@ bool mip_field_is_valid(const mip_field* field) /// ///@param field /// -void mip_field_init_empty(mip_field* field) +void mip_field_init_empty(mip_field_view* field) { mip_field_init(field, MIP_INVALID_DESCRIPTOR_SET, MIP_INVALID_FIELD_DESCRIPTOR, NULL, 0); } @@ -115,9 +115,9 @@ void mip_field_init_empty(mip_field* field) /// ///@returns a mip_field struct with the field data. /// -mip_field mip_field_from_header_ptr(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set) +mip_field_view mip_field_from_header_ptr(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set) { - mip_field field; + mip_field_view field; // Default invalid values. field._payload = NULL; @@ -163,7 +163,7 @@ mip_field mip_field_from_header_ptr(const uint8_t* header, uint8_t total_length, /// ///@returns A mip_field struct with the first field from the packet. /// -mip_field mip_field_first_from_packet(const mip_packet_view* packet) +mip_field_view mip_field_first_from_packet(const mip_packet_view* packet) { return mip_field_from_header_ptr( mip_packet_payload(packet), mip_packet_payload_length(packet), mip_packet_descriptor_set(packet) ); } @@ -178,7 +178,7 @@ mip_field mip_field_first_from_packet(const mip_packet_view* packet) ///@returns A mip_field struct referencing the next field after the input /// field._ Check mip_field_is_valid() to see if the field exists. /// -mip_field mip_field_next_after(const mip_field* field) +mip_field_view mip_field_next_after(const mip_field_view* field) { // Payload length must be zero if payload is NULL. assert(!(field->_payload == NULL) || (field->_payload_length == 0)); @@ -197,7 +197,7 @@ mip_field mip_field_next_after(const mip_field* field) /// ///@returns true if the field exists and is valid. /// -bool mip_field_next(mip_field* field) +bool mip_field_next(mip_field_view* field) { *field = mip_field_next_after(field); @@ -226,7 +226,7 @@ bool mip_field_next(mip_field* field) /// } ///@endcode /// -bool mip_field_next_in_packet(mip_field* field, const mip_packet_view* packet) +bool mip_field_next_in_packet(mip_field_view* field, const mip_packet_view* packet) { if( field->_descriptor_set != MIP_INVALID_DESCRIPTOR_SET ) *field = mip_field_next_after(field); @@ -294,7 +294,7 @@ void microstrain_serializer_finish_new_field(const microstrain_serializer* seria ///@param serializer ///@param field /// -void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field* field) +void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field_view* field) { microstrain_serializer_init_extraction(serializer, mip_field_payload(field), mip_field_payload_length(field)); } diff --git a/src/mip/mip_field.h b/src/mip/mip_field.h index 1b590c3d9..992b1e705 100644 --- a/src/mip/mip_field.h +++ b/src/mip/mip_field.h @@ -49,17 +49,17 @@ extern "C" { /// considered an internal implementation detail. Avoid accessing them directly /// as they are subject to change in future versions of this software. /// -typedef struct mip_field +typedef struct mip_field_view { const uint8_t* _payload; ///<@private The field payload, excluding the header. uint8_t _payload_length; ///<@private The length of the payload, excluding the header. uint8_t _field_descriptor; ///<@private MIP field descriptor. Field not valid if set to 0x00. uint8_t _descriptor_set; ///<@private MIP descriptor set (from the packet) uint8_t _remaining_length; ///<@private Remaining space after this field. -} mip_field; +} mip_field_view; -void mip_field_init(mip_field* field, uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length); +void mip_field_init(mip_field_view* field, uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length); //////////////////////////////////////////////////////////////////////////////// ///@defgroup FieldAccess Field Accessors [C] @@ -68,12 +68,12 @@ void mip_field_init(mip_field* field, uint8_t descriptor_set, uint8_t field_desc /// ///@{ -uint8_t mip_field_descriptor_set(const mip_field* field); -uint8_t mip_field_field_descriptor(const mip_field* field); -uint8_t mip_field_payload_length(const mip_field* field); -const uint8_t* mip_field_payload(const mip_field* field); +uint8_t mip_field_descriptor_set(const mip_field_view* field); +uint8_t mip_field_field_descriptor(const mip_field_view* field); +uint8_t mip_field_payload_length(const mip_field_view* field); +const uint8_t* mip_field_payload(const mip_field_view* field); -bool mip_field_is_valid(const mip_field* field); +bool mip_field_is_valid(const mip_field_view* field); ///@} //////////////////////////////////////////////////////////////////////////////// @@ -100,15 +100,15 @@ bool mip_field_is_valid(const mip_field* field); /// ///@{ -void mip_field_init_empty(mip_field* field); +void mip_field_init_empty(mip_field_view* field); -mip_field mip_field_from_header_ptr(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set); +mip_field_view mip_field_from_header_ptr(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set); -mip_field mip_field_first_from_packet(const mip_packet_view* packet); -mip_field mip_field_next_after(const mip_field* field); -bool mip_field_next(mip_field* field); +mip_field_view mip_field_first_from_packet(const mip_packet_view* packet); +mip_field_view mip_field_next_after(const mip_field_view* field); +bool mip_field_next(mip_field_view* field); -bool mip_field_next_in_packet(mip_field* field, const mip_packet_view* packet); +bool mip_field_next_in_packet(mip_field_view* field, const mip_packet_view* packet); // bool mip_field_is_at_end(const struct mip_field* field); diff --git a/src/mip/mip_field.hpp b/src/mip/mip_field.hpp index 66c438b96..64aff5de4 100644 --- a/src/mip/mip_field.hpp +++ b/src/mip/mip_field.hpp @@ -18,19 +18,19 @@ namespace mip /// /// This is a thin wrapper around the C mip_field struct. /// -class Field : public C::mip_field +class Field : public C::mip_field_view { public: static constexpr size_t MAX_PAYLOAD_LENGTH = C::MIP_FIELD_PAYLOAD_LENGTH_MAX; /// Construct an empty MIP field. - Field() { C::mip_field::_payload=nullptr; C::mip_field::_payload_length=0; C::mip_field::_field_descriptor=0x00; C::mip_field::_descriptor_set=0x00; C::mip_field::_remaining_length=0; } + Field() { C::mip_field_view::_payload=nullptr; C::mip_field_view::_payload_length=0; C::mip_field_view::_field_descriptor=0x00; C::mip_field_view::_descriptor_set=0x00; C::mip_field_view::_remaining_length=0; } ///@copydoc mip_field_init() Field(uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) { C::mip_field_init(this, descriptor_set, field_descriptor, payload, payload_length); } ///@copydoc mip_field_from_header_ptr() Field(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set) { *this = C::mip_field_from_header_ptr(header, total_length, descriptor_set); } /// Creates a %Field class from the mip_field C struct. - Field(const C::mip_field& other) { std::memcpy(static_cast(this), &other, sizeof(C::mip_field)); } + Field(const C::mip_field_view& other) { std::memcpy(static_cast(this), &other, sizeof(C::mip_field_view)); } // // C function wrappers diff --git a/src/mip/mip_interface.hpp b/src/mip/mip_interface.hpp index ce1e52863..aa85481a1 100644 --- a/src/mip/mip_interface.hpp +++ b/src/mip/mip_interface.hpp @@ -527,7 +527,7 @@ void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t template void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, void* userData) { - auto callback = [](void* context, const C::mip_field* field, Timestamp timestamp) + auto callback = [](void* context, const C::mip_field_view* field, Timestamp timestamp) { Callback(context, Field(*field), timestamp); }; @@ -569,7 +569,7 @@ void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t template void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, Object* object) { - auto callback = [](void* pointer, const C::mip_field* field, Timestamp timestamp) + auto callback = [](void* pointer, const C::mip_field_view* field, Timestamp timestamp) { Object* obj = static_cast(pointer); (obj->*Callback)(Field(*field), timestamp); @@ -624,7 +624,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* use if(descriptorSet == 0xFF) return; - auto callback = [](void* context, const C::mip_field* field, Timestamp timestamp) + auto callback = [](void* context, const C::mip_field_view* field, Timestamp timestamp) { DataField data; @@ -683,7 +683,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* use if(descriptorSet == 0xFF) return; - auto callback = [](void* context, const C::mip_field* field, Timestamp timestamp) + auto callback = [](void* context, const C::mip_field_view* field, Timestamp timestamp) { DataField data; @@ -743,7 +743,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* o if(descriptorSet == 0xFF) return; - auto callback = [](void* pointer, const C::mip_field* field, Timestamp timestamp) + auto callback = [](void* pointer, const C::mip_field_view* field, Timestamp timestamp) { DataField data; @@ -804,7 +804,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* o if(descriptorSet == 0xFF) return; - auto callback = [](void* pointer, const C::mip_field* field, Timestamp timestamp) + auto callback = [](void* pointer, const C::mip_field_view* field, Timestamp timestamp) { DataField data; @@ -822,7 +822,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* o template void Interface::registerExtractor(C::mip_dispatch_handler& handler, DataField* field, uint8_t descriptorSet) { - auto callback = [](void* pointer, const C::mip_field* field, Timestamp timestamp) + auto callback = [](void* pointer, const C::mip_field_view* field, Timestamp timestamp) { Field(*field).extract( *static_cast(pointer) ); }; diff --git a/test/mip/test_mip_fields.c b/test/mip/test_mip_fields.c index a2d729d96..ee0a5f6c1 100644 --- a/test/mip/test_mip_fields.c +++ b/test/mip/test_mip_fields.c @@ -10,7 +10,7 @@ uint8_t packet_buffer[MIP_PACKET_LENGTH_MAX]; struct mip_packet_view packet; -struct mip_field fields[MIP_PACKET_PAYLOAD_LENGTH_MAX / MIP_FIELD_LENGTH_MIN]; +struct mip_field_view fields[MIP_PACKET_PAYLOAD_LENGTH_MAX / MIP_FIELD_LENGTH_MIN]; unsigned int num_fields = 0; @@ -61,7 +61,7 @@ int main(int argc, const char* argv[]) // Now iterate the fields and verify they match. unsigned int scanned_fields = 0; - for(struct mip_field field = mip_field_first_from_packet(&packet); mip_field_is_valid(&field); mip_field_next(&field)) + for(struct mip_field_view field = mip_field_first_from_packet(&packet); mip_field_is_valid(&field); mip_field_next(&field)) { const uint8_t test_field_desc = mip_field_field_descriptor(&field); const uint8_t test_desc_set = mip_field_descriptor_set(&field); From 575ad307995813a44fb91ff55d58cfa486c3b646 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 6 Jun 2024 17:13:58 -0400 Subject: [PATCH 025/147] Fix compilation errors in mip_cmdqueue.hpp and bogus include in mip_all.hpp. --- src/mip/mip_all.hpp | 1 - src/mip/mip_cmdqueue.hpp | 1 + 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mip/mip_all.hpp b/src/mip/mip_all.hpp index 7fe51b488..e1037403b 100644 --- a/src/mip/mip_all.hpp +++ b/src/mip/mip_all.hpp @@ -2,7 +2,6 @@ //MIP Core #include "mip_cmdqueue.hpp" -#include "mip_dispatch.hpp" #include "mip_field.hpp" #include "mip_interface.hpp" #include "mip_packet.hpp" diff --git a/src/mip/mip_cmdqueue.hpp b/src/mip/mip_cmdqueue.hpp index 67c16c06d..daa0e4842 100644 --- a/src/mip/mip_cmdqueue.hpp +++ b/src/mip/mip_cmdqueue.hpp @@ -2,6 +2,7 @@ #include "mip_cmdqueue.h" +#include "mip_result.hpp" #include #include From f106c287536fc43a26f1cfd1cc4f2b027ab41b49 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 6 Jun 2024 17:19:26 -0400 Subject: [PATCH 026/147] Rename Field to FieldView. --- examples/CV7/CV7_example.cpp | 4 ++-- examples/watch_imu.cpp | 4 ++-- src/mip/mip_field.hpp | 12 ++++++------ src/mip/mip_interface.hpp | 22 +++++++++++----------- src/mip/mip_packet.hpp | 8 ++++---- test/mip/test_mip.cpp | 6 +++--- 6 files changed, 28 insertions(+), 28 deletions(-) diff --git a/examples/CV7/CV7_example.cpp b/examples/CV7/CV7_example.cpp index 61d6854f0..bfdeb52cf 100644 --- a/examples/CV7/CV7_example.cpp +++ b/examples/CV7/CV7_example.cpp @@ -66,7 +66,7 @@ int usage(const char* argv0); void exit_gracefully(const char *message); bool should_exit(); -void handleFilterEventSource(void*, const mip::Field& field, mip::Timestamp timestamp); +void handleFilterEventSource(void*, const mip::FieldView& field, mip::Timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// // Main Function @@ -312,7 +312,7 @@ int main(int argc, const char* argv[]) // Filter Event Source Field Handler //////////////////////////////////////////////////////////////////////////////// -void handleFilterEventSource(void*, const mip::Field& field, mip::Timestamp timestamp) +void handleFilterEventSource(void*, const mip::FieldView& field, mip::Timestamp timestamp) { mip::data_shared::EventSource data; diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index 2a196cd2a..41bed2956 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -26,13 +26,13 @@ void handlePacket(void*, const mip::PacketView& packet, mip::Timestamp timestamp printf("\nGot packet with descriptor set 0x%02X:", packet.descriptorSet()); - for(mip::Field field : packet) + for(mip::FieldView field : packet) printf(" %02X", field.fieldDescriptor()); printf("\n"); } -void handleAccel(void*, const mip::Field& field, mip::Timestamp timestamp) +void handleAccel(void*, const mip::FieldView& field, mip::Timestamp timestamp) { mip::data_sensor::ScaledAccel data; diff --git a/src/mip/mip_field.hpp b/src/mip/mip_field.hpp index 64aff5de4..4077545db 100644 --- a/src/mip/mip_field.hpp +++ b/src/mip/mip_field.hpp @@ -18,19 +18,19 @@ namespace mip /// /// This is a thin wrapper around the C mip_field struct. /// -class Field : public C::mip_field_view +class FieldView : public C::mip_field_view { public: static constexpr size_t MAX_PAYLOAD_LENGTH = C::MIP_FIELD_PAYLOAD_LENGTH_MAX; /// Construct an empty MIP field. - Field() { C::mip_field_view::_payload=nullptr; C::mip_field_view::_payload_length=0; C::mip_field_view::_field_descriptor=0x00; C::mip_field_view::_descriptor_set=0x00; C::mip_field_view::_remaining_length=0; } + FieldView() { C::mip_field_view::_payload=nullptr; C::mip_field_view::_payload_length=0; C::mip_field_view::_field_descriptor=0x00; C::mip_field_view::_descriptor_set=0x00; C::mip_field_view::_remaining_length=0; } ///@copydoc mip_field_init() - Field(uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) { C::mip_field_init(this, descriptor_set, field_descriptor, payload, payload_length); } + FieldView(uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) { C::mip_field_init(this, descriptor_set, field_descriptor, payload, payload_length); } ///@copydoc mip_field_from_header_ptr() - Field(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set) { *this = C::mip_field_from_header_ptr(header, total_length, descriptor_set); } + FieldView(const uint8_t* header, uint8_t total_length, uint8_t descriptor_set) { *this = C::mip_field_from_header_ptr(header, total_length, descriptor_set); } /// Creates a %Field class from the mip_field C struct. - Field(const C::mip_field_view& other) { std::memcpy(static_cast(this), &other, sizeof(C::mip_field_view)); } + FieldView(const C::mip_field_view& other) { std::memcpy(static_cast(this), &other, sizeof(C::mip_field_view)); } // // C function wrappers @@ -58,7 +58,7 @@ class Field : public C::mip_field_view bool isValid() const { return C::mip_field_is_valid(this); } ///@copydoc mip_field_next_after - Field nextAfter() const { return C::mip_field_next_after(this); } + FieldView nextAfter() const { return C::mip_field_next_after(this); } ///@copydoc mip_field_next bool next() { return C::mip_field_next(this); } diff --git a/src/mip/mip_interface.hpp b/src/mip/mip_interface.hpp index aa85481a1..453927176 100644 --- a/src/mip/mip_interface.hpp +++ b/src/mip/mip_interface.hpp @@ -175,10 +175,10 @@ class Interface : public C::mip_interface void registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, bool afterFields, Object* object); - template + template void registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, void* userData=nullptr); - template + template void registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, Object* object); @@ -524,12 +524,12 @@ void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t /// ///@endcode /// -template +template void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, void* userData) { auto callback = [](void* context, const C::mip_field_view* field, Timestamp timestamp) { - Callback(context, Field(*field), timestamp); + Callback(context, FieldView(*field), timestamp); }; registerFieldCallback(handler, descriptorSet, fieldDescriptor, callback, userData); @@ -566,13 +566,13 @@ void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t /// }; ///@endcode /// -template +template void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t descriptorSet, uint8_t fieldDescriptor, Object* object) { auto callback = [](void* pointer, const C::mip_field_view* field, Timestamp timestamp) { Object* obj = static_cast(pointer); - (obj->*Callback)(Field(*field), timestamp); + (obj->*Callback)(FieldView(*field), timestamp); }; registerFieldCallback(handler, descriptorSet, fieldDescriptor, callback, object); @@ -628,7 +628,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* use { DataField data; - bool ok = Field(*field).extract(data); + bool ok = FieldView(*field).extract(data); assert(ok); (void)ok; Callback(context, data, timestamp); @@ -687,7 +687,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* use { DataField data; - bool ok = Field(*field).extract(data); + bool ok = FieldView(*field).extract(data); assert(ok); (void)ok; Callback(context, data, mip_field_descriptor_set(field), timestamp); @@ -747,7 +747,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* o { DataField data; - bool ok = Field(*field).extract(data); + bool ok = FieldView(*field).extract(data); assert(ok); (void)ok; Object* obj = static_cast(pointer); @@ -808,7 +808,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* o { DataField data; - bool ok = Field(*field).extract(data); + bool ok = FieldView(*field).extract(data); assert(ok); (void)ok; Object* obj = static_cast(pointer); @@ -824,7 +824,7 @@ void Interface::registerExtractor(C::mip_dispatch_handler& handler, DataField* f { auto callback = [](void* pointer, const C::mip_field_view* field, Timestamp timestamp) { - Field(*field).extract( *static_cast(pointer) ); + FieldView(*field).extract( *static_cast(pointer) ); }; registerFieldCallback(handler, descriptorSet, DataField::FIELD_DESCRIPTOR, callback, field); diff --git a/src/mip/mip_packet.hpp b/src/mip/mip_packet.hpp index 12a42098a..f1cc5af8d 100644 --- a/src/mip/mip_packet.hpp +++ b/src/mip/mip_packet.hpp @@ -144,7 +144,7 @@ class PacketView : public C::mip_packet_view /// ///@returns A Field instance representing the first field (if any). /// - Field firstField() const { return Field(C::mip_field_first_from_packet(this)); } + FieldView firstField() const { return FieldView(C::mip_field_first_from_packet(this)); } ///@brief Adds a field of the given type to the packet. /// @@ -206,7 +206,7 @@ class PacketView : public C::mip_packet_view /// Create an iterator given the first field to iterate in a packet. /// Technically this can be any field, not just the first field. - FieldIterator(const Field& first) : mField(first) {} + FieldIterator(const FieldView& first) : mField(first) {} /// Comparison between any two iterators. /// This works even for iterators over different packets, which will @@ -225,13 +225,13 @@ class PacketView : public C::mip_packet_view bool operator!=(std::nullptr_t) const { return mField.isValid(); } /// Dereference the iterator as a Field instance. - const Field& operator*() const { return mField; } + const FieldView& operator*() const { return mField; } /// Advance to the next field. FieldIterator& operator++() { mField.next(); return *this; } private: - Field mField; + FieldView mField; }; }; diff --git a/test/mip/test_mip.cpp b/test/mip/test_mip.cpp index 4933c0d94..952194aad 100644 --- a/test/mip/test_mip.cpp +++ b/test/mip/test_mip.cpp @@ -14,7 +14,7 @@ using namespace mip::C; uint8_t packetBuffer[PACKET_LENGTH_MAX]; uint8_t parseBuffer[1024]; -Field fields[MIP_PACKET_PAYLOAD_LENGTH_MAX / MIP_FIELD_LENGTH_MIN]; +FieldView fields[MIP_PACKET_PAYLOAD_LENGTH_MAX / MIP_FIELD_LENGTH_MIN]; unsigned int numFields = 0; unsigned int numErrors = 0; @@ -27,7 +27,7 @@ int main(int argc, const char* argv[]) { unsigned int parsedFields = 0; bool error = false; - for(Field field : *parsedPacket) + for(FieldView field : *parsedPacket) { if( field.descriptorSet() != fields[parsedFields].descriptorSet() ) { @@ -94,7 +94,7 @@ int main(int argc, const char* argv[]) for(unsigned int p=0; p Date: Fri, 14 Jun 2024 18:19:10 -0400 Subject: [PATCH 027/147] Move files into c/ and cpp/ subdirectories [WIP]. --- .gitignore | 2 +- CMakeLists.txt | 29 ++++- src/c/microstrain/CMakeLists.txt | 3 + src/{ => c}/microstrain/common/CMakeLists.txt | 19 ++- .../microstrain/common/device_models.c | 0 .../microstrain/common/device_models.h | 0 .../microstrain/common/embedded_time.h | 5 - src/{ => c}/microstrain/common/logging.c | 0 src/{ => c}/microstrain/common/logging.h | 0 src/{ => c}/microstrain/common/platform.h | 8 -- .../microstrain/common/serialization.c | 0 .../microstrain/common/serialization.h | 7 +- src/c/microstrain/connections/CMakeLists.txt | 13 ++ .../connections/serial/CMakeLists.txt | 6 - .../connections/serial/serial_port.c | 0 .../connections/serial/serial_port.h | 0 .../connections/tcp/CMakeLists.txt | 6 - .../microstrain/connections/tcp/tcp_socket.c | 0 .../microstrain/connections/tcp/tcp_socket.h | 0 src/c/mip/CMakeLists.txt | 100 ++++++++++++++ src/{ => c}/mip/definitions/commands_3dm.c | 0 src/{ => c}/mip/definitions/commands_3dm.h | 0 src/{ => c}/mip/definitions/commands_aiding.c | 0 src/{ => c}/mip/definitions/commands_aiding.h | 0 src/{ => c}/mip/definitions/commands_base.c | 0 src/{ => c}/mip/definitions/commands_base.h | 0 src/{ => c}/mip/definitions/commands_filter.c | 0 src/{ => c}/mip/definitions/commands_filter.h | 0 src/{ => c}/mip/definitions/commands_gnss.c | 0 src/{ => c}/mip/definitions/commands_gnss.h | 0 src/{ => c}/mip/definitions/commands_rtk.c | 0 src/{ => c}/mip/definitions/commands_rtk.h | 0 src/{ => c}/mip/definitions/commands_system.c | 0 src/{ => c}/mip/definitions/commands_system.h | 0 src/{ => c}/mip/definitions/common.c | 0 src/{ => c}/mip/definitions/common.h | 1 + src/{ => c}/mip/definitions/data_filter.c | 0 src/{ => c}/mip/definitions/data_filter.h | 0 src/{ => c}/mip/definitions/data_gnss.c | 0 src/{ => c}/mip/definitions/data_gnss.h | 0 src/{ => c}/mip/definitions/data_sensor.c | 0 src/{ => c}/mip/definitions/data_sensor.h | 0 src/{ => c}/mip/definitions/data_shared.c | 0 src/{ => c}/mip/definitions/data_shared.h | 0 src/{ => c}/mip/definitions/data_system.c | 0 src/{ => c}/mip/definitions/data_system.h | 0 src/{ => c}/mip/mip_all.h | 0 src/{ => c}/mip/mip_cmdqueue.c | 0 src/{ => c}/mip/mip_cmdqueue.h | 0 src/{ => c}/mip/mip_descriptors.c | 0 src/{ => c}/mip/mip_descriptors.h | 0 src/{ => c}/mip/mip_dispatch.c | 0 src/{ => c}/mip/mip_dispatch.h | 0 src/{ => c}/mip/mip_field.c | 0 src/{ => c}/mip/mip_field.h | 0 src/{ => c}/mip/mip_interface.c | 0 src/{ => c}/mip/mip_interface.h | 0 src/{ => c}/mip/mip_offsets.h | 0 src/{ => c}/mip/mip_packet.c | 0 src/{ => c}/mip/mip_packet.h | 0 src/{ => c}/mip/mip_parser.c | 0 src/{ => c}/mip/mip_parser.h | 0 src/{ => c}/mip/mip_result.c | 0 src/{ => c}/mip/mip_result.h | 0 src/{ => c}/mip/mip_types.h | 4 +- src/{ => c}/mip/utils/byte_ring.c | 0 src/{ => c}/mip/utils/byte_ring.h | 0 src/{ => cpp}/microstrain/CMakeLists.txt | 0 src/cpp/microstrain/common/CMakeLists.txt | 10 ++ .../microstrain/common/descriptor_id.hpp | 0 src/cpp/microstrain/common/embedded_time.hpp | 12 ++ src/{ => cpp}/microstrain/common/index.hpp | 0 src/cpp/microstrain/common/logging.hpp | 33 +++++ src/cpp/microstrain/common/platform.hpp | 10 ++ .../microstrain/common/serialization.hpp | 0 .../microstrain/connections/CMakeLists.txt | 13 ++ .../microstrain/connections}/connection.hpp | 2 +- .../connections/recording/CMakeLists.txt | 9 ++ .../recording/recording_connection.cpp | 0 .../recording/recording_connection.hpp | 2 +- .../connections/serial/CMakeLists.txt | 9 ++ .../connections/serial/serial_connection.cpp | 2 +- .../connections/serial/serial_connection.hpp | 6 +- .../connections/tcp/CMakeLists.txt | 9 ++ .../connections/tcp/tcp_connection.cpp | 0 .../connections/tcp/tcp_connection.hpp | 4 +- src/cpp/microstrain/extras/CMakeLists.txt | 10 ++ .../microstrain/extras/composite_result.hpp | 0 .../microstrain/extras/scope_helper.cpp | 0 .../microstrain/extras/scope_helper.hpp | 0 src/{ => cpp}/microstrain/extras/version.cpp | 0 src/{ => cpp}/microstrain/extras/version.hpp | 0 src/cpp/mip/CMakeLists.txt | 29 +++++ .../mip/definitions/commands_3dm.cpp | 0 .../mip/definitions/commands_3dm.hpp | 0 .../mip/definitions/commands_aiding.cpp | 0 .../mip/definitions/commands_aiding.hpp | 0 .../mip/definitions/commands_base.cpp | 0 .../mip/definitions/commands_base.hpp | 4 +- .../mip/definitions/commands_filter.cpp | 0 .../mip/definitions/commands_filter.hpp | 2 +- .../mip/definitions/commands_gnss.cpp | 0 .../mip/definitions/commands_gnss.hpp | 0 .../mip/definitions/commands_rtk.cpp | 0 .../mip/definitions/commands_rtk.hpp | 0 .../mip/definitions/commands_system.cpp | 0 .../mip/definitions/commands_system.hpp | 0 src/{ => cpp}/mip/definitions/common.hpp | 0 src/{ => cpp}/mip/definitions/data_filter.cpp | 0 src/{ => cpp}/mip/definitions/data_filter.hpp | 0 src/{ => cpp}/mip/definitions/data_gnss.cpp | 0 src/{ => cpp}/mip/definitions/data_gnss.hpp | 0 src/{ => cpp}/mip/definitions/data_sensor.cpp | 0 src/{ => cpp}/mip/definitions/data_sensor.hpp | 0 src/{ => cpp}/mip/definitions/data_shared.cpp | 0 src/{ => cpp}/mip/definitions/data_shared.hpp | 0 src/{ => cpp}/mip/definitions/data_system.cpp | 0 src/{ => cpp}/mip/definitions/data_system.hpp | 0 src/{ => cpp}/mip/mip.hpp | 0 src/{ => cpp}/mip/mip_all.hpp | 0 src/{ => cpp}/mip/mip_cmdqueue.hpp | 2 +- src/{ => cpp}/mip/mip_descriptors.hpp | 4 +- src/{ => cpp}/mip/mip_field.hpp | 5 +- src/{ => cpp}/mip/mip_interface.cpp | 2 +- src/{ => cpp}/mip/mip_interface.hpp | 5 +- src/{ => cpp}/mip/mip_packet.hpp | 4 +- src/{ => cpp}/mip/mip_parser.hpp | 2 +- src/{ => cpp}/mip/mip_result.hpp | 2 +- src/{ => cpp}/mip/mip_serialization.hpp | 0 src/microstrain/connections/CMakeLists.txt | 17 --- .../connections/recording/CMakeLists.txt | 13 -- src/microstrain/extras/CMakeLists.txt | 5 - src/mip/CMakeLists.txt | 123 ------------------ 133 files changed, 326 insertions(+), 227 deletions(-) create mode 100644 src/c/microstrain/CMakeLists.txt rename src/{ => c}/microstrain/common/CMakeLists.txt (51%) rename src/{ => c}/microstrain/common/device_models.c (100%) rename src/{ => c}/microstrain/common/device_models.h (100%) rename src/{ => c}/microstrain/common/embedded_time.h (91%) rename src/{ => c}/microstrain/common/logging.c (100%) rename src/{ => c}/microstrain/common/logging.h (100%) rename src/{ => c}/microstrain/common/platform.h (72%) rename src/{ => c}/microstrain/common/serialization.c (100%) rename src/{ => c}/microstrain/common/serialization.h (97%) create mode 100644 src/c/microstrain/connections/CMakeLists.txt rename src/{ => c}/microstrain/connections/serial/CMakeLists.txt (51%) rename src/{ => c}/microstrain/connections/serial/serial_port.c (100%) rename src/{ => c}/microstrain/connections/serial/serial_port.h (100%) rename src/{ => c}/microstrain/connections/tcp/CMakeLists.txt (62%) rename src/{ => c}/microstrain/connections/tcp/tcp_socket.c (100%) rename src/{ => c}/microstrain/connections/tcp/tcp_socket.h (100%) create mode 100644 src/c/mip/CMakeLists.txt rename src/{ => c}/mip/definitions/commands_3dm.c (100%) rename src/{ => c}/mip/definitions/commands_3dm.h (100%) rename src/{ => c}/mip/definitions/commands_aiding.c (100%) rename src/{ => c}/mip/definitions/commands_aiding.h (100%) rename src/{ => c}/mip/definitions/commands_base.c (100%) rename src/{ => c}/mip/definitions/commands_base.h (100%) rename src/{ => c}/mip/definitions/commands_filter.c (100%) rename src/{ => c}/mip/definitions/commands_filter.h (100%) rename src/{ => c}/mip/definitions/commands_gnss.c (100%) rename src/{ => c}/mip/definitions/commands_gnss.h (100%) rename src/{ => c}/mip/definitions/commands_rtk.c (100%) rename src/{ => c}/mip/definitions/commands_rtk.h (100%) rename src/{ => c}/mip/definitions/commands_system.c (100%) rename src/{ => c}/mip/definitions/commands_system.h (100%) rename src/{ => c}/mip/definitions/common.c (100%) rename src/{ => c}/mip/definitions/common.h (94%) rename src/{ => c}/mip/definitions/data_filter.c (100%) rename src/{ => c}/mip/definitions/data_filter.h (100%) rename src/{ => c}/mip/definitions/data_gnss.c (100%) rename src/{ => c}/mip/definitions/data_gnss.h (100%) rename src/{ => c}/mip/definitions/data_sensor.c (100%) rename src/{ => c}/mip/definitions/data_sensor.h (100%) rename src/{ => c}/mip/definitions/data_shared.c (100%) rename src/{ => c}/mip/definitions/data_shared.h (100%) rename src/{ => c}/mip/definitions/data_system.c (100%) rename src/{ => c}/mip/definitions/data_system.h (100%) rename src/{ => c}/mip/mip_all.h (100%) rename src/{ => c}/mip/mip_cmdqueue.c (100%) rename src/{ => c}/mip/mip_cmdqueue.h (100%) rename src/{ => c}/mip/mip_descriptors.c (100%) rename src/{ => c}/mip/mip_descriptors.h (100%) rename src/{ => c}/mip/mip_dispatch.c (100%) rename src/{ => c}/mip/mip_dispatch.h (100%) rename src/{ => c}/mip/mip_field.c (100%) rename src/{ => c}/mip/mip_field.h (100%) rename src/{ => c}/mip/mip_interface.c (100%) rename src/{ => c}/mip/mip_interface.h (100%) rename src/{ => c}/mip/mip_offsets.h (100%) rename src/{ => c}/mip/mip_packet.c (100%) rename src/{ => c}/mip/mip_packet.h (100%) rename src/{ => c}/mip/mip_parser.c (100%) rename src/{ => c}/mip/mip_parser.h (100%) rename src/{ => c}/mip/mip_result.c (100%) rename src/{ => c}/mip/mip_result.h (100%) rename src/{ => c}/mip/mip_types.h (89%) rename src/{ => c}/mip/utils/byte_ring.c (100%) rename src/{ => c}/mip/utils/byte_ring.h (100%) rename src/{ => cpp}/microstrain/CMakeLists.txt (100%) create mode 100644 src/cpp/microstrain/common/CMakeLists.txt rename src/{ => cpp}/microstrain/common/descriptor_id.hpp (100%) create mode 100644 src/cpp/microstrain/common/embedded_time.hpp rename src/{ => cpp}/microstrain/common/index.hpp (100%) create mode 100644 src/cpp/microstrain/common/logging.hpp create mode 100644 src/cpp/microstrain/common/platform.hpp rename src/{ => cpp}/microstrain/common/serialization.hpp (100%) create mode 100644 src/cpp/microstrain/connections/CMakeLists.txt rename src/{microstrain/common => cpp/microstrain/connections}/connection.hpp (97%) create mode 100644 src/cpp/microstrain/connections/recording/CMakeLists.txt rename src/{ => cpp}/microstrain/connections/recording/recording_connection.cpp (100%) rename src/{ => cpp}/microstrain/connections/recording/recording_connection.hpp (98%) create mode 100644 src/cpp/microstrain/connections/serial/CMakeLists.txt rename src/{ => cpp}/microstrain/connections/serial/serial_connection.cpp (95%) rename src/{ => cpp}/microstrain/connections/serial/serial_connection.hpp (94%) create mode 100644 src/cpp/microstrain/connections/tcp/CMakeLists.txt rename src/{ => cpp}/microstrain/connections/tcp/tcp_connection.cpp (100%) rename src/{ => cpp}/microstrain/connections/tcp/tcp_connection.hpp (94%) create mode 100644 src/cpp/microstrain/extras/CMakeLists.txt rename src/{ => cpp}/microstrain/extras/composite_result.hpp (100%) rename src/{ => cpp}/microstrain/extras/scope_helper.cpp (100%) rename src/{ => cpp}/microstrain/extras/scope_helper.hpp (100%) rename src/{ => cpp}/microstrain/extras/version.cpp (100%) rename src/{ => cpp}/microstrain/extras/version.hpp (100%) create mode 100644 src/cpp/mip/CMakeLists.txt rename src/{ => cpp}/mip/definitions/commands_3dm.cpp (100%) rename src/{ => cpp}/mip/definitions/commands_3dm.hpp (100%) rename src/{ => cpp}/mip/definitions/commands_aiding.cpp (100%) rename src/{ => cpp}/mip/definitions/commands_aiding.hpp (100%) rename src/{ => cpp}/mip/definitions/commands_base.cpp (100%) rename src/{ => cpp}/mip/definitions/commands_base.hpp (99%) rename src/{ => cpp}/mip/definitions/commands_filter.cpp (100%) rename src/{ => cpp}/mip/definitions/commands_filter.hpp (99%) rename src/{ => cpp}/mip/definitions/commands_gnss.cpp (100%) rename src/{ => cpp}/mip/definitions/commands_gnss.hpp (100%) rename src/{ => cpp}/mip/definitions/commands_rtk.cpp (100%) rename src/{ => cpp}/mip/definitions/commands_rtk.hpp (100%) rename src/{ => cpp}/mip/definitions/commands_system.cpp (100%) rename src/{ => cpp}/mip/definitions/commands_system.hpp (100%) rename src/{ => cpp}/mip/definitions/common.hpp (100%) rename src/{ => cpp}/mip/definitions/data_filter.cpp (100%) rename src/{ => cpp}/mip/definitions/data_filter.hpp (100%) rename src/{ => cpp}/mip/definitions/data_gnss.cpp (100%) rename src/{ => cpp}/mip/definitions/data_gnss.hpp (100%) rename src/{ => cpp}/mip/definitions/data_sensor.cpp (100%) rename src/{ => cpp}/mip/definitions/data_sensor.hpp (100%) rename src/{ => cpp}/mip/definitions/data_shared.cpp (100%) rename src/{ => cpp}/mip/definitions/data_shared.hpp (100%) rename src/{ => cpp}/mip/definitions/data_system.cpp (100%) rename src/{ => cpp}/mip/definitions/data_system.hpp (100%) rename src/{ => cpp}/mip/mip.hpp (100%) rename src/{ => cpp}/mip/mip_all.hpp (100%) rename src/{ => cpp}/mip/mip_cmdqueue.hpp (99%) rename src/{ => cpp}/mip/mip_descriptors.hpp (99%) rename src/{ => cpp}/mip/mip_field.hpp (98%) rename src/{ => cpp}/mip/mip_interface.cpp (97%) rename src/{ => cpp}/mip/mip_interface.hpp (99%) rename src/{ => cpp}/mip/mip_packet.hpp (99%) rename src/{ => cpp}/mip/mip_parser.hpp (99%) rename src/{ => cpp}/mip/mip_result.hpp (99%) rename src/{ => cpp}/mip/mip_serialization.hpp (100%) delete mode 100644 src/microstrain/connections/CMakeLists.txt delete mode 100644 src/microstrain/connections/recording/CMakeLists.txt delete mode 100644 src/microstrain/extras/CMakeLists.txt delete mode 100644 src/mip/CMakeLists.txt diff --git a/.gitignore b/.gitignore index 79868ed81..8dadf5d41 100644 --- a/.gitignore +++ b/.gitignore @@ -5,4 +5,4 @@ int/ .idea/ .vs/ -src/mip/mip_version.h +src/c/mip/mip_version.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 068993802..6add043fc 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,7 +8,7 @@ set(CMAKE_C_STANDARD_REQUIRED ON) project( "MIP SDK" - VERSION "2.0.00" + VERSION "3.0.00" DESCRIPTION "MicroStrain Communications Library for embedded systems" LANGUAGES C CXX ) @@ -68,21 +68,42 @@ endif() # Generate the version header file set(VERSION_IN_FILE "${MIP_CMAKE_DIR}/mip_version.h.in") -set(VERSION_OUT_FILE "${MIP_DIR}/mip_version.h") +set(VERSION_OUT_FILE "${CMAKE_CURRENT_LIST_DIR}/src/c/mip/mip_version.h") configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) # # Build options # +option(MICROSTRAIN_CPP "Enables the C++ API. Turn off to avoid compiling the C++ API." ON) +option(MICROSTRAIN_CPP_C_NAMESPACE "Wraps the C api in a C++ namespace to avoid global namespace pollution (e.g. microstrain::C::microstrain_serial_port)" ${MICROSTRAIN_CPP}) +option(MICROSTRAIN_CMAKE_DEBUG "If set, prints build system debug info such as source files and preprocessor definitions." ON) # TODO: off by default + option(MIP_USE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) option(BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) +# Suppress warnings due to adding files with target_sources. +cmake_policy(SET CMP0076 NEW) + +include_directories(src/c) +if(MICROSTRAIN_CPP) + include_directories(src/cpp) +endif() + +# Add all the C files (required even for C++ API) +add_subdirectory(src/c/microstrain) +add_subdirectory(src/c/mip) + +# Add all the C++ files (if C++ enabled) +if(MICROSTRAIN_CPP) + add_subdirectory(src/cpp/microstrain) + add_subdirectory(src/cpp/mip) -add_subdirectory(src/microstrain) -add_subdirectory(src/mip) + #target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_CPP=1") + target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_CPP_C_NAMESPACE=${MICROSTRAIN_CPP_C_NAMESPACE}") +endif() if(MIP_USE_EXTRAS) diff --git a/src/c/microstrain/CMakeLists.txt b/src/c/microstrain/CMakeLists.txt new file mode 100644 index 000000000..e501bfb7a --- /dev/null +++ b/src/c/microstrain/CMakeLists.txt @@ -0,0 +1,3 @@ + +add_subdirectory(common) +add_subdirectory(connections) diff --git a/src/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt similarity index 51% rename from src/microstrain/common/CMakeLists.txt rename to src/c/microstrain/common/CMakeLists.txt index c90dca4b1..2ca1c88b0 100644 --- a/src/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -1,31 +1,28 @@ -option(MIP_ENABLE_LOGGING "Build with logging functions enabled" ON) +option(MICROSTRAIN_ENABLE_LOGGING "Build with logging functions enabled" ON) set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any call to logging functions with a higher level than this will be compiled out.") +set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") set(SOURCES - serialization.hpp - connection.hpp - descriptor_id.hpp - index.hpp logging.h platform.h serialization.c serialization.h ) - add_library(microstrain_common ${SOURCES}) +target_compile_definitions(microstrain_common PUBLIC "MIP_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") # TODO rename # Logging is a little weird since we need to install the header no matter what -if(MIP_ENABLE_LOGGING) +if(MICROSTRAIN_ENABLE_LOGGING) if(MICROSTRAIN_LOGGING_MAX_LEVEL STREQUAL "") - message(ERROR "MICROSTRAIN_LOGGING_MAX_LEVEL must be MIP_LOG_LEVEL_* or a number") + message(ERROR "MICROSTRAIN_LOGGING_MAX_LEVEL must be MICROSTRAIN_LOG_LEVEL_* or a number") endif() - target_sources(microstrain_common PRIVATE "logging.c") + target_sources(microstrain_common PRIVATE "../../../c/microstrain/common/logging.c") message("MicroStrain logging is enabled. Max level = '${MICROSTRAIN_LOGGING_MAX_LEVEL}'") - target_compile_definitions(microstrain_common PUBLIC "MIP_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") + target_compile_definitions(microstrain_common PUBLIC "MIP_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") # TODO rename endif() -target_include_directories(microstrain_common PUBLIC ${SRC_DIR}) +#target_include_directories(microstrain_common PUBLIC ${CMAKE_CURRENT_LIST_DIR}) diff --git a/src/microstrain/common/device_models.c b/src/c/microstrain/common/device_models.c similarity index 100% rename from src/microstrain/common/device_models.c rename to src/c/microstrain/common/device_models.c diff --git a/src/microstrain/common/device_models.h b/src/c/microstrain/common/device_models.h similarity index 100% rename from src/microstrain/common/device_models.h rename to src/c/microstrain/common/device_models.h diff --git a/src/microstrain/common/embedded_time.h b/src/c/microstrain/common/embedded_time.h similarity index 91% rename from src/microstrain/common/embedded_time.h rename to src/c/microstrain/common/embedded_time.h index b05eda6fa..2078dde63 100644 --- a/src/microstrain/common/embedded_time.h +++ b/src/c/microstrain/common/embedded_time.h @@ -35,11 +35,6 @@ typedef uint32_t microstrain_timestamp; typedef microstrain_embedded_timestamp microstrain_embedded_timeout; #ifdef __cplusplus - } // namespace C - -using EmbeddedTimestamp = C::microstrain_embedded_timestamp; -using EmbeddedTimeout = C::microstrain_embedded_timeout; - } // namespace microstrain #endif // __cplusplus diff --git a/src/microstrain/common/logging.c b/src/c/microstrain/common/logging.c similarity index 100% rename from src/microstrain/common/logging.c rename to src/c/microstrain/common/logging.c diff --git a/src/microstrain/common/logging.h b/src/c/microstrain/common/logging.h similarity index 100% rename from src/microstrain/common/logging.h rename to src/c/microstrain/common/logging.h diff --git a/src/microstrain/common/platform.h b/src/c/microstrain/common/platform.h similarity index 72% rename from src/microstrain/common/platform.h rename to src/c/microstrain/common/platform.h index 89555cce9..e63f60c58 100644 --- a/src/microstrain/common/platform.h +++ b/src/c/microstrain/common/platform.h @@ -12,11 +12,3 @@ #else #define MICROSTRAIN_PLATFORM_OTHER #endif - -#ifdef __cplusplus -#if __cpp_if_constexpr >= 201606L -#define IF_CONSTEXPR if constexpr -#else -#define IF_CONSTEXPR if -#endif -#endif diff --git a/src/microstrain/common/serialization.c b/src/c/microstrain/common/serialization.c similarity index 100% rename from src/microstrain/common/serialization.c rename to src/c/microstrain/common/serialization.c diff --git a/src/microstrain/common/serialization.h b/src/c/microstrain/common/serialization.h similarity index 97% rename from src/microstrain/common/serialization.h rename to src/c/microstrain/common/serialization.h index 576113875..bc99f80e4 100644 --- a/src/microstrain/common/serialization.h +++ b/src/c/microstrain/common/serialization.h @@ -1,10 +1,11 @@ #pragma once -#include "mip/mip_field.h" -#include "mip/mip_packet.h" -#include "mip/mip_types.h" +//#include "mip/mip_field.h" +//#include "mip/mip_packet.h" +//#include "mip/mip_types.h" #include +#include #include //////////////////////////////////////////////////////////////////////////////// diff --git a/src/c/microstrain/connections/CMakeLists.txt b/src/c/microstrain/connections/CMakeLists.txt new file mode 100644 index 000000000..48980b7f9 --- /dev/null +++ b/src/c/microstrain/connections/CMakeLists.txt @@ -0,0 +1,13 @@ + + +option(MIP_USE_SERIAL "Build serial connection support into the library and examples" ON) +option(MIP_USE_TCP "Build TCP connection support into the library and exampels" ON) + + +if(MIP_USE_SERIAL) + add_subdirectory(serial) +endif() + +if(MIP_USE_TCP) + add_subdirectory(tcp) +endif() diff --git a/src/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt similarity index 51% rename from src/microstrain/connections/serial/CMakeLists.txt rename to src/c/microstrain/connections/serial/CMakeLists.txt index acc3ce820..e20fec293 100644 --- a/src/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -1,15 +1,9 @@ - set(SOURCES - serial_connection.cpp - serial_connection.hpp serial_port.h serial_port.c - ../../common/connection.hpp ) add_library(microstrain_serial ${SOURCES}) target_link_libraries(microstrain_serial PUBLIC microstrain_common) - -#target_include_directories(microstrain_serial PRIVATE ${SRC_DIR}) diff --git a/src/microstrain/connections/serial/serial_port.c b/src/c/microstrain/connections/serial/serial_port.c similarity index 100% rename from src/microstrain/connections/serial/serial_port.c rename to src/c/microstrain/connections/serial/serial_port.c diff --git a/src/microstrain/connections/serial/serial_port.h b/src/c/microstrain/connections/serial/serial_port.h similarity index 100% rename from src/microstrain/connections/serial/serial_port.h rename to src/c/microstrain/connections/serial/serial_port.h diff --git a/src/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt similarity index 62% rename from src/microstrain/connections/tcp/CMakeLists.txt rename to src/c/microstrain/connections/tcp/CMakeLists.txt index 7da5a076f..68a23f2d2 100644 --- a/src/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -1,11 +1,7 @@ - set(SOURCES - tcp_connection.cpp - tcp_connection.hpp tcp_socket.h tcp_socket.c - ../../common/connection.hpp ) add_library(microstrain_socket ${SOURCES}) @@ -15,5 +11,3 @@ target_link_libraries(microstrain_socket PUBLIC microstrain_common) if(WIN32) target_link_libraries(microstrain_socket PUBLIC "ws2_32") endif() - -#target_include_directories(microstrain_socket PRIVATE ${SRC_DIR}) diff --git a/src/microstrain/connections/tcp/tcp_socket.c b/src/c/microstrain/connections/tcp/tcp_socket.c similarity index 100% rename from src/microstrain/connections/tcp/tcp_socket.c rename to src/c/microstrain/connections/tcp/tcp_socket.c diff --git a/src/microstrain/connections/tcp/tcp_socket.h b/src/c/microstrain/connections/tcp/tcp_socket.h similarity index 100% rename from src/microstrain/connections/tcp/tcp_socket.h rename to src/c/microstrain/connections/tcp/tcp_socket.h diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt new file mode 100644 index 000000000..03ce316a9 --- /dev/null +++ b/src/c/mip/CMakeLists.txt @@ -0,0 +1,100 @@ + + +option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) + + +set(MIP_SOURCES + "${VERSION_OUT_FILE}" + mip_cmdqueue.c + mip_cmdqueue.h + mip_descriptors.c + mip_descriptors.h + mip_dispatch.c + mip_dispatch.h + mip_field.c + mip_field.h + mip_interface.c + mip_interface.h + mip_offsets.h + mip_packet.c + mip_packet.h + mip_parser.c + mip_parser.h + mip_result.c + mip_result.h + mip_types.h + definitions/common.c + definitions/common.h + mip_all.h + + "utils/byte_ring.c" + "utils/byte_ring.h" +) + +add_library(mip ${MIP_SOURCES}) + + +set(MIPDEFS + commands_3dm + commands_aiding + commands_base + commands_filter + commands_gnss + commands_rtk + commands_system + data_filter + data_gnss + data_sensor + data_shared + data_system +# ${INTDEF_SOURCES} # Todo +) + +set_target_properties(mip PROPERTIES definitions "${MIPDEFS}") + +set(MIPDEF_HEADERS ${MIPDEFS}) +set(MIPDEF_SOURCES ${MIPDEFS}) +list(TRANSFORM MIPDEF_HEADERS APPEND ".h") +list(TRANSFORM MIPDEF_SOURCES APPEND ".c") +list(APPEND MIPDEF_SOURCES ${MIPDEF_HEADERS}) +list(TRANSFORM MIPDEF_SOURCES PREPEND "definitions/") + +if(MICROSTRAIN_CMAKE_DEBUG) + message("C definitions = ${MIPDEF_SOURCES}") +endif() + +target_sources(mip PUBLIC ${MIPDEF_SOURCES}) + +#string(REGEX REPLACE "\.h(;|$)" ".hpp\\1" MIPDEF_HPP_SOURCES "${MIPDEF_SOURCES}") +#string(REGEX REPLACE "\.c(;|$)" ".cpp\\1" MIPDEF_CPP_SOURCES "${MIPDEF_HPP_SOURCES}") +# +#set(ALL_MIP_SOURCES +# ${MIPDEF_SOURCES} +# ${MIPDEF_CPP_SOURCES} +# ${MIP_SOURCES_C} +# ${MIP_SOURCES_CPP} +# ${UTILS_SOURCES} +# ${MIP_CPP_HEADERS} +# ${MIP_INTERFACE_SOURCES} +# ${MIP_EXTRA_SOURCES} +#) +# +#if(MIP_DISABLE_CPP) +# list(FILTER ALL_MIP_SOURCES EXCLUDE REGEX "[c|h]pp$") +#endif() +# + + +if(${MIP_ENABLE_DIAGNOSTICS}) + list(APPEND MIP_DEFINES "MIP_ENABLE_DIAGNOSTICS") +endif() + +if(${MIP_TIMESTAMP_TYPE}) + list(APPEND MIP_DEFINES "MIP_TIMESTAMP_TYPE=${MIP_TIMESTAMP_TYPE}") +endif() + +target_compile_definitions(mip PUBLIC "${MIP_DEFINES}") + +target_link_libraries(mip PUBLIC microstrain_common) + +#target_include_directories(mip INTERFACE ${CMAKE_CURRENT_LIST_DIR}) diff --git a/src/mip/definitions/commands_3dm.c b/src/c/mip/definitions/commands_3dm.c similarity index 100% rename from src/mip/definitions/commands_3dm.c rename to src/c/mip/definitions/commands_3dm.c diff --git a/src/mip/definitions/commands_3dm.h b/src/c/mip/definitions/commands_3dm.h similarity index 100% rename from src/mip/definitions/commands_3dm.h rename to src/c/mip/definitions/commands_3dm.h diff --git a/src/mip/definitions/commands_aiding.c b/src/c/mip/definitions/commands_aiding.c similarity index 100% rename from src/mip/definitions/commands_aiding.c rename to src/c/mip/definitions/commands_aiding.c diff --git a/src/mip/definitions/commands_aiding.h b/src/c/mip/definitions/commands_aiding.h similarity index 100% rename from src/mip/definitions/commands_aiding.h rename to src/c/mip/definitions/commands_aiding.h diff --git a/src/mip/definitions/commands_base.c b/src/c/mip/definitions/commands_base.c similarity index 100% rename from src/mip/definitions/commands_base.c rename to src/c/mip/definitions/commands_base.c diff --git a/src/mip/definitions/commands_base.h b/src/c/mip/definitions/commands_base.h similarity index 100% rename from src/mip/definitions/commands_base.h rename to src/c/mip/definitions/commands_base.h diff --git a/src/mip/definitions/commands_filter.c b/src/c/mip/definitions/commands_filter.c similarity index 100% rename from src/mip/definitions/commands_filter.c rename to src/c/mip/definitions/commands_filter.c diff --git a/src/mip/definitions/commands_filter.h b/src/c/mip/definitions/commands_filter.h similarity index 100% rename from src/mip/definitions/commands_filter.h rename to src/c/mip/definitions/commands_filter.h diff --git a/src/mip/definitions/commands_gnss.c b/src/c/mip/definitions/commands_gnss.c similarity index 100% rename from src/mip/definitions/commands_gnss.c rename to src/c/mip/definitions/commands_gnss.c diff --git a/src/mip/definitions/commands_gnss.h b/src/c/mip/definitions/commands_gnss.h similarity index 100% rename from src/mip/definitions/commands_gnss.h rename to src/c/mip/definitions/commands_gnss.h diff --git a/src/mip/definitions/commands_rtk.c b/src/c/mip/definitions/commands_rtk.c similarity index 100% rename from src/mip/definitions/commands_rtk.c rename to src/c/mip/definitions/commands_rtk.c diff --git a/src/mip/definitions/commands_rtk.h b/src/c/mip/definitions/commands_rtk.h similarity index 100% rename from src/mip/definitions/commands_rtk.h rename to src/c/mip/definitions/commands_rtk.h diff --git a/src/mip/definitions/commands_system.c b/src/c/mip/definitions/commands_system.c similarity index 100% rename from src/mip/definitions/commands_system.c rename to src/c/mip/definitions/commands_system.c diff --git a/src/mip/definitions/commands_system.h b/src/c/mip/definitions/commands_system.h similarity index 100% rename from src/mip/definitions/commands_system.h rename to src/c/mip/definitions/commands_system.h diff --git a/src/mip/definitions/common.c b/src/c/mip/definitions/common.c similarity index 100% rename from src/mip/definitions/common.c rename to src/c/mip/definitions/common.c diff --git a/src/mip/definitions/common.h b/src/c/mip/definitions/common.h similarity index 94% rename from src/mip/definitions/common.h rename to src/c/mip/definitions/common.h index 62e3d58d1..04a7c3e40 100644 --- a/src/mip/definitions/common.h +++ b/src/c/mip/definitions/common.h @@ -1,6 +1,7 @@ #pragma once #include +#include "../mip_field.h" #include #include diff --git a/src/mip/definitions/data_filter.c b/src/c/mip/definitions/data_filter.c similarity index 100% rename from src/mip/definitions/data_filter.c rename to src/c/mip/definitions/data_filter.c diff --git a/src/mip/definitions/data_filter.h b/src/c/mip/definitions/data_filter.h similarity index 100% rename from src/mip/definitions/data_filter.h rename to src/c/mip/definitions/data_filter.h diff --git a/src/mip/definitions/data_gnss.c b/src/c/mip/definitions/data_gnss.c similarity index 100% rename from src/mip/definitions/data_gnss.c rename to src/c/mip/definitions/data_gnss.c diff --git a/src/mip/definitions/data_gnss.h b/src/c/mip/definitions/data_gnss.h similarity index 100% rename from src/mip/definitions/data_gnss.h rename to src/c/mip/definitions/data_gnss.h diff --git a/src/mip/definitions/data_sensor.c b/src/c/mip/definitions/data_sensor.c similarity index 100% rename from src/mip/definitions/data_sensor.c rename to src/c/mip/definitions/data_sensor.c diff --git a/src/mip/definitions/data_sensor.h b/src/c/mip/definitions/data_sensor.h similarity index 100% rename from src/mip/definitions/data_sensor.h rename to src/c/mip/definitions/data_sensor.h diff --git a/src/mip/definitions/data_shared.c b/src/c/mip/definitions/data_shared.c similarity index 100% rename from src/mip/definitions/data_shared.c rename to src/c/mip/definitions/data_shared.c diff --git a/src/mip/definitions/data_shared.h b/src/c/mip/definitions/data_shared.h similarity index 100% rename from src/mip/definitions/data_shared.h rename to src/c/mip/definitions/data_shared.h diff --git a/src/mip/definitions/data_system.c b/src/c/mip/definitions/data_system.c similarity index 100% rename from src/mip/definitions/data_system.c rename to src/c/mip/definitions/data_system.c diff --git a/src/mip/definitions/data_system.h b/src/c/mip/definitions/data_system.h similarity index 100% rename from src/mip/definitions/data_system.h rename to src/c/mip/definitions/data_system.h diff --git a/src/mip/mip_all.h b/src/c/mip/mip_all.h similarity index 100% rename from src/mip/mip_all.h rename to src/c/mip/mip_all.h diff --git a/src/mip/mip_cmdqueue.c b/src/c/mip/mip_cmdqueue.c similarity index 100% rename from src/mip/mip_cmdqueue.c rename to src/c/mip/mip_cmdqueue.c diff --git a/src/mip/mip_cmdqueue.h b/src/c/mip/mip_cmdqueue.h similarity index 100% rename from src/mip/mip_cmdqueue.h rename to src/c/mip/mip_cmdqueue.h diff --git a/src/mip/mip_descriptors.c b/src/c/mip/mip_descriptors.c similarity index 100% rename from src/mip/mip_descriptors.c rename to src/c/mip/mip_descriptors.c diff --git a/src/mip/mip_descriptors.h b/src/c/mip/mip_descriptors.h similarity index 100% rename from src/mip/mip_descriptors.h rename to src/c/mip/mip_descriptors.h diff --git a/src/mip/mip_dispatch.c b/src/c/mip/mip_dispatch.c similarity index 100% rename from src/mip/mip_dispatch.c rename to src/c/mip/mip_dispatch.c diff --git a/src/mip/mip_dispatch.h b/src/c/mip/mip_dispatch.h similarity index 100% rename from src/mip/mip_dispatch.h rename to src/c/mip/mip_dispatch.h diff --git a/src/mip/mip_field.c b/src/c/mip/mip_field.c similarity index 100% rename from src/mip/mip_field.c rename to src/c/mip/mip_field.c diff --git a/src/mip/mip_field.h b/src/c/mip/mip_field.h similarity index 100% rename from src/mip/mip_field.h rename to src/c/mip/mip_field.h diff --git a/src/mip/mip_interface.c b/src/c/mip/mip_interface.c similarity index 100% rename from src/mip/mip_interface.c rename to src/c/mip/mip_interface.c diff --git a/src/mip/mip_interface.h b/src/c/mip/mip_interface.h similarity index 100% rename from src/mip/mip_interface.h rename to src/c/mip/mip_interface.h diff --git a/src/mip/mip_offsets.h b/src/c/mip/mip_offsets.h similarity index 100% rename from src/mip/mip_offsets.h rename to src/c/mip/mip_offsets.h diff --git a/src/mip/mip_packet.c b/src/c/mip/mip_packet.c similarity index 100% rename from src/mip/mip_packet.c rename to src/c/mip/mip_packet.c diff --git a/src/mip/mip_packet.h b/src/c/mip/mip_packet.h similarity index 100% rename from src/mip/mip_packet.h rename to src/c/mip/mip_packet.h diff --git a/src/mip/mip_parser.c b/src/c/mip/mip_parser.c similarity index 100% rename from src/mip/mip_parser.c rename to src/c/mip/mip_parser.c diff --git a/src/mip/mip_parser.h b/src/c/mip/mip_parser.h similarity index 100% rename from src/mip/mip_parser.h rename to src/c/mip/mip_parser.h diff --git a/src/mip/mip_result.c b/src/c/mip/mip_result.c similarity index 100% rename from src/mip/mip_result.c rename to src/c/mip/mip_result.c diff --git a/src/mip/mip_result.h b/src/c/mip/mip_result.h similarity index 100% rename from src/mip/mip_result.h rename to src/c/mip/mip_result.h diff --git a/src/mip/mip_types.h b/src/c/mip/mip_types.h similarity index 89% rename from src/mip/mip_types.h rename to src/c/mip/mip_types.h index 7ccb3e98a..ea6ddb232 100644 --- a/src/mip/mip_types.h +++ b/src/c/mip/mip_types.h @@ -8,6 +8,8 @@ namespace mip { namespace C { extern "C" { +#else +#include // For static_assert in C11 #endif @@ -27,7 +29,7 @@ typedef int mip_remaining_count; /// #ifdef MIP_TIMESTAMP_TYPE typedef MIP_TIMESTAMP_TYPE mip_timestamp; - static_assert( sizeof(mip_timestamp) >= 8 || mip_timestamp(-1) > 0, "MIP_TIMESTAMP_TYPE must be unsigned unless 64 bits."); + static_assert( sizeof(mip_timestamp) >= 8 || (mip_timestamp)(-1) > 0, "MIP_TIMESTAMP_TYPE must be unsigned unless 64 bits."); #else typedef uint64_t mip_timestamp; #endif diff --git a/src/mip/utils/byte_ring.c b/src/c/mip/utils/byte_ring.c similarity index 100% rename from src/mip/utils/byte_ring.c rename to src/c/mip/utils/byte_ring.c diff --git a/src/mip/utils/byte_ring.h b/src/c/mip/utils/byte_ring.h similarity index 100% rename from src/mip/utils/byte_ring.h rename to src/c/mip/utils/byte_ring.h diff --git a/src/microstrain/CMakeLists.txt b/src/cpp/microstrain/CMakeLists.txt similarity index 100% rename from src/microstrain/CMakeLists.txt rename to src/cpp/microstrain/CMakeLists.txt diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt new file mode 100644 index 000000000..a69ab92ae --- /dev/null +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -0,0 +1,10 @@ + +# microstrain_common is defined by the C api. +target_sources(microstrain_common PUBLIC + serialization.hpp + descriptor_id.hpp + index.hpp + embedded_time.hpp + logging.hpp + platform.hpp +) diff --git a/src/microstrain/common/descriptor_id.hpp b/src/cpp/microstrain/common/descriptor_id.hpp similarity index 100% rename from src/microstrain/common/descriptor_id.hpp rename to src/cpp/microstrain/common/descriptor_id.hpp diff --git a/src/cpp/microstrain/common/embedded_time.hpp b/src/cpp/microstrain/common/embedded_time.hpp new file mode 100644 index 000000000..0a77a599e --- /dev/null +++ b/src/cpp/microstrain/common/embedded_time.hpp @@ -0,0 +1,12 @@ +#pragma once + +#include + + +namespace microstrain +{ + +using EmbeddedTimestamp = C::microstrain_embedded_timestamp; +using EmbeddedTimeout = C::microstrain_embedded_timeout; + +} // namespace microstrain diff --git a/src/microstrain/common/index.hpp b/src/cpp/microstrain/common/index.hpp similarity index 100% rename from src/microstrain/common/index.hpp rename to src/cpp/microstrain/common/index.hpp diff --git a/src/cpp/microstrain/common/logging.hpp b/src/cpp/microstrain/common/logging.hpp new file mode 100644 index 000000000..5837f3ab7 --- /dev/null +++ b/src/cpp/microstrain/common/logging.hpp @@ -0,0 +1,33 @@ +#pragma once + +#include + + +namespace microstrain +{ + +enum class LogLevel +{ + OFF = MICROSTRAIN_LOG_LEVEL_OFF, + FATAL = MICROSTRAIN_LOG_LEVEL_FATAL, + ERROR = MICROSTRAIN_LOG_LEVEL_ERROR, + WARN = MICROSTRAIN_LOG_LEVEL_WARN, + INFO = MICROSTRAIN_LOG_LEVEL_INFO, + DEBUG = MICROSTRAIN_LOG_LEVEL_DEBUG, + TRACE = MICROSTRAIN_LOG_LEVEL_TRACE, +}; + +//namespace logging +//{ +// using Callback = ::microstrain_log_callback; +// +// void init(Callback callback, LogLevel max_level, void* user=nullptr); +// +// Callback get_callback() { return ::microstrain_logging_callback(); } +// LogLevel max_level() { return static_cast(::microstrain_logging_level()); } +// void* user_pointer() { return ::microstrain_logging_user_data(); } +// +// //void log(LogLevel level, const char* fmt, ...) { ::microstrain_logging_log(level, fmt, args); } +//} + +} // namespace microstrain diff --git a/src/cpp/microstrain/common/platform.hpp b/src/cpp/microstrain/common/platform.hpp new file mode 100644 index 000000000..32fabb00d --- /dev/null +++ b/src/cpp/microstrain/common/platform.hpp @@ -0,0 +1,10 @@ +#pragma once + +#include + + +#if __cpp_if_constexpr >= 201606L + #define IF_CONSTEXPR if constexpr +#else + #define IF_CONSTEXPR if +#endif diff --git a/src/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp similarity index 100% rename from src/microstrain/common/serialization.hpp rename to src/cpp/microstrain/common/serialization.hpp diff --git a/src/cpp/microstrain/connections/CMakeLists.txt b/src/cpp/microstrain/connections/CMakeLists.txt new file mode 100644 index 000000000..662348b23 --- /dev/null +++ b/src/cpp/microstrain/connections/CMakeLists.txt @@ -0,0 +1,13 @@ + +if(MIP_USE_SERIAL) + add_subdirectory(serial) +endif() + +if(MIP_USE_TCP) + add_subdirectory(tcp) +endif() + +# Don't include recording connection if no connections are enabled. +if(MIP_USE_SERIAL OR MIP_USE_TCP) + add_subdirectory(recording) +endif() diff --git a/src/microstrain/common/connection.hpp b/src/cpp/microstrain/connections/connection.hpp similarity index 97% rename from src/microstrain/common/connection.hpp rename to src/cpp/microstrain/connections/connection.hpp index 5d81c6cf0..e79cd9ef0 100644 --- a/src/microstrain/common/connection.hpp +++ b/src/cpp/microstrain/connections/connection.hpp @@ -1,6 +1,6 @@ #pragma once -#include "microstrain/common/embedded_time.h" +#include #include #include diff --git a/src/cpp/microstrain/connections/recording/CMakeLists.txt b/src/cpp/microstrain/connections/recording/CMakeLists.txt new file mode 100644 index 000000000..7484ebaf6 --- /dev/null +++ b/src/cpp/microstrain/connections/recording/CMakeLists.txt @@ -0,0 +1,9 @@ + + +add_library(microstrain_recording_connection + recording_connection.cpp + recording_connection.hpp + ../connection.hpp +) + +target_link_libraries(microstrain_recording_connection PUBLIC microstrain_common) diff --git a/src/microstrain/connections/recording/recording_connection.cpp b/src/cpp/microstrain/connections/recording/recording_connection.cpp similarity index 100% rename from src/microstrain/connections/recording/recording_connection.cpp rename to src/cpp/microstrain/connections/recording/recording_connection.cpp diff --git a/src/microstrain/connections/recording/recording_connection.hpp b/src/cpp/microstrain/connections/recording/recording_connection.hpp similarity index 98% rename from src/microstrain/connections/recording/recording_connection.hpp rename to src/cpp/microstrain/connections/recording/recording_connection.hpp index c320bb433..ead3a5aa8 100644 --- a/src/microstrain/connections/recording/recording_connection.hpp +++ b/src/cpp/microstrain/connections/recording/recording_connection.hpp @@ -1,6 +1,6 @@ #pragma once -#include +#include "../connection.hpp" #include #include diff --git a/src/cpp/microstrain/connections/serial/CMakeLists.txt b/src/cpp/microstrain/connections/serial/CMakeLists.txt new file mode 100644 index 000000000..f16d5a4c3 --- /dev/null +++ b/src/cpp/microstrain/connections/serial/CMakeLists.txt @@ -0,0 +1,9 @@ + + +target_sources(microstrain_serial + PRIVATE + serial_connection.cpp + PUBLIC + serial_connection.hpp + ../connection.hpp +) diff --git a/src/microstrain/connections/serial/serial_connection.cpp b/src/cpp/microstrain/connections/serial/serial_connection.cpp similarity index 95% rename from src/microstrain/connections/serial/serial_connection.cpp rename to src/cpp/microstrain/connections/serial/serial_connection.cpp index b4c769d6d..baf66caf4 100644 --- a/src/microstrain/connections/serial/serial_connection.cpp +++ b/src/cpp/microstrain/connections/serial/serial_connection.cpp @@ -55,7 +55,7 @@ bool SerialConnection::disconnect() ///@copydoc mip::Connection::recvFromDevice -bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, mip::Timestamp* timestamp) +bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, EmbeddedTimestamp* timestamp) { *timestamp = std::chrono::duration_cast(std::chrono::steady_clock::now().time_since_epoch()).count(); diff --git a/src/microstrain/connections/serial/serial_connection.hpp b/src/cpp/microstrain/connections/serial/serial_connection.hpp similarity index 94% rename from src/microstrain/connections/serial/serial_connection.hpp rename to src/cpp/microstrain/connections/serial/serial_connection.hpp index 5408486dc..42d438c7b 100644 --- a/src/microstrain/connections/serial/serial_connection.hpp +++ b/src/cpp/microstrain/connections/serial/serial_connection.hpp @@ -1,8 +1,8 @@ #pragma once -#include "mip/mip_interface.hpp" -#include -#include "serial_port.h" +#include "../connection.hpp" + +#include #include diff --git a/src/cpp/microstrain/connections/tcp/CMakeLists.txt b/src/cpp/microstrain/connections/tcp/CMakeLists.txt new file mode 100644 index 000000000..0e5df794c --- /dev/null +++ b/src/cpp/microstrain/connections/tcp/CMakeLists.txt @@ -0,0 +1,9 @@ + + +target_sources(microstrain_socket + PRIVATE + tcp_connection.cpp + PUBLIC + tcp_connection.hpp + ../connection.hpp +) diff --git a/src/microstrain/connections/tcp/tcp_connection.cpp b/src/cpp/microstrain/connections/tcp/tcp_connection.cpp similarity index 100% rename from src/microstrain/connections/tcp/tcp_connection.cpp rename to src/cpp/microstrain/connections/tcp/tcp_connection.cpp diff --git a/src/microstrain/connections/tcp/tcp_connection.hpp b/src/cpp/microstrain/connections/tcp/tcp_connection.hpp similarity index 94% rename from src/microstrain/connections/tcp/tcp_connection.hpp rename to src/cpp/microstrain/connections/tcp/tcp_connection.hpp index 76c8fbb7b..52bee90e1 100644 --- a/src/microstrain/connections/tcp/tcp_connection.hpp +++ b/src/cpp/microstrain/connections/tcp/tcp_connection.hpp @@ -1,8 +1,8 @@ #pragma once -#include +#include "../connection.hpp" -#include "tcp_socket.h" +#include #include diff --git a/src/cpp/microstrain/extras/CMakeLists.txt b/src/cpp/microstrain/extras/CMakeLists.txt new file mode 100644 index 000000000..78bde7bcc --- /dev/null +++ b/src/cpp/microstrain/extras/CMakeLists.txt @@ -0,0 +1,10 @@ + +set(SOURCES + composite_result.hpp + scope_helper.cpp + scope_helper.hpp + version.cpp + version.hpp +) + +add_library(microstrain_extras ${SOURCES}) diff --git a/src/microstrain/extras/composite_result.hpp b/src/cpp/microstrain/extras/composite_result.hpp similarity index 100% rename from src/microstrain/extras/composite_result.hpp rename to src/cpp/microstrain/extras/composite_result.hpp diff --git a/src/microstrain/extras/scope_helper.cpp b/src/cpp/microstrain/extras/scope_helper.cpp similarity index 100% rename from src/microstrain/extras/scope_helper.cpp rename to src/cpp/microstrain/extras/scope_helper.cpp diff --git a/src/microstrain/extras/scope_helper.hpp b/src/cpp/microstrain/extras/scope_helper.hpp similarity index 100% rename from src/microstrain/extras/scope_helper.hpp rename to src/cpp/microstrain/extras/scope_helper.hpp diff --git a/src/microstrain/extras/version.cpp b/src/cpp/microstrain/extras/version.cpp similarity index 100% rename from src/microstrain/extras/version.cpp rename to src/cpp/microstrain/extras/version.cpp diff --git a/src/microstrain/extras/version.hpp b/src/cpp/microstrain/extras/version.hpp similarity index 100% rename from src/microstrain/extras/version.hpp rename to src/cpp/microstrain/extras/version.hpp diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt new file mode 100644 index 000000000..e9f7df9de --- /dev/null +++ b/src/cpp/mip/CMakeLists.txt @@ -0,0 +1,29 @@ + +target_sources(mip PUBLIC + mip.hpp + mip_all.hpp + mip_cmdqueue.hpp + mip_descriptors.hpp + mip_field.hpp + mip_interface.hpp + mip_interface.cpp + mip_packet.hpp + mip_parser.hpp + mip_result.hpp + mip_serialization.hpp +) + +get_target_property(MIPDEFS mip definitions) + +set(MIPDEF_HEADERS ${MIPDEFS}) +set(MIPDEF_SOURCES ${MIPDEFS}) +list(TRANSFORM MIPDEF_HEADERS APPEND ".hpp") +list(TRANSFORM MIPDEF_SOURCES APPEND ".cpp") +list(APPEND MIPDEF_SOURCES ${MIPDEF_HEADERS}) +list(TRANSFORM MIPDEF_SOURCES PREPEND "definitions/") + +if(MICROSTRAIN_CMAKE_DEBUG) + message("C++ definitions = ${MIPDEF_SOURCES}") +endif() + +target_sources(mip PUBLIC ${MIP_SOURCES}) diff --git a/src/mip/definitions/commands_3dm.cpp b/src/cpp/mip/definitions/commands_3dm.cpp similarity index 100% rename from src/mip/definitions/commands_3dm.cpp rename to src/cpp/mip/definitions/commands_3dm.cpp diff --git a/src/mip/definitions/commands_3dm.hpp b/src/cpp/mip/definitions/commands_3dm.hpp similarity index 100% rename from src/mip/definitions/commands_3dm.hpp rename to src/cpp/mip/definitions/commands_3dm.hpp diff --git a/src/mip/definitions/commands_aiding.cpp b/src/cpp/mip/definitions/commands_aiding.cpp similarity index 100% rename from src/mip/definitions/commands_aiding.cpp rename to src/cpp/mip/definitions/commands_aiding.cpp diff --git a/src/mip/definitions/commands_aiding.hpp b/src/cpp/mip/definitions/commands_aiding.hpp similarity index 100% rename from src/mip/definitions/commands_aiding.hpp rename to src/cpp/mip/definitions/commands_aiding.hpp diff --git a/src/mip/definitions/commands_base.cpp b/src/cpp/mip/definitions/commands_base.cpp similarity index 100% rename from src/mip/definitions/commands_base.cpp rename to src/cpp/mip/definitions/commands_base.cpp diff --git a/src/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp similarity index 99% rename from src/mip/definitions/commands_base.hpp rename to src/cpp/mip/definitions/commands_base.hpp index 6cfed1a41..22480cc7d 100644 --- a/src/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -1,8 +1,8 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include +#include #include #include diff --git a/src/mip/definitions/commands_filter.cpp b/src/cpp/mip/definitions/commands_filter.cpp similarity index 100% rename from src/mip/definitions/commands_filter.cpp rename to src/cpp/mip/definitions/commands_filter.cpp diff --git a/src/mip/definitions/commands_filter.hpp b/src/cpp/mip/definitions/commands_filter.hpp similarity index 99% rename from src/mip/definitions/commands_filter.hpp rename to src/cpp/mip/definitions/commands_filter.hpp index b3036e0e1..48708d853 100644 --- a/src/mip/definitions/commands_filter.hpp +++ b/src/cpp/mip/definitions/commands_filter.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include #include #include diff --git a/src/mip/definitions/commands_gnss.cpp b/src/cpp/mip/definitions/commands_gnss.cpp similarity index 100% rename from src/mip/definitions/commands_gnss.cpp rename to src/cpp/mip/definitions/commands_gnss.cpp diff --git a/src/mip/definitions/commands_gnss.hpp b/src/cpp/mip/definitions/commands_gnss.hpp similarity index 100% rename from src/mip/definitions/commands_gnss.hpp rename to src/cpp/mip/definitions/commands_gnss.hpp diff --git a/src/mip/definitions/commands_rtk.cpp b/src/cpp/mip/definitions/commands_rtk.cpp similarity index 100% rename from src/mip/definitions/commands_rtk.cpp rename to src/cpp/mip/definitions/commands_rtk.cpp diff --git a/src/mip/definitions/commands_rtk.hpp b/src/cpp/mip/definitions/commands_rtk.hpp similarity index 100% rename from src/mip/definitions/commands_rtk.hpp rename to src/cpp/mip/definitions/commands_rtk.hpp diff --git a/src/mip/definitions/commands_system.cpp b/src/cpp/mip/definitions/commands_system.cpp similarity index 100% rename from src/mip/definitions/commands_system.cpp rename to src/cpp/mip/definitions/commands_system.cpp diff --git a/src/mip/definitions/commands_system.hpp b/src/cpp/mip/definitions/commands_system.hpp similarity index 100% rename from src/mip/definitions/commands_system.hpp rename to src/cpp/mip/definitions/commands_system.hpp diff --git a/src/mip/definitions/common.hpp b/src/cpp/mip/definitions/common.hpp similarity index 100% rename from src/mip/definitions/common.hpp rename to src/cpp/mip/definitions/common.hpp diff --git a/src/mip/definitions/data_filter.cpp b/src/cpp/mip/definitions/data_filter.cpp similarity index 100% rename from src/mip/definitions/data_filter.cpp rename to src/cpp/mip/definitions/data_filter.cpp diff --git a/src/mip/definitions/data_filter.hpp b/src/cpp/mip/definitions/data_filter.hpp similarity index 100% rename from src/mip/definitions/data_filter.hpp rename to src/cpp/mip/definitions/data_filter.hpp diff --git a/src/mip/definitions/data_gnss.cpp b/src/cpp/mip/definitions/data_gnss.cpp similarity index 100% rename from src/mip/definitions/data_gnss.cpp rename to src/cpp/mip/definitions/data_gnss.cpp diff --git a/src/mip/definitions/data_gnss.hpp b/src/cpp/mip/definitions/data_gnss.hpp similarity index 100% rename from src/mip/definitions/data_gnss.hpp rename to src/cpp/mip/definitions/data_gnss.hpp diff --git a/src/mip/definitions/data_sensor.cpp b/src/cpp/mip/definitions/data_sensor.cpp similarity index 100% rename from src/mip/definitions/data_sensor.cpp rename to src/cpp/mip/definitions/data_sensor.cpp diff --git a/src/mip/definitions/data_sensor.hpp b/src/cpp/mip/definitions/data_sensor.hpp similarity index 100% rename from src/mip/definitions/data_sensor.hpp rename to src/cpp/mip/definitions/data_sensor.hpp diff --git a/src/mip/definitions/data_shared.cpp b/src/cpp/mip/definitions/data_shared.cpp similarity index 100% rename from src/mip/definitions/data_shared.cpp rename to src/cpp/mip/definitions/data_shared.cpp diff --git a/src/mip/definitions/data_shared.hpp b/src/cpp/mip/definitions/data_shared.hpp similarity index 100% rename from src/mip/definitions/data_shared.hpp rename to src/cpp/mip/definitions/data_shared.hpp diff --git a/src/mip/definitions/data_system.cpp b/src/cpp/mip/definitions/data_system.cpp similarity index 100% rename from src/mip/definitions/data_system.cpp rename to src/cpp/mip/definitions/data_system.cpp diff --git a/src/mip/definitions/data_system.hpp b/src/cpp/mip/definitions/data_system.hpp similarity index 100% rename from src/mip/definitions/data_system.hpp rename to src/cpp/mip/definitions/data_system.hpp diff --git a/src/mip/mip.hpp b/src/cpp/mip/mip.hpp similarity index 100% rename from src/mip/mip.hpp rename to src/cpp/mip/mip.hpp diff --git a/src/mip/mip_all.hpp b/src/cpp/mip/mip_all.hpp similarity index 100% rename from src/mip/mip_all.hpp rename to src/cpp/mip/mip_all.hpp diff --git a/src/mip/mip_cmdqueue.hpp b/src/cpp/mip/mip_cmdqueue.hpp similarity index 99% rename from src/mip/mip_cmdqueue.hpp rename to src/cpp/mip/mip_cmdqueue.hpp index daa0e4842..47ed7546d 100644 --- a/src/mip/mip_cmdqueue.hpp +++ b/src/cpp/mip/mip_cmdqueue.hpp @@ -1,6 +1,6 @@ #pragma once -#include "mip_cmdqueue.h" +#include #include "mip_result.hpp" diff --git a/src/mip/mip_descriptors.hpp b/src/cpp/mip/mip_descriptors.hpp similarity index 99% rename from src/mip/mip_descriptors.hpp rename to src/cpp/mip/mip_descriptors.hpp index c2fd5ebb3..1695c1da6 100644 --- a/src/mip/mip_descriptors.hpp +++ b/src/cpp/mip/mip_descriptors.hpp @@ -1,11 +1,11 @@ #pragma once -#include "mip_descriptors.h" - #include "mip_result.hpp" #include "microstrain/common/serialization.hpp" +#include + #include #include #include diff --git a/src/mip/mip_field.hpp b/src/cpp/mip/mip_field.hpp similarity index 98% rename from src/mip/mip_field.hpp rename to src/cpp/mip/mip_field.hpp index 4077545db..5f44275c1 100644 --- a/src/mip/mip_field.hpp +++ b/src/cpp/mip/mip_field.hpp @@ -1,9 +1,10 @@ #pragma once -#include "mip_field.h" -#include "mip_offsets.h" #include "mip_descriptors.hpp" +#include +#include + #include diff --git a/src/mip/mip_interface.cpp b/src/cpp/mip/mip_interface.cpp similarity index 97% rename from src/mip/mip_interface.cpp rename to src/cpp/mip/mip_interface.cpp index d5ea8c9c5..02e14e7b8 100644 --- a/src/mip/mip_interface.cpp +++ b/src/cpp/mip/mip_interface.cpp @@ -1,7 +1,7 @@ #include "mip_interface.hpp" -#include +#include namespace mip { diff --git a/src/mip/mip_interface.hpp b/src/cpp/mip/mip_interface.hpp similarity index 99% rename from src/mip/mip_interface.hpp rename to src/cpp/mip/mip_interface.hpp index 453927176..e8e985180 100644 --- a/src/mip/mip_interface.hpp +++ b/src/cpp/mip/mip_interface.hpp @@ -3,9 +3,8 @@ #include "mip_parser.hpp" #include "mip_cmdqueue.hpp" -#include "mip_interface.h" - -#include "mip_descriptors.h" +#include +#include #include #include diff --git a/src/mip/mip_packet.hpp b/src/cpp/mip/mip_packet.hpp similarity index 99% rename from src/mip/mip_packet.hpp rename to src/cpp/mip/mip_packet.hpp index f1cc5af8d..fb4bbd6e7 100644 --- a/src/mip/mip_packet.hpp +++ b/src/cpp/mip/mip_packet.hpp @@ -2,8 +2,8 @@ #include "mip_field.hpp" -#include "mip_packet.h" -#include "mip_offsets.h" +#include +#include #include diff --git a/src/mip/mip_parser.hpp b/src/cpp/mip/mip_parser.hpp similarity index 99% rename from src/mip/mip_parser.hpp rename to src/cpp/mip/mip_parser.hpp index a59efe1f1..f3bb86b1a 100644 --- a/src/mip/mip_parser.hpp +++ b/src/cpp/mip/mip_parser.hpp @@ -2,7 +2,7 @@ #include "mip_packet.hpp" -#include "mip_parser.h" +#include namespace mip diff --git a/src/mip/mip_result.hpp b/src/cpp/mip/mip_result.hpp similarity index 99% rename from src/mip/mip_result.hpp rename to src/cpp/mip/mip_result.hpp index c9ca9d1b3..066b298d2 100644 --- a/src/mip/mip_result.hpp +++ b/src/cpp/mip/mip_result.hpp @@ -1,6 +1,6 @@ #pragma once -#include "mip_result.h" +#include namespace mip diff --git a/src/mip/mip_serialization.hpp b/src/cpp/mip/mip_serialization.hpp similarity index 100% rename from src/mip/mip_serialization.hpp rename to src/cpp/mip/mip_serialization.hpp diff --git a/src/microstrain/connections/CMakeLists.txt b/src/microstrain/connections/CMakeLists.txt deleted file mode 100644 index 2370ed165..000000000 --- a/src/microstrain/connections/CMakeLists.txt +++ /dev/null @@ -1,17 +0,0 @@ - - -option(MIP_USE_SERIAL "Build serial connection support into the library and examples" ON) -option(MIP_USE_TCP "Build TCP connection support into the library and exampels" ON) - -if(MIP_USE_SERIAL) - add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/serial) -endif() - -if(MIP_USE_TCP) - add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/tcp) -endif() - -# Don't include recording connection if no connections are enabled. -if(MIP_USE_SERIAL OR MIP_USE_TCP) - add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/recording) -endif() diff --git a/src/microstrain/connections/recording/CMakeLists.txt b/src/microstrain/connections/recording/CMakeLists.txt deleted file mode 100644 index b1a72eaa2..000000000 --- a/src/microstrain/connections/recording/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ - - -set(SOURCES - recording_connection.cpp - recording_connection.hpp - ../../common/connection.hpp -) - -add_library(microstrain_recording_connection ${SOURCES}) - -target_link_libraries(microstrain_recording_connection PUBLIC microstrain_common) - -#target_include_directories(microstrain_serial PRIVATE ${SRC_DIR}) diff --git a/src/microstrain/extras/CMakeLists.txt b/src/microstrain/extras/CMakeLists.txt deleted file mode 100644 index 7d1509e22..000000000 --- a/src/microstrain/extras/CMakeLists.txt +++ /dev/null @@ -1,5 +0,0 @@ - - -set(SOURCES - composite_result.hpp -) diff --git a/src/mip/CMakeLists.txt b/src/mip/CMakeLists.txt deleted file mode 100644 index 498549bfd..000000000 --- a/src/mip/CMakeLists.txt +++ /dev/null @@ -1,123 +0,0 @@ - - -option(MIP_DISABLE_CPP "Excludes all C++ files from the project." OFF) -option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) - -set(MIP_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") - -# -# Utils -# - -set(UTILS_DIR "${MIP_DIR}/utils") - -set(UTILS_SOURCES - "${UTILS_DIR}/byte_ring.c" - "${UTILS_DIR}/byte_ring.h" -) - -# -# MIP Control -# - -set(MIP_SOURCES_C - "${VERSION_OUT_FILE}" - "${MIP_DIR}/mip_cmdqueue.c" - "${MIP_DIR}/mip_cmdqueue.h" - "${MIP_DIR}/mip_descriptors.c" - "${MIP_DIR}/mip_descriptors.h" - "${MIP_DIR}/mip_dispatch.c" - "${MIP_DIR}/mip_dispatch.h" - "${MIP_DIR}/mip_field.c" - "${MIP_DIR}/mip_field.h" - "${MIP_DIR}/mip_interface.c" - "${MIP_DIR}/mip_interface.h" - "${MIP_DIR}/mip_offsets.h" - "${MIP_DIR}/mip_packet.c" - "${MIP_DIR}/mip_packet.h" - "${MIP_DIR}/mip_parser.c" - "${MIP_DIR}/mip_parser.h" - "${MIP_DIR}/mip_result.c" - "${MIP_DIR}/mip_result.h" - "${MIP_DIR}/mip_types.h" - "${MIP_DIR}/definitions/common.c" - "${MIP_DIR}/definitions/common.h" - "${MIP_DIR}/mip_all.h" -) - -set(MIP_SOURCES_CPP - "mip.hpp" - "mip_all.hpp" - "mip_cmdqueue.hpp" - "mip_descriptors.hpp" - "mip_field.hpp" - "mip_packet.hpp" - "mip_parser.hpp" - "mip_result.hpp" - "mip_interface.cpp" - "mip_interface.hpp" -) - -set(MIPDEF_SOURCES - "${MIP_DIR}/definitions/commands_3dm.c" - "${MIP_DIR}/definitions/commands_3dm.h" - "${MIP_DIR}/definitions/commands_base.c" - "${MIP_DIR}/definitions/commands_base.h" - "${MIP_DIR}/definitions/commands_filter.c" - "${MIP_DIR}/definitions/commands_filter.h" - "${MIP_DIR}/definitions/commands_gnss.c" - "${MIP_DIR}/definitions/commands_gnss.h" - "${MIP_DIR}/definitions/commands_rtk.c" - "${MIP_DIR}/definitions/commands_rtk.h" - "${MIP_DIR}/definitions/commands_aiding.c" - "${MIP_DIR}/definitions/commands_aiding.h" - "${MIP_DIR}/definitions/commands_system.c" - "${MIP_DIR}/definitions/commands_system.h" - "${MIP_DIR}/definitions/data_filter.c" - "${MIP_DIR}/definitions/data_filter.h" - "${MIP_DIR}/definitions/data_gnss.c" - "${MIP_DIR}/definitions/data_gnss.h" - "${MIP_DIR}/definitions/data_sensor.c" - "${MIP_DIR}/definitions/data_sensor.h" - "${MIP_DIR}/definitions/data_shared.c" - "${MIP_DIR}/definitions/data_shared.h" - "${MIP_DIR}/definitions/data_system.c" - "${MIP_DIR}/definitions/data_system.h" - ${INTDEF_SOURCES} -) - -string(REGEX REPLACE "\.h(;|$)" ".hpp\\1" MIPDEF_HPP_SOURCES "${MIPDEF_SOURCES}") -string(REGEX REPLACE "\.c(;|$)" ".cpp\\1" MIPDEF_CPP_SOURCES "${MIPDEF_HPP_SOURCES}") - -set(ALL_MIP_SOURCES - ${MIPDEF_SOURCES} - ${MIPDEF_CPP_SOURCES} - ${MIP_SOURCES_C} - ${MIP_SOURCES_CPP} - ${UTILS_SOURCES} - ${MIP_CPP_HEADERS} - ${MIP_INTERFACE_SOURCES} - ${MIP_EXTRA_SOURCES} -) - -if(MIP_DISABLE_CPP) - list(FILTER ALL_MIP_SOURCES EXCLUDE REGEX "[c|h]pp$") -endif() - -add_library(mip ${ALL_MIP_SOURCES}) - - - -if(${MIP_ENABLE_DIAGNOSTICS}) - list(APPEND MIP_DEFINES "MIP_ENABLE_DIAGNOSTICS") -endif() - -if(${MIP_TIMESTAMP_TYPE}) - list(APPEND MIP_DEFINES "MIP_TIMESTAMP_TYPE=${MIP_TIMESTAMP_TYPE}") -endif() - -target_compile_definitions(mip PUBLIC "${MIP_DEFINES}") - -target_link_libraries(mip PUBLIC microstrain_common) - -#target_include_directories(mip INTERFACE ${CMAKE_CURRENT_LIST_DIR}) From 65f065be5502e7ff0c2dc98d2cfc615eac5ffd91 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:36:42 -0400 Subject: [PATCH 028/147] Fix definition files. --- src/cpp/mip/CMakeLists.txt | 2 +- src/cpp/mip/definitions/commands_3dm.cpp | 2 +- src/cpp/mip/definitions/commands_3dm.hpp | 2 +- src/cpp/mip/definitions/commands_aiding.cpp | 2 +- src/cpp/mip/definitions/commands_aiding.hpp | 2 +- src/cpp/mip/definitions/commands_base.cpp | 2 +- src/cpp/mip/definitions/commands_filter.cpp | 2 +- src/cpp/mip/definitions/commands_gnss.cpp | 2 +- src/cpp/mip/definitions/commands_gnss.hpp | 2 +- src/cpp/mip/definitions/commands_rtk.cpp | 2 +- src/cpp/mip/definitions/commands_rtk.hpp | 2 +- src/cpp/mip/definitions/commands_system.cpp | 2 +- src/cpp/mip/definitions/commands_system.hpp | 2 +- src/cpp/mip/definitions/data_filter.cpp | 2 +- src/cpp/mip/definitions/data_filter.hpp | 2 +- src/cpp/mip/definitions/data_gnss.cpp | 2 +- src/cpp/mip/definitions/data_gnss.hpp | 2 +- src/cpp/mip/definitions/data_sensor.cpp | 2 +- src/cpp/mip/definitions/data_sensor.hpp | 2 +- src/cpp/mip/definitions/data_shared.cpp | 2 +- src/cpp/mip/definitions/data_shared.hpp | 2 +- src/cpp/mip/definitions/data_system.cpp | 2 +- src/cpp/mip/definitions/data_system.hpp | 2 +- 23 files changed, 23 insertions(+), 23 deletions(-) diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index e9f7df9de..9ec2e68b2 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -26,4 +26,4 @@ if(MICROSTRAIN_CMAKE_DEBUG) message("C++ definitions = ${MIPDEF_SOURCES}") endif() -target_sources(mip PUBLIC ${MIP_SOURCES}) +target_sources(mip PUBLIC ${MIPDEF_SOURCES}) diff --git a/src/cpp/mip/definitions/commands_3dm.cpp b/src/cpp/mip/definitions/commands_3dm.cpp index 9ccc8d28c..3a5e883d6 100644 --- a/src/cpp/mip/definitions/commands_3dm.cpp +++ b/src/cpp/mip/definitions/commands_3dm.cpp @@ -2,7 +2,7 @@ #include "commands_3dm.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/commands_3dm.hpp b/src/cpp/mip/definitions/commands_3dm.hpp index c7685fc1c..82c92dd48 100644 --- a/src/cpp/mip/definitions/commands_3dm.hpp +++ b/src/cpp/mip/definitions/commands_3dm.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include diff --git a/src/cpp/mip/definitions/commands_aiding.cpp b/src/cpp/mip/definitions/commands_aiding.cpp index 319abdb5d..6c839f013 100644 --- a/src/cpp/mip/definitions/commands_aiding.cpp +++ b/src/cpp/mip/definitions/commands_aiding.cpp @@ -2,7 +2,7 @@ #include "commands_aiding.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/commands_aiding.hpp b/src/cpp/mip/definitions/commands_aiding.hpp index b8f3cef89..fdb5ca91f 100644 --- a/src/cpp/mip/definitions/commands_aiding.hpp +++ b/src/cpp/mip/definitions/commands_aiding.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include diff --git a/src/cpp/mip/definitions/commands_base.cpp b/src/cpp/mip/definitions/commands_base.cpp index 6f22ae166..8796511d2 100644 --- a/src/cpp/mip/definitions/commands_base.cpp +++ b/src/cpp/mip/definitions/commands_base.cpp @@ -2,7 +2,7 @@ #include "commands_base.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/commands_filter.cpp b/src/cpp/mip/definitions/commands_filter.cpp index 40ed6e902..f823e73ec 100644 --- a/src/cpp/mip/definitions/commands_filter.cpp +++ b/src/cpp/mip/definitions/commands_filter.cpp @@ -2,7 +2,7 @@ #include "commands_filter.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/commands_gnss.cpp b/src/cpp/mip/definitions/commands_gnss.cpp index 39fa58778..6a866fd6c 100644 --- a/src/cpp/mip/definitions/commands_gnss.cpp +++ b/src/cpp/mip/definitions/commands_gnss.cpp @@ -2,7 +2,7 @@ #include "commands_gnss.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/commands_gnss.hpp b/src/cpp/mip/definitions/commands_gnss.hpp index a30014d49..998aa5420 100644 --- a/src/cpp/mip/definitions/commands_gnss.hpp +++ b/src/cpp/mip/definitions/commands_gnss.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include diff --git a/src/cpp/mip/definitions/commands_rtk.cpp b/src/cpp/mip/definitions/commands_rtk.cpp index 147c7f1aa..85287fd75 100644 --- a/src/cpp/mip/definitions/commands_rtk.cpp +++ b/src/cpp/mip/definitions/commands_rtk.cpp @@ -2,7 +2,7 @@ #include "commands_rtk.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/commands_rtk.hpp b/src/cpp/mip/definitions/commands_rtk.hpp index a1b396abb..e28b2fa10 100644 --- a/src/cpp/mip/definitions/commands_rtk.hpp +++ b/src/cpp/mip/definitions/commands_rtk.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include diff --git a/src/cpp/mip/definitions/commands_system.cpp b/src/cpp/mip/definitions/commands_system.cpp index 4b2988671..bbb5756c1 100644 --- a/src/cpp/mip/definitions/commands_system.cpp +++ b/src/cpp/mip/definitions/commands_system.cpp @@ -2,7 +2,7 @@ #include "commands_system.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/commands_system.hpp b/src/cpp/mip/definitions/commands_system.hpp index 5b7eb6f88..f9b296976 100644 --- a/src/cpp/mip/definitions/commands_system.hpp +++ b/src/cpp/mip/definitions/commands_system.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include diff --git a/src/cpp/mip/definitions/data_filter.cpp b/src/cpp/mip/definitions/data_filter.cpp index 92604c13d..c912dddab 100644 --- a/src/cpp/mip/definitions/data_filter.cpp +++ b/src/cpp/mip/definitions/data_filter.cpp @@ -2,7 +2,7 @@ #include "data_filter.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/data_filter.hpp b/src/cpp/mip/definitions/data_filter.hpp index b83b04671..a9290b52c 100644 --- a/src/cpp/mip/definitions/data_filter.hpp +++ b/src/cpp/mip/definitions/data_filter.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include diff --git a/src/cpp/mip/definitions/data_gnss.cpp b/src/cpp/mip/definitions/data_gnss.cpp index 2f89e88b3..0d6c21692 100644 --- a/src/cpp/mip/definitions/data_gnss.cpp +++ b/src/cpp/mip/definitions/data_gnss.cpp @@ -2,7 +2,7 @@ #include "data_gnss.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/data_gnss.hpp b/src/cpp/mip/definitions/data_gnss.hpp index 682a5cbc2..a4aa2b4d2 100644 --- a/src/cpp/mip/definitions/data_gnss.hpp +++ b/src/cpp/mip/definitions/data_gnss.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include diff --git a/src/cpp/mip/definitions/data_sensor.cpp b/src/cpp/mip/definitions/data_sensor.cpp index b6e231669..883c7629d 100644 --- a/src/cpp/mip/definitions/data_sensor.cpp +++ b/src/cpp/mip/definitions/data_sensor.cpp @@ -2,7 +2,7 @@ #include "data_sensor.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/data_sensor.hpp b/src/cpp/mip/definitions/data_sensor.hpp index 2dd9cb7e7..443b6fdff 100644 --- a/src/cpp/mip/definitions/data_sensor.hpp +++ b/src/cpp/mip/definitions/data_sensor.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include diff --git a/src/cpp/mip/definitions/data_shared.cpp b/src/cpp/mip/definitions/data_shared.cpp index 8b6097091..7872b60ab 100644 --- a/src/cpp/mip/definitions/data_shared.cpp +++ b/src/cpp/mip/definitions/data_shared.cpp @@ -2,7 +2,7 @@ #include "data_shared.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/data_shared.hpp b/src/cpp/mip/definitions/data_shared.hpp index 57455f544..42193fd55 100644 --- a/src/cpp/mip/definitions/data_shared.hpp +++ b/src/cpp/mip/definitions/data_shared.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include diff --git a/src/cpp/mip/definitions/data_system.cpp b/src/cpp/mip/definitions/data_system.cpp index 08abd531d..a6c339eba 100644 --- a/src/cpp/mip/definitions/data_system.cpp +++ b/src/cpp/mip/definitions/data_system.cpp @@ -2,7 +2,7 @@ #include "data_system.hpp" #include "microstrain/common/serialization.hpp" -#include "../mip_interface.h" +#include "../mip_interface.hpp" #include diff --git a/src/cpp/mip/definitions/data_system.hpp b/src/cpp/mip/definitions/data_system.hpp index 5bb910dde..b2c1db326 100644 --- a/src/cpp/mip/definitions/data_system.hpp +++ b/src/cpp/mip/definitions/data_system.hpp @@ -2,7 +2,7 @@ #include "common.hpp" #include "mip/mip_descriptors.hpp" -#include "../mip_result.h" +#include "../mip_result.hpp" #include #include From e86576e419e560f52aa336b59c8b5887b021b113 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 20 Jun 2024 18:00:23 -0400 Subject: [PATCH 029/147] WIP implementing metadata + serialization. --- src/cpp/microstrain/common/serialization.hpp | 23 ++++ src/cpp/mip/definitions/commands_base.hpp | 25 +++- src/cpp/mip/mip_metadata.hpp | 130 +++++++++++++++++++ src/cpp/mip/mip_serialization.hpp | 20 --- 4 files changed, 177 insertions(+), 21 deletions(-) create mode 100644 src/cpp/mip/mip_metadata.hpp diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index 78c3adb74..b3e9bf5fe 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -189,6 +189,19 @@ typename std::enable_if::value, size_t>::type return sizeof(BaseType); } +// std::tuple +template +size_t insert(Serializer& serializer, const std::tuple& values) +{ + auto lambda = [&serializer](const auto&... args) { + return insert(serializer, args...); + }; + + return std::apply(lambda, values); +} + + +// Multiple values at once #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type @@ -263,6 +276,16 @@ typename std::enable_if::value, size_t>::type return sizeof(BaseType); } +// std::tuple of references +template +size_t extract(Serializer& serializer, const std::tuple...>& values) +{ + auto lambda = [&serializer](auto&... args) { + return extract(serializer, args...); + }; + + return std::apply(lambda, values); +} // // Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. // template // typename std::enable_if::value, size_t>::type diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index 22480cc7d..dcda89563 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -3,6 +3,7 @@ #include "common.hpp" #include #include +#include #include #include @@ -210,7 +211,7 @@ struct Ping static constexpr const bool HAS_FUNCTION_SELECTOR = false; static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - + auto as_tuple() const { return std::make_tuple(); @@ -220,6 +221,12 @@ struct Ping { return std::make_tuple(); } + + static constexpr inline ParameterInfo PARAMETERS[] = {}; + + auto asTuple() const { return as_tuple(); } + auto asTuple() { return as_tuple(); } + typedef void Response; }; void insert(::microstrain::Serializer& serializer, const Ping& self); @@ -260,6 +267,11 @@ struct SetIdle { return std::make_tuple(); } + static constexpr inline ParameterInfo PARAMETERS[] = {}; + + auto asTuple() const { return as_tuple(); } + auto asTuple() { return as_tuple(); } + typedef void Response; }; void insert(::microstrain::Serializer& serializer, const SetIdle& self); @@ -297,6 +309,12 @@ struct GetDeviceInfo { return std::make_tuple(); } + + static constexpr inline ParameterInfo PARAMETERS[] = {}; + + auto asTuple() const { return as_tuple(); } + auto asTuple() { return as_tuple(); } + struct Response { static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; @@ -357,6 +375,11 @@ struct GetDeviceDescriptors { return std::make_tuple(); } + static constexpr inline ParameterInfo PARAMETERS[] = {}; + + auto asTuple() const { return as_tuple(); } + auto asTuple() { return as_tuple(); } + struct Response { static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; diff --git a/src/cpp/mip/mip_metadata.hpp b/src/cpp/mip/mip_metadata.hpp new file mode 100644 index 000000000..be119a506 --- /dev/null +++ b/src/cpp/mip/mip_metadata.hpp @@ -0,0 +1,130 @@ +#pragma once + +#include + +#include "mip_descriptors.hpp" + +namespace mip +{ + + +struct FuncBits +{ + constexpr FuncBits() = default; + constexpr FuncBits(bool w, bool r, bool s, bool l, bool d) : bits(0x00) { write(w); read(r); save(s); load(l); reset(d); } + + constexpr bool any() const { return bits > 0; } + + constexpr bool write() const { return bits & 0b00000001; } + constexpr bool read() const { return bits & 0b00000010; } + constexpr bool save() const { return bits & 0b00000100; } + constexpr bool load() const { return bits & 0b00001000; } + constexpr bool reset() const { return bits & 0b00010000; } + + constexpr FuncBits& write(bool w) { bits = (bits & 0b11111110) | (uint8_t(w)<<0); return *this; } + constexpr FuncBits& read (bool r) { bits = (bits & 0b11111101) | (uint8_t(r)<<0); return *this; } + constexpr FuncBits& save (bool s) { bits = (bits & 0b11111011) | (uint8_t(s)<<0); return *this; } + constexpr FuncBits& load (bool l) { bits = (bits & 0b11110111) | (uint8_t(l)<<0); return *this; } + constexpr FuncBits& reset(bool d) { bits = (bits & 0b11101111) | (uint8_t(d)<<0); return *this; } + + constexpr bool has(mip::FunctionSelector function) const { return (bits >> (static_cast(function) - static_cast(mip::FunctionSelector::WRITE))) & 1; } + + uint8_t bits = 0x00; +}; + + +struct ParameterInfo +{ + enum class Type + { + NONE = 0, + BOOL, + U8, + S8, + U16, + S16, + U32, + S32, + U64, + S64, + FLOAT, + DOUBLE, + ENUM, + BITS, + STRUCT, + UNION, + }; + + Type type = Type::NONE; + const char* name = nullptr; + const char* docs = nullptr; + uint8_t offset = 0; + FuncBits functions; + uint8_t count = 1; + uint8_t counter_idx = 0xFF; + uint8_t union_index = 0xFF; + uint16_t union_value = 0; +}; + +struct FieldStruct +{ + //static_assert(std::is_base_of, T>::value, "T must inherit from FieldStruct"); + +private: + // No direct instantiation or destruction, + // this class must be inherited. + FieldStruct() = default; + ~FieldStruct() = default; +}; + +template +using isField = std::is_base_of; + + +struct Example : public FieldStruct +{ + static constexpr inline ParameterInfo PARAMETERS[] = { + { + /*.type = */ ParameterInfo::Type::BOOL, + /*.name = */ "Enable", + /*.docs = */ "Enables the thing", + /*.offset = */ 0, + /*.functions = */ {true, false, false, false, false}, + }, + { + /*.type = */ ParameterInfo::Type::U8, + /*.name = */ "Count", + /*.docs = */ "Number of things", + /*.offset = */ 1, + /*.functions = */ {true, true, false, false, false}, + } + }; + + bool enable = false; + uint8_t count = 0; + + auto asTuple() { return std::make_tuple(std::ref(enable), std::ref(count)); } + auto asTuple() const { return std::make_tuple(enable, count); } +}; + + + +} // namespace mip + +#include + +// These functions must be in the microstrain namespace in order to be seen as overloads. +namespace microstrain +{ + +template +std::enable_if::value, size_t>::type +/*size_t*/ insert(microstrain::Serializer& serializer, const T& field) +{ + //static_assert(std::is_base_of, T>::value, "T doesn't derive from FieldStruct"); + + return insert(serializer, static_cast(field).asTuple()); +} + + +} // namespace microstrain diff --git a/src/cpp/mip/mip_serialization.hpp b/src/cpp/mip/mip_serialization.hpp index a7f45c6eb..61f6e5be3 100644 --- a/src/cpp/mip/mip_serialization.hpp +++ b/src/cpp/mip/mip_serialization.hpp @@ -68,23 +68,3 @@ struct UnionConditionalParameter : Parameter //} } // namespace mip - - -// These functions must be in the microstrain namespace in order to be seen as overloads. -namespace microstrain -{ - -// Generic class types - assume class has a `size_t serialize(Buffer& buffer) const` function. -template -typename std::enable_if::value, size_t>::type // todo: only MIP structs/fields -/*size_t*/ insert(microstrain::Serializer& serializer, const T& value) -{ - //return value.serialize(buffer); - auto values = value.as_tuple(); - - return std::apply([](auto... args){ - return mip::serialize_parameters(args...); - }, values); -} - -} // namespace microstrain From b036bc1ff0d44757001133a78a5320f02d7120e3 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 21 Jun 2024 12:26:22 -0400 Subject: [PATCH 030/147] Fix mip::FieldView::extract. --- CMakeLists.txt | 2 +- src/cpp/microstrain/common/serialization.hpp | 17 +++ src/cpp/mip/definitions/commands_base.hpp | 36 ++++-- src/cpp/mip/mip_field.hpp | 3 +- src/cpp/mip/mip_metadata.hpp | 26 +---- src/cpp/mip/mip_serialization.hpp | 111 ++++++++++++------- 6 files changed, 124 insertions(+), 71 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6add043fc..f365d75f2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -68,7 +68,7 @@ endif() # Generate the version header file set(VERSION_IN_FILE "${MIP_CMAKE_DIR}/mip_version.h.in") -set(VERSION_OUT_FILE "${CMAKE_CURRENT_LIST_DIR}/src/c/mip/mip_version.h") +set(VERSION_OUT_FILE "${SRC_DIR}/c/mip/mip_version.h") configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) # diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index b3e9bf5fe..513ade514 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -200,6 +200,14 @@ size_t insert(Serializer& serializer, const std::tuple& values) return std::apply(lambda, values); } +// Raw buffer +template +bool insert(const T& value, uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=true) +{ + Serializer serializer(buffer, buffer_length, offset); + serializer.insert(value); + return exact_size ? serializer.noRemaining() : serializer.isOk(); +} // Multiple values at once #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L @@ -294,6 +302,15 @@ size_t extract(Serializer& serializer, const std::tuple +bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=true) +{ + Serializer serializer(buffer, buffer_length, offset); + extract(serializer, value); + return exact_size ? serializer.noRemaining() : serializer.isOk(); +} + #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index dcda89563..2cdc7594e 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -222,7 +222,7 @@ struct Ping return std::make_tuple(); } - static constexpr inline ParameterInfo PARAMETERS[] = {}; + static constexpr inline std::initializer_list PARAMETERS = {}; auto asTuple() const { return as_tuple(); } auto asTuple() { return as_tuple(); } @@ -267,7 +267,7 @@ struct SetIdle { return std::make_tuple(); } - static constexpr inline ParameterInfo PARAMETERS[] = {}; + static constexpr inline std::initializer_list PARAMETERS = {}; auto asTuple() const { return as_tuple(); } auto asTuple() { return as_tuple(); } @@ -310,7 +310,7 @@ struct GetDeviceInfo return std::make_tuple(); } - static constexpr inline ParameterInfo PARAMETERS[] = {}; + static constexpr inline std::initializer_list PARAMETERS = {}; auto asTuple() const { return as_tuple(); } auto asTuple() { return as_tuple(); } @@ -375,7 +375,7 @@ struct GetDeviceDescriptors { return std::make_tuple(); } - static constexpr inline ParameterInfo PARAMETERS[] = {}; + static constexpr inline std::initializer_list PARAMETERS = {}; auto asTuple() const { return as_tuple(); } auto asTuple() { return as_tuple(); } @@ -670,7 +670,26 @@ struct CommSpeed static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; static constexpr const uint32_t ECHOED_PARAMS = 0x0001; static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - + + static constexpr inline std::initializer_list PARAMETERS = { + { + ParameterInfo::Type::U8, + "port", + "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports.", + 1, + {true, true, true, true, true}, + 1, + }, + { + ParameterInfo::Type::U32, + "baud", + "Port baud rate. Must be a supported rate.", + 2, + {true,false,false,false,false}, + 1, + }, + }; + auto as_tuple() const { return std::make_tuple(port,baud); @@ -680,7 +699,7 @@ struct CommSpeed { return std::make_tuple(std::ref(port),std::ref(baud)); } - + static CommSpeed create_sld_all(::mip::FunctionSelector function) { CommSpeed cmd; @@ -688,7 +707,10 @@ struct CommSpeed cmd.port = 0; return cmd; } - + + auto asTuple() const { return as_tuple(); } + auto asTuple() { return as_tuple(); } + struct Response { static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; diff --git a/src/cpp/mip/mip_field.hpp b/src/cpp/mip/mip_field.hpp index 5f44275c1..948372a6c 100644 --- a/src/cpp/mip/mip_field.hpp +++ b/src/cpp/mip/mip_field.hpp @@ -1,6 +1,7 @@ #pragma once #include "mip_descriptors.hpp" +#include "mip_serialization.hpp" #include #include @@ -79,7 +80,7 @@ class FieldView : public C::mip_field_view /// too few bytes (or to many if exact_size is specified). The field data is not /// valid unless this function returns true. template - bool extract(FieldType& field, bool exact_size=true) const { return mip::extract(field, payload(), payloadLength(), 0, exact_size); } + bool extract(FieldType& field, bool exact_size=true) const { return microstrain::extract(field, payload(), payloadLength(), 0, exact_size); } ///@brief Determines if the field holds data (and not a command, reply, or response). diff --git a/src/cpp/mip/mip_metadata.hpp b/src/cpp/mip/mip_metadata.hpp index be119a506..c18fd4d0a 100644 --- a/src/cpp/mip/mip_metadata.hpp +++ b/src/cpp/mip/mip_metadata.hpp @@ -1,6 +1,7 @@ #pragma once #include +#include #include "mip_descriptors.hpp" @@ -66,15 +67,16 @@ struct ParameterInfo uint16_t union_value = 0; }; + + struct FieldStruct { //static_assert(std::is_base_of, T>::value, "T must inherit from FieldStruct"); private: - // No direct instantiation or destruction, + // No direct instantiation, // this class must be inherited. FieldStruct() = default; - ~FieldStruct() = default; }; template @@ -83,7 +85,7 @@ using isField = std::is_base_of; struct Example : public FieldStruct { - static constexpr inline ParameterInfo PARAMETERS[] = { + static constexpr inline std::initializer_list PARAMETERS = { { /*.type = */ ParameterInfo::Type::BOOL, /*.name = */ "Enable", @@ -110,21 +112,3 @@ struct Example : public FieldStruct } // namespace mip - -#include - -// These functions must be in the microstrain namespace in order to be seen as overloads. -namespace microstrain -{ - -template -std::enable_if::value, size_t>::type -/*size_t*/ insert(microstrain::Serializer& serializer, const T& field) -{ - //static_assert(std::is_base_of, T>::value, "T doesn't derive from FieldStruct"); - - return insert(serializer, static_cast(field).asTuple()); -} - - -} // namespace microstrain diff --git a/src/cpp/mip/mip_serialization.hpp b/src/cpp/mip/mip_serialization.hpp index 61f6e5be3..74934a8f8 100644 --- a/src/cpp/mip/mip_serialization.hpp +++ b/src/cpp/mip/mip_serialization.hpp @@ -1,5 +1,7 @@ #pragma once +#include "mip_metadata.hpp" + #include #include @@ -12,59 +14,86 @@ namespace mip -template -size_t serialize_parameters_r(const std::tuple& args) -{ - constexpr size_t counter_offset = (StructType::COUNTER_PARAMS >> (2*I)) & 0b11; - constexpr bool is_array = counter_offset != 0; +// template +// size_t serialize_parameters_r(const std::tuple& args) +// { +// constexpr size_t counter_offset = (StructType::COUNTER_PARAMS >> (2*I)) & 0b11; +// constexpr bool is_array = counter_offset != 0; +// +// // Non-arrays get appended +// if constexpr(!is_array) +// return serialize_parameters_r(args); +// +// //const size_t counter_index = +// } +// +// +// template +// size_t serialize_parameters(std::tuple& args) +// { +// +// } +// +// +// template +// struct Parameter +// { +// T& value; +// }; +// +// template +// struct ArrayParameter : Parameter +// { +// Counter& count; +// static constexpr size_t max_count = MAX_SIZE_T; +// }; +// template +// struct ArrayParameter : Parameter +// { +// static constexpr size_t max_count = MAX_SIZE_T; +// }; +// +// template +// struct UnionConditionalParameter : Parameter +// { +// const U& selector; +// +// bool matches() const { return selector == SELECTED_VALUE_T; } +// }; - // Non-arrays get appended - if constexpr(!is_array) - return serialize_parameters_r(args); - //const size_t counter_index = -} +//template +//void apply(FieldType& field, Action action) +//{ +// auto values = field.as_tuple(); +//} -template -size_t serialize_parameters(std::tuple& args) -{ +} // namespace mip -} +#include +// These functions must be in the microstrain namespace in order to be seen as overloads. +namespace microstrain +{ template -struct Parameter +std::enable_if::value, size_t>::type +/*size_t*/ insert(microstrain::Serializer& serializer, const T& field) { - T& value; -}; + //static_assert(std::is_base_of, T>::value, "T doesn't derive from FieldStruct"); -template -struct ArrayParameter : Parameter -{ - Counter& count; - static constexpr size_t max_count = MAX_SIZE_T; -}; -template -struct ArrayParameter : Parameter -{ - static constexpr size_t max_count = MAX_SIZE_T; -}; + return insert(serializer, field.asTuple()); +} -template -struct UnionConditionalParameter : Parameter +template +std::enable_if::value, size_t>::type +/*size_t*/ extract(microstrain::Serializer& serializer, T& field) { - const U& selector; - - bool matches() const { return selector == SELECTED_VALUE_T; } -}; + //static_assert(std::is_base_of, T>::value, "T doesn't derive from FieldStruct"); + return extract(serializer, field.asTuple()); +} -//template -//void apply(FieldType& field, Action action) -//{ -// auto values = field.as_tuple(); -//} - -} // namespace mip +} // namespace microstrain From 7e543e2d04ed4dcd0780f425440e3245af3027d0 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 21 Jun 2024 18:05:00 -0400 Subject: [PATCH 031/147] WIP implementing metadata. --- examples/ping.cpp | 286 ------------------ src/cpp/mip/definitions/commands_3dm_meta.hpp | 18 ++ src/cpp/mip/definitions/commands_base.hpp | 19 -- .../mip/definitions/commands_base_meta.hpp | 57 ++++ src/cpp/mip/mip_metadata.hpp | 198 +++++++++--- 5 files changed, 238 insertions(+), 340 deletions(-) delete mode 100644 examples/ping.cpp create mode 100644 src/cpp/mip/definitions/commands_3dm_meta.hpp create mode 100644 src/cpp/mip/definitions/commands_base_meta.hpp diff --git a/examples/ping.cpp b/examples/ping.cpp deleted file mode 100644 index f987dc735..000000000 --- a/examples/ping.cpp +++ /dev/null @@ -1,286 +0,0 @@ - -#include "serial_mip_device.hpp" - -#include -#include -#include -#include - -#include -#include - -namespace mip -{ - namespace C { - CmdResult mipcmd_base_getDeviceInfo(struct C::MipInterfaceState* device, const struct MipCmd_Base_GetDeviceInfo* cmd, struct MipCmd_Base_GetDeviceInfo_Response* response); - CmdResult mipcmd_base_getDeviceInfo(struct C::MipInterfaceState* device, struct MipBaseDeviceInfo* info); - } -} - -int usage(const char* argv[]) -{ - fprintf(stderr, "Usage: %s \n", argv[0]); - return 1; -} - - -int main(int argc, const char* argv[]) -{ - uint32_t baud = 0; - - if( argc == 1 ) - { - printf("Available serial ports:\n"); - std::vector ports = serial::list_ports(); - - for(const serial::PortInfo& port : ports) - { - printf(" %s %s %s\n", port.port.c_str(), port.description.c_str(), port.hardware_id.c_str()); - } - return 0; - } - else if( argc == 3 ) - { - baud = std::strtoul(argv[2], nullptr, 10); - if( baud == 0 ) - { - fprintf(stderr, "Error: invalid baud rate '%s'\n", argv[2]); - return 1; - } - } - else - { - return usage(argv); - } - - try - { -#define METHOD 8 - -#if METHOD == 1 || METHOD == 2 || METHOD == 3 - serial::Serial port(argv[1], baud, serial::Timeout::simpleTimeout(10)); - - uint8_t buffer[PACKET_LENGTH_MAX]; - - mip::Packet packet(buffer, sizeof(buffer), mip::MIP_BASE_COMMAND_DESC_SET); - - uint8_t* payload; - mip::RemainingCount available = packet.allocField(mip::MIP_CMD_DESC_BASE_PING, 0, &payload); - - #if METHOD == 1 - mip::MipCmd_Base_GetDeviceInfo info; - size_t used = mip::insert_MipCmd_Base_GetDeviceInfo(payload, available, 0, &info); - #elif METHOD == 2 - mip::MipCmd_Base_GetDeviceInfo info; - size_t used = mip::insert(payload, available, 0, info); - #elif METHOD == 3 - size_t used = mip::insert_MipCmd_Base_GetDeviceInfo_args(payload, available, 0); - #endif - - // Skip error checking as this field will always fit in this buffer. - packet.reallocLastField(payload, used); - - packet.finalize(); - - printf("Send bytes ["); - for(size_t i=0; i= 5 - MipDevice device(argv[1], baud); - - mip::MipCmd_Base_GetDeviceInfo cmd; - mip::MipCmd_Base_GetDeviceInfo_Response response; - - #if METHOD == 5 - mip::CmdResult result = exec_MipCmd_Base_GetDeviceInfo(&device, &cmd, &response); - #elif METHOD == 6 - mip::CmdResult result = mipcmd_base_getDeviceInfo(&device, &response.device_info); - #elif METHOD == 7 - mip::CmdResult result = mip::runCommand(&device, cmd, response); - #elif METHOD == 8 - mip::DeviceInterface* device2 = &device; - mip::C::MipInterfaceState* device3 = device2; - mip::MipInterfaceState* device4 = device3; - static_assert(std::is_same::value, "Not the same"); - mip::CmdResult result = mip::get_device_information(device4, &response.device_info); - #endif - - if( result == mip::MIP_ACK_OK ) - { - printf("Success:\n"); - - auto print_info = [](const char* name, const char info[16]) - { - char msg[17] = {0}; - std::strncpy(msg, info, 16); - printf(" %s%s\n", name, msg); - }; - - print_info("Model name: ", response.device_info.model_name); - print_info("Model number: ", response.device_info.model_number); - print_info("Serial Number: ", response.device_info.serial_number); - print_info("Device Options: ", response.device_info.device_options); - print_info("Lot Number: ", response.device_info.lot_number); - - printf( " Firmware version: %d.%d.%d\n\n", - (response.device_info.firmware_version / 1000), - (response.device_info.firmware_version / 100) % 10, - (response.device_info.firmware_version / 1) % 100 - ); - } - else - { - printf("Error: command completed with NACK: %s (%d)\n", mip::MipCmdResult_toString(result), result); - } - -#endif - } - catch(const std::exception& ex) - { - fprintf(stderr, "Could not open serial port: %s", ex.what()); - return 1; - } - - return 0; -} -// -// namespace mip -// { -// namespace C -// { -// -// CmdResult mipcmd_base_getDeviceInfo(struct C::MipInterfaceState* device, struct MipBaseDeviceInfo* info) -// { -// uint8_t payload[MIP_FIELD_LENGTH_MAX]; -// -// size_t payloadLength = insert_MipCmd_Base_GetDeviceInfo(payload, sizeof(payload), 0, NULL); -// assert(payloadLength <= sizeof(payload)); -// -// uint8_t responseLength; -// CmdResult result = C::MipInterface_runCommandWithResponse(device, MIP_BASE_COMMAND_DESC_SET, MIP_CMD_DESC_BASE_GET_DEVICE_INFO, payload, payloadLength, MIP_REPLY_DESC_BASE_DEVICE_INFO, payload, &responseLength); -// if( result == MIP_ACK_OK ) -// { -// size_t used = extract_MipBaseDeviceInfo(payload, responseLength, 0, info); -// if( used != responseLength ) -// result = MIP_STATUS_ERROR; -// } -// -// return result; -// } -// -// CmdResult mipcmd_base_getDeviceInfo(struct C::MipInterfaceState* device, const struct MipCmd_Base_GetDeviceInfo* cmd, struct MipCmd_Base_GetDeviceInfo_Response* response) -// { -// uint8_t buffer[PACKET_LENGTH_MAX]; -// -// struct C::Packet packet; -// MipPacket_create(&packet, buffer, sizeof(buffer), MIP_BASE_COMMAND_DESC_SET); -// -// uint8_t* payload; -// RemainingCount available = MipPacket_allocField(&packet, MIP_CMD_DESC_BASE_GET_DEVICE_INFO, 0, &payload); -// -// size_t used = insert_MipCmd_Base_GetDeviceInfo(payload, available, 0, cmd); -// assert( used <= available ); -// MipPacket_reallocLastField(&packet, payload, used); -// -// MipPacket_finalize(&packet); -// -// -// struct C::MipPendingCmd pending; -// C::MipPendingCmd_initWithResponse(&pending, MIP_BASE_COMMAND_DESC_SET, MIP_CMD_DESC_BASE_GET_DEVICE_INFO, MIP_REPLY_DESC_BASE_DEVICE_INFO, buffer, MIP_FIELD_PAYLOAD_LENGTH_MAX); -// -// C::MipCmdQueue_enqueue( C::MipInterface_cmdQueue(device), &pending ); -// -// if( !C::MipInterface_sendToDevice(device, MipPacket_pointer(&packet), MipPacket_totalLength(&packet)) ) -// { -// C::MipCmdQueue_dequeue(C::MipInterface_cmdQueue(device), &pending); -// return MIP_STATUS_ERROR; -// } -// -// CmdResult result = C::MipInterface_waitForReply(device, &pending); -// -// if( result == MIP_ACK_OK ) -// { -// size_t responseLength = C::MipPendingCmd_responseLength(&pending); -// -// used = extract_MipCmd_Base_GetDeviceInfo_Response( C::MipPendingCmd_response(&pending), responseLength, 0, response); -// -// if( used!= responseLength ) -// return MIP_STATUS_ERROR; -// } -// -// return result; -// } -// -// } -// } diff --git a/src/cpp/mip/definitions/commands_3dm_meta.hpp b/src/cpp/mip/definitions/commands_3dm_meta.hpp new file mode 100644 index 000000000..cd0760ee6 --- /dev/null +++ b/src/cpp/mip/definitions/commands_3dm_meta.hpp @@ -0,0 +1,18 @@ + +#include "commands_3dm.hpp" + +#include + +namespace mip +{ +namespace commands_3dm +{ + +template<> +struct FieldInfo +{ + sta +}; + +} // namespace commands_3dm +} // namespace mip diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index 2cdc7594e..a171d59b2 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -671,25 +671,6 @@ struct CommSpeed static constexpr const uint32_t ECHOED_PARAMS = 0x0001; static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - static constexpr inline std::initializer_list PARAMETERS = { - { - ParameterInfo::Type::U8, - "port", - "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports.", - 1, - {true, true, true, true, true}, - 1, - }, - { - ParameterInfo::Type::U32, - "baud", - "Port baud rate. Must be a supported rate.", - 2, - {true,false,false,false,false}, - 1, - }, - }; - auto as_tuple() const { return std::make_tuple(port,baud); diff --git a/src/cpp/mip/definitions/commands_base_meta.hpp b/src/cpp/mip/definitions/commands_base_meta.hpp new file mode 100644 index 000000000..b41fd49d0 --- /dev/null +++ b/src/cpp/mip/definitions/commands_base_meta.hpp @@ -0,0 +1,57 @@ +#pragma once + +#include "commands_base.hpp" + +#include + + +namespace mip +{ + +template<> +struct FieldInfo +{ + using Cmd = commands_base::Ping; + using Rsp = Cmd::Response; + + static constexpr inline const char* NAME = "Ping"; + static constexpr inline const char* DOC_NAME = "Ping"; + static constexpr CompositeDescriptor DESCRIPTOR = Cmd::DESCRIPTOR; + + static constexpr inline std::initializer_list PARAMETERS = {}; +}; + + +template<> +struct FieldInfo +{ + using Cmd = commands_base::CommSpeed; + using Rsp = Cmd::Response; + + static constexpr inline const char* NAME = "CommSpeed"; + static constexpr inline const char* DOC_NAME = "Comm Port Speed"; + static constexpr CompositeDescriptor DESCRIPTOR = Cmd::DESCRIPTOR; + + static constexpr inline std::initializer_list PARAMETERS = { + FUNCTION_PARAMETER, + { + /* .type = */ ParameterInfo::Type::U8, + /* .name = */ "port", + /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports.", + /* .byte_offset = */ 1, + /* .struct_offset = */ offsetof(Cmd,port), + /* .functions = */ {true, true, true, true, true, true}, + }, + { + /* .type = */ ParameterInfo::Type::U32, + /* .name = */ "baud", + /* .docs = */ "Port baud rate. Must be a supported rate.", + /* .byte_offset = */ 2, + /* .struct_offset = */ offsetof(Cmd,baud), + /* .functions = */ {true,false,false,false,false}, + }, + }; +}; + + +} // namespace mip diff --git a/src/cpp/mip/mip_metadata.hpp b/src/cpp/mip/mip_metadata.hpp index c18fd4d0a..f68518512 100644 --- a/src/cpp/mip/mip_metadata.hpp +++ b/src/cpp/mip/mip_metadata.hpp @@ -8,11 +8,25 @@ namespace mip { +struct FieldStruct +{ + //static_assert(std::is_base_of, T>::value, "T must inherit from FieldStruct"); + +private: + // No direct instantiation, + // this class must be inherited. + FieldStruct() = default; +}; + +template +using isField = std::is_base_of; + + struct FuncBits { constexpr FuncBits() = default; - constexpr FuncBits(bool w, bool r, bool s, bool l, bool d) : bits(0x00) { write(w); read(r); save(s); load(l); reset(d); } + constexpr FuncBits(bool w, bool r, bool s, bool l, bool d, bool e=false) : bits(0x00) { write(w); read(r); save(s); load(l); reset(d); echo(e); } constexpr bool any() const { return bits > 0; } @@ -21,12 +35,14 @@ struct FuncBits constexpr bool save() const { return bits & 0b00000100; } constexpr bool load() const { return bits & 0b00001000; } constexpr bool reset() const { return bits & 0b00010000; } + constexpr bool echo() const { return bits & 0b10000000; } constexpr FuncBits& write(bool w) { bits = (bits & 0b11111110) | (uint8_t(w)<<0); return *this; } - constexpr FuncBits& read (bool r) { bits = (bits & 0b11111101) | (uint8_t(r)<<0); return *this; } - constexpr FuncBits& save (bool s) { bits = (bits & 0b11111011) | (uint8_t(s)<<0); return *this; } - constexpr FuncBits& load (bool l) { bits = (bits & 0b11110111) | (uint8_t(l)<<0); return *this; } - constexpr FuncBits& reset(bool d) { bits = (bits & 0b11101111) | (uint8_t(d)<<0); return *this; } + constexpr FuncBits& read (bool r) { bits = (bits & 0b11111101) | (uint8_t(r)<<1); return *this; } + constexpr FuncBits& save (bool s) { bits = (bits & 0b11111011) | (uint8_t(s)<<2); return *this; } + constexpr FuncBits& load (bool l) { bits = (bits & 0b11110111) | (uint8_t(l)<<3); return *this; } + constexpr FuncBits& reset(bool d) { bits = (bits & 0b11101111) | (uint8_t(d)<<4); return *this; } + constexpr FuncBits& echo (bool e) { bits = (bits & 0b01111111) | (uint8_t(e)<<7); return *this; } constexpr bool has(mip::FunctionSelector function) const { return (bits >> (static_cast(function) - static_cast(mip::FunctionSelector::WRITE))) & 1; } @@ -34,11 +50,15 @@ struct FuncBits }; +struct StructInfo; + + struct ParameterInfo { - enum class Type + enum class Type : uint8_t { - NONE = 0, + NONE = 0, ///< Invalid/unknown. + BOOL, U8, S8, @@ -50,55 +70,163 @@ struct ParameterInfo S64, FLOAT, DOUBLE, + ENUM, - BITS, + BITFIELD, STRUCT, UNION, }; - Type type = Type::NONE; - const char* name = nullptr; - const char* docs = nullptr; - uint8_t offset = 0; - FuncBits functions; - uint8_t count = 1; - uint8_t counter_idx = 0xFF; - uint8_t union_index = 0xFF; - uint16_t union_value = 0; + struct TypeInfo + { + template + TypeInfo(T Field::*member); + + Type type; + uint8_t struct_offset = 0; + StructInfo* + }; + + const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). + const char* docs = nullptr; ///< Human-readable documentation. + Type type = Type::NONE; ///< Data type. + uint8_t struct_offset = 0; ///< Offset into the corresponding struct (e.g. using offsetof). + uint8_t byte_offset = 0; ///< Offset "on the wire" or in a serialized buffer, in bytes. + FuncBits functions; ///< This parameter is required for the specified function selectors. + uint8_t count = 1; ///< Number of elements. 0 if size is specified at runtime. + int8_t counter_idx = 0; ///< When count == 0, this specifies the parameter holding the runtime count, relative to this parameter's index. + int8_t union_index = 0; ///< When type is UNION, this specifies the parameter that controls which union member is active (the discriminator). + uint16_t union_value = 0; ///< When in a union, this specifies the value of the discriminator parameter that selects this member. }; +template static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::NONE; + +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::BOOL; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::U8; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType< int8_t, void> = ParameterInfo::Type::S8; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::U16; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType< int16_t, void> = ParameterInfo::Type::S16; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::U32; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType< int32_t, void> = ParameterInfo::Type::S32; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::U64; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType< int64_t, void> = ParameterInfo::Type::S64; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::FLOAT; +template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::DOUBLE; +template static constexpr inline ParameterInfo::Type paramTypeFromCppType::value, T>::type> = ParameterInfo::Type::ENUM; +template static constexpr inline ParameterInfo::Type paramTypeFromCppType, T> = ParameterInfo::Type::BITFIELD; +template static constexpr inline ParameterInfo::Type paramTypeFromCppType::value, T>::type> = ParameterInfo::Type::STRUCT; +template static constexpr inline ParameterInfo::Type paramTypeFromCppType::value, T>::type> = ParameterInfo::Type::UNION; + +//template +//struct ParamTypeFromCppType; +// +//template<> +//struct ParamTypeFromCppType : public std::integral_constant ParameterInfo::Type type = + +//constexpr ParameterInfo::Type typeEnumFromCppType(bool ) { return ParameterInfo::Type::BOOL; } +//constexpr ParameterInfo::Type typeEnumFromCppType(uint8_t) { return ParameterInfo::Type::U8; } +//constexpr ParameterInfo::Type typeEnumFromCppType( int8_t) { return ParameterInfo::Type::S8; } +//constexpr ParameterInfo::Type typeEnumFromCppType(uint16_t) { return ParameterInfo::Type::U16; } +//constexpr ParameterInfo::Type typeEnumFromCppType( int16_t) { return ParameterInfo::Type::S16; } +//constexpr ParameterInfo::Type typeEnumFromCppType(uint32_t) { return ParameterInfo::Type::U32; } +//constexpr ParameterInfo::Type typeEnumFromCppType( int32_t) { return ParameterInfo::Type::S32; } +//constexpr ParameterInfo::Type typeEnumFromCppType(uint64_t) { return ParameterInfo::Type::U64; } +//constexpr ParameterInfo::Type typeEnumFromCppType( int64_t) { return ParameterInfo::Type::S64; } +//constexpr ParameterInfo::Type typeEnumFromCppType(float ) { return ParameterInfo::Type::FLOAT; } +//constexpr ParameterInfo::Type typeEnumFromCppType(double ) { return ParameterInfo::Type::DOUBLE; } +// +//template +//constexpr typename std::enable_if::value, ParameterInfo::Type>::type +///*ParameterInfo::Type*/ typeEnumFromCppType() { return ParameterInfo::Type::ENUM; } +// +//template +//constexpr ParameterInfo::Type typeEnumFromCppType(Bitfield) { return ParameterInfo::Type::BITFIELD; } +// +//template +//constexpr ParameterInfo::Type typeEnumFromCppType(typename std::enable_if::value, T>::type) { return ParameterInfo::Type::STRUCT; } +// +//template +//constexpr ParameterInfo::Type typeEnumFromCppType(typename std::enable_if::value, T>::type) { return ParameterInfo::Type::UNION; } + + +static constexpr inline ParameterInfo FUNCTION_PARAMETER = { + /* .type = */ ParameterInfo::Type::ENUM, + /* .name = */ "function", + /* .docs = */ "Standard MIP function selector", + /* .byte_offset = */ 0, + /* .struct_offset = */ 0, // Function selector MUST be the first struct member. + /* .functions = */ {true,true,true,true,true}, + /* .count = default */ + /* .counter_idx = default */ + /* .union_index = default */ + /* .union_value = default */ +}; -struct FieldStruct + +struct EnumInfo { - //static_assert(std::is_base_of, T>::value, "T must inherit from FieldStruct"); + struct Entry + { + const char* name = nullptr; + uint32_t value = 0; + }; -private: - // No direct instantiation, - // this class must be inherited. - FieldStruct() = default; + const char* name = nullptr; + const char* docs = nullptr; + ParameterInfo::Type type = ParameterInfo::Type::NONE; + std::initializer_list entries = {}; }; -template -using isField = std::is_base_of; +struct StructInfo +{ + const char* name = nullptr; + const char* title = nullptr; + const char* docs = nullptr; + std::initializer_list parameters; +}; + + +// Type trait class to be specialized for each field type. +template +struct FieldInfo; + + + +template +ParamType get(FieldType& field) +{ + return +} + +template +auto get(FieldType& field) +{ + const ParameterInfo& paramInfo = FieldInfo::PARAMETERS[ParameterIndex]; + + +} + struct Example : public FieldStruct { static constexpr inline std::initializer_list PARAMETERS = { { - /*.type = */ ParameterInfo::Type::BOOL, - /*.name = */ "Enable", - /*.docs = */ "Enables the thing", - /*.offset = */ 0, - /*.functions = */ {true, false, false, false, false}, + /*.type = */ ParameterInfo::Type::BOOL, + /*.name = */ "Enable", + /*.docs = */ "Enables the thing", + /*.byte_offset = */ 0, + /*.struct_offset = */ 0, + /*.functions = */ {true, false, false, false, false}, }, { - /*.type = */ ParameterInfo::Type::U8, - /*.name = */ "Count", - /*.docs = */ "Number of things", - /*.offset = */ 1, - /*.functions = */ {true, true, false, false, false}, + /*.type = */ ParameterInfo::Type::U8, + /*.name = */ "Count", + /*.docs = */ "Number of things", + /*.byte_offset = */ 1, + /*.struct_offset = */ 1, + /*.functions = */ {true, true, false, false, false}, } }; From ecdf4a50c56abb85f83cdbec427b880ee02a2eff Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 24 Jun 2024 13:34:22 -0400 Subject: [PATCH 032/147] Fix reference to FieldView. --- src/cpp/mip/mip_packet.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/cpp/mip/mip_packet.hpp b/src/cpp/mip/mip_packet.hpp index fb4bbd6e7..deca65839 100644 --- a/src/cpp/mip/mip_packet.hpp +++ b/src/cpp/mip/mip_packet.hpp @@ -131,7 +131,7 @@ class PacketView : public C::mip_packet_view // Using nullptr is simpler and more efficient than creating an end iterator. std::nullptr_t end() const { return nullptr; } #else - FieldIterator end() const { return Field(); } + FieldIterator end() const { return FieldView(); } #endif ///@brief Returns the first field in the packet. From 372a5c8fa6c29b8b6d28f35491298aef069b9543 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 24 Jun 2024 14:03:49 -0400 Subject: [PATCH 033/147] Fix serialization for c++11. --- src/cpp/microstrain/common/serialization.hpp | 27 +----- src/cpp/mip/definitions/commands_base.hpp | 9 -- src/cpp/mip/mip_descriptors.hpp | 18 ++++ src/cpp/mip/mip_metadata.hpp | 15 +--- src/cpp/mip/mip_serialization.hpp | 87 ++++++-------------- 5 files changed, 46 insertions(+), 110 deletions(-) diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index 513ade514..b5aec0bc0 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -153,14 +153,6 @@ class Serializer }; - -//template -//struct fixed_size {}; -// -//template -//struct fixed_size> : std::integral_constant {}; - - // // General Insertion // @@ -233,24 +225,13 @@ typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type } #else template -size_t insert(Buffer& buffer, T0 value0, Ts... values) +size_t insert(Serializer& serializer, T0 value0, Ts... values) { - return insert(buffer, value0) + insert(buffer, values...); + return insert(serializer, value0) + insert(serializer, values...); } #endif -//template -//size_t insert(Buffer& buffer, Ts... values) { return detail::insert(buffer, values...); } - - -//// Class types with known size -//template::value> -//size_t insert(Buffer& buffer, T value) -//{ -// if(auto ptr = buffer.getPtrAndAdvance(Size)) -// insert -//} // // General Extraction @@ -334,9 +315,9 @@ typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type } #else template -size_t extract(Buffer& buffer, T0 value0, Ts... values) +size_t extract(Serializer& serializer, T0 value0, Ts... values) { - return extract(buffer, value0) + extract(buffer, values...); + return extract(serializer, value0) + extract(serializer, values...); } #endif diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index a171d59b2..83626b68c 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -222,8 +222,6 @@ struct Ping return std::make_tuple(); } - static constexpr inline std::initializer_list PARAMETERS = {}; - auto asTuple() const { return as_tuple(); } auto asTuple() { return as_tuple(); } @@ -267,7 +265,6 @@ struct SetIdle { return std::make_tuple(); } - static constexpr inline std::initializer_list PARAMETERS = {}; auto asTuple() const { return as_tuple(); } auto asTuple() { return as_tuple(); } @@ -310,8 +307,6 @@ struct GetDeviceInfo return std::make_tuple(); } - static constexpr inline std::initializer_list PARAMETERS = {}; - auto asTuple() const { return as_tuple(); } auto asTuple() { return as_tuple(); } @@ -375,10 +370,6 @@ struct GetDeviceDescriptors { return std::make_tuple(); } - static constexpr inline std::initializer_list PARAMETERS = {}; - - auto asTuple() const { return as_tuple(); } - auto asTuple() { return as_tuple(); } struct Response { diff --git a/src/cpp/mip/mip_descriptors.hpp b/src/cpp/mip/mip_descriptors.hpp index 1695c1da6..c568c521f 100644 --- a/src/cpp/mip/mip_descriptors.hpp +++ b/src/cpp/mip/mip_descriptors.hpp @@ -40,6 +40,24 @@ struct CompositeDescriptor }; +// All MIP command/data fields should inherit this struct. +struct FieldStruct +{ + //static_assert(std::is_base_of, T>::value, "T must inherit from FieldStruct"); + +private: + // No direct instantiation, + // this class must be inherited. + FieldStruct() = default; +}; + +template +using isField = std::is_base_of; + +template +using EnableForFieldTypes = std::enable_if::value, T>; + + ///@brief A dummy struct which is used to mark bitfield objects. /// template struct Bitfield {}; diff --git a/src/cpp/mip/mip_metadata.hpp b/src/cpp/mip/mip_metadata.hpp index f68518512..9775e0e34 100644 --- a/src/cpp/mip/mip_metadata.hpp +++ b/src/cpp/mip/mip_metadata.hpp @@ -1,26 +1,13 @@ #pragma once #include -#include +#include "mip_serialization.hpp" #include "mip_descriptors.hpp" namespace mip { -struct FieldStruct -{ - //static_assert(std::is_base_of, T>::value, "T must inherit from FieldStruct"); - -private: - // No direct instantiation, - // this class must be inherited. - FieldStruct() = default; -}; - -template -using isField = std::is_base_of; - struct FuncBits diff --git a/src/cpp/mip/mip_serialization.hpp b/src/cpp/mip/mip_serialization.hpp index 74934a8f8..6ef2370dd 100644 --- a/src/cpp/mip/mip_serialization.hpp +++ b/src/cpp/mip/mip_serialization.hpp @@ -1,7 +1,5 @@ #pragma once -#include "mip_metadata.hpp" - #include #include @@ -10,75 +8,18 @@ namespace mip { - - - - -// template -// size_t serialize_parameters_r(const std::tuple& args) -// { -// constexpr size_t counter_offset = (StructType::COUNTER_PARAMS >> (2*I)) & 0b11; -// constexpr bool is_array = counter_offset != 0; -// -// // Non-arrays get appended -// if constexpr(!is_array) -// return serialize_parameters_r(args); -// -// //const size_t counter_index = -// } -// -// -// template -// size_t serialize_parameters(std::tuple& args) -// { -// -// } -// -// -// template -// struct Parameter -// { -// T& value; -// }; -// -// template -// struct ArrayParameter : Parameter -// { -// Counter& count; -// static constexpr size_t max_count = MAX_SIZE_T; -// }; -// template -// struct ArrayParameter : Parameter -// { -// static constexpr size_t max_count = MAX_SIZE_T; -// }; -// -// template -// struct UnionConditionalParameter : Parameter -// { -// const U& selector; -// -// bool matches() const { return selector == SELECTED_VALUE_T; } -// }; - - - -//template -//void apply(FieldType& field, Action action) -//{ -// auto values = field.as_tuple(); -//} - } // namespace mip -#include // These functions must be in the microstrain namespace in order to be seen as overloads. namespace microstrain { +// +// Mip field types (commands and data) +// template -std::enable_if::value, size_t>::type +typename std::enable_if::value, size_t>::type /*size_t*/ insert(microstrain::Serializer& serializer, const T& field) { //static_assert(std::is_base_of, T>::value, "T doesn't derive from FieldStruct"); @@ -87,7 +28,7 @@ std::enable_if::value, size_t>::type } template -std::enable_if::value, size_t>::type +typename std::enable_if::value, size_t>::type /*size_t*/ extract(microstrain::Serializer& serializer, T& field) { //static_assert(std::is_base_of, T>::value, "T doesn't derive from FieldStruct"); @@ -95,5 +36,23 @@ std::enable_if::value, size_t>::type return extract(serializer, field.asTuple()); } +// +// Bitfields +// + +template +typename std::enable_if, T>::value, size_t>::type +/*size_t*/ insert(Serializer& serializer, T bits) +{ + return insert(serializer, bits.value); +} + +template +typename std::enable_if, T>::value, size_t>::type +/*size_t*/ extract(Serializer& serializer, T& bits) +{ + return extract(serializer, bits.value); +} + } // namespace microstrain From 51cba78e0b38655d8124fe1bef49ab9588fcd14e Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 24 Jun 2024 14:29:31 -0400 Subject: [PATCH 034/147] Commit WIP. --- CMakeLists.txt | 2 +- src/cpp/microstrain/common/platform.hpp | 6 + .../mip/definitions/commands_base_meta.hpp | 14 +- src/cpp/mip/mip_metadata.hpp | 170 ++++++++++-------- 4 files changed, 114 insertions(+), 78 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f365d75f2..26c0928c5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.10) -set(CMAKE_CXX_STANDARD 20) +set(CMAKE_CXX_STANDARD 11) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_C_STANDARD 11) set(CMAKE_C_STANDARD_REQUIRED ON) diff --git a/src/cpp/microstrain/common/platform.hpp b/src/cpp/microstrain/common/platform.hpp index 32fabb00d..02065cf59 100644 --- a/src/cpp/microstrain/common/platform.hpp +++ b/src/cpp/microstrain/common/platform.hpp @@ -2,6 +2,12 @@ #include +#if __cpp_inline_variables >= 201606L +#define INLINE_VAR inline +#else +#define INLINE_VAR +#endif + #if __cpp_if_constexpr >= 201606L #define IF_CONSTEXPR if constexpr diff --git a/src/cpp/mip/definitions/commands_base_meta.hpp b/src/cpp/mip/definitions/commands_base_meta.hpp index b41fd49d0..f8c1d16f0 100644 --- a/src/cpp/mip/definitions/commands_base_meta.hpp +++ b/src/cpp/mip/definitions/commands_base_meta.hpp @@ -35,23 +35,29 @@ struct FieldInfo static constexpr inline std::initializer_list PARAMETERS = { FUNCTION_PARAMETER, { - /* .type = */ ParameterInfo::Type::U8, /* .name = */ "port", /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports.", + /* .type = */ ParameterInfo::Type::U8, + /* .accessor = */ utils::access, /* .byte_offset = */ 1, - /* .struct_offset = */ offsetof(Cmd,port), /* .functions = */ {true, true, true, true, true, true}, }, { - /* .type = */ ParameterInfo::Type::U32, /* .name = */ "baud", /* .docs = */ "Port baud rate. Must be a supported rate.", + /* .type = */ ParameterInfo::Type::U32, + /* .accessor = */ utils::access, /* .byte_offset = */ 2, - /* .struct_offset = */ offsetof(Cmd,baud), /* .functions = */ {true,false,false,false,false}, }, }; }; +using CommandsBase = std::tuple< + FieldInfo, + FieldInfo, + void +>; + } // namespace mip diff --git a/src/cpp/mip/mip_metadata.hpp b/src/cpp/mip/mip_metadata.hpp index 9775e0e34..c7342fed6 100644 --- a/src/cpp/mip/mip_metadata.hpp +++ b/src/cpp/mip/mip_metadata.hpp @@ -39,6 +39,10 @@ struct FuncBits struct StructInfo; +// Type trait class to be specialized for each field type. +template +struct FieldInfo; + struct ParameterInfo { @@ -64,20 +68,22 @@ struct ParameterInfo UNION, }; - struct TypeInfo - { - template - TypeInfo(T Field::*member); + // struct TypeInfo + // { + // template + // TypeInfo(T Field::*member); + // + // Type type; + // uint8_t struct_offset = 0; + // StructInfo* + // }; - Type type; - uint8_t struct_offset = 0; - StructInfo* - }; + using Accessor = void* (*)(void*); const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). const char* docs = nullptr; ///< Human-readable documentation. Type type = Type::NONE; ///< Data type. - uint8_t struct_offset = 0; ///< Offset into the corresponding struct (e.g. using offsetof). + Accessor accessor = nullptr; ///< Obtains a reference to the member variable. uint8_t byte_offset = 0; ///< Offset "on the wire" or in a serialized buffer, in bytes. FuncBits functions; ///< This parameter is required for the specified function selectors. uint8_t count = 1; ///< Number of elements. 0 if size is specified at runtime. @@ -86,63 +92,86 @@ struct ParameterInfo uint16_t union_value = 0; ///< When in a union, this specifies the value of the discriminator parameter that selects this member. }; +template struct ParamType { static INLINE_VAR constexpr auto value = ParameterInfo::Type::NONE; }; + +template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::BOOL; }; +template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::U8; }; +template<> struct ParamType< int8_t, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::S8; }; +template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::U16; }; +template<> struct ParamType< int16_t, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::S16; }; +template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::U32; }; +template<> struct ParamType< int32_t, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::S32; }; +template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::U64; }; +template<> struct ParamType< int64_t, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::S64; }; +template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::FLOAT; }; +template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::DOUBLE; }; +template struct ParamType, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::BITFIELD; }; +template struct ParamType::value, T>::type> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::ENUM; }; +template struct ParamType::type> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::STRUCT; }; +template struct ParamType::value, T>::type> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::UNION; }; + +template +struct ParamEnum { using type = void; }; + +template<> struct ParamEnum { using type = uint8_t; }; +template<> struct ParamEnum { using type = int8_t; }; +template<> struct ParamEnum { using type = uint16_t; }; +template<> struct ParamEnum { using type = int16_t; }; +template<> struct ParamEnum { using type = uint32_t; }; +template<> struct ParamEnum { using type = int32_t; }; +template<> struct ParamEnum { using type = uint64_t; }; +template<> struct ParamEnum { using type = int64_t; }; +template<> struct ParamEnum { using type = float; }; +template<> struct ParamEnum { using type = double; }; + +// template struct ParamEnum; +// template<> struct ParamEnum : + + +///@brief Gets a reference to parameter 'I' in the struct for the given field. +/// +///@tparam I Index indicating which parameter to access. 0-based. +///@tparam FieldType Type of the MIP field struct. +/// +///@param field An instance of the field struct whose member variable will be accessed. +/// +///@returns A reference to member I of the given field. +/// +template +auto& get(typename EnableForFieldTypes::type& field) +{ + constexpr ParameterInfo& paramInfo = FieldInfo::PARAMETERS[I].type; + using T = ParamEnum::type; + return *static_cast(paramInfo.accessor(&field)); +} -template static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::NONE; - -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::BOOL; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::U8; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType< int8_t, void> = ParameterInfo::Type::S8; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::U16; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType< int16_t, void> = ParameterInfo::Type::S16; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::U32; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType< int32_t, void> = ParameterInfo::Type::S32; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::U64; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType< int64_t, void> = ParameterInfo::Type::S64; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::FLOAT; -template<> static constexpr inline ParameterInfo::Type paramTypeFromCppType = ParameterInfo::Type::DOUBLE; -template static constexpr inline ParameterInfo::Type paramTypeFromCppType::value, T>::type> = ParameterInfo::Type::ENUM; -template static constexpr inline ParameterInfo::Type paramTypeFromCppType, T> = ParameterInfo::Type::BITFIELD; -template static constexpr inline ParameterInfo::Type paramTypeFromCppType::value, T>::type> = ParameterInfo::Type::STRUCT; -template static constexpr inline ParameterInfo::Type paramTypeFromCppType::value, T>::type> = ParameterInfo::Type::UNION; - -//template -//struct ParamTypeFromCppType; -// -//template<> -//struct ParamTypeFromCppType : public std::integral_constant ParameterInfo::Type type = - -//constexpr ParameterInfo::Type typeEnumFromCppType(bool ) { return ParameterInfo::Type::BOOL; } -//constexpr ParameterInfo::Type typeEnumFromCppType(uint8_t) { return ParameterInfo::Type::U8; } -//constexpr ParameterInfo::Type typeEnumFromCppType( int8_t) { return ParameterInfo::Type::S8; } -//constexpr ParameterInfo::Type typeEnumFromCppType(uint16_t) { return ParameterInfo::Type::U16; } -//constexpr ParameterInfo::Type typeEnumFromCppType( int16_t) { return ParameterInfo::Type::S16; } -//constexpr ParameterInfo::Type typeEnumFromCppType(uint32_t) { return ParameterInfo::Type::U32; } -//constexpr ParameterInfo::Type typeEnumFromCppType( int32_t) { return ParameterInfo::Type::S32; } -//constexpr ParameterInfo::Type typeEnumFromCppType(uint64_t) { return ParameterInfo::Type::U64; } -//constexpr ParameterInfo::Type typeEnumFromCppType( int64_t) { return ParameterInfo::Type::S64; } -//constexpr ParameterInfo::Type typeEnumFromCppType(float ) { return ParameterInfo::Type::FLOAT; } -//constexpr ParameterInfo::Type typeEnumFromCppType(double ) { return ParameterInfo::Type::DOUBLE; } -// -//template -//constexpr typename std::enable_if::value, ParameterInfo::Type>::type -///*ParameterInfo::Type*/ typeEnumFromCppType() { return ParameterInfo::Type::ENUM; } -// -//template -//constexpr ParameterInfo::Type typeEnumFromCppType(Bitfield) { return ParameterInfo::Type::BITFIELD; } -// -//template -//constexpr ParameterInfo::Type typeEnumFromCppType(typename std::enable_if::value, T>::type) { return ParameterInfo::Type::STRUCT; } -// -//template -//constexpr ParameterInfo::Type typeEnumFromCppType(typename std::enable_if::value, T>::type) { return ParameterInfo::Type::UNION; } - - -static constexpr inline ParameterInfo FUNCTION_PARAMETER = { - /* .type = */ ParameterInfo::Type::ENUM, + +namespace utils +{ + // Gets a void pointer to the member identified by Ptr, given an + // instance of field passed by void pointer. + template + void* access(void* p) + { + return &(static_cast(p)->*Ptr); + } + + // Converts a pointer to a struct to a pointer to FunctionSelector. + // Note: this assumes the function selector is the very first parameter, + // no non-empty base classes, etc. and is legal c++. + inline void* accessFunctionSelector(void* p) + { + return static_cast(p); + } +} + +// Function selector MUST be the first struct member (or not a member at all)! +static constexpr INLINE_VAR ParameterInfo FUNCTION_PARAMETER = { /* .name = */ "function", /* .docs = */ "Standard MIP function selector", + /* .type = */ ParameterInfo::Type::ENUM, + /* .accessor = */ utils::accessFunctionSelector, /* .byte_offset = */ 0, - /* .struct_offset = */ 0, // Function selector MUST be the first struct member. /* .functions = */ {true,true,true,true,true}, /* .count = default */ /* .counter_idx = default */ @@ -162,7 +191,7 @@ struct EnumInfo const char* name = nullptr; const char* docs = nullptr; ParameterInfo::Type type = ParameterInfo::Type::NONE; - std::initializer_list entries = {}; + std::initializer_list entries; }; struct StructInfo @@ -174,16 +203,11 @@ struct StructInfo }; -// Type trait class to be specialized for each field type. -template -struct FieldInfo; - template ParamType get(FieldType& field) { - return } template @@ -198,20 +222,20 @@ auto get(FieldType& field) struct Example : public FieldStruct { - static constexpr inline std::initializer_list PARAMETERS = { + static constexpr INLINE_VAR std::initializer_list PARAMETERS = { { - /*.type = */ ParameterInfo::Type::BOOL, /*.name = */ "Enable", /*.docs = */ "Enables the thing", + /*.type = */ ParameterInfo::Type::BOOL, + /*.accessor = */ nullptr,//[](void*)->void*{return nullptr;}, /*.byte_offset = */ 0, - /*.struct_offset = */ 0, /*.functions = */ {true, false, false, false, false}, }, { - /*.type = */ ParameterInfo::Type::U8, /*.name = */ "Count", /*.docs = */ "Number of things", - /*.byte_offset = */ 1, + /*.type = */ ParameterInfo::Type::U8, + /*.accessor = */ nullptr, //[](void*)->void*{return nullptr;}, /*.struct_offset = */ 1, /*.functions = */ {true, true, false, false, false}, } From 4657fc9e9686dfeb1cf3268aa89d8baa1b726333 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 24 Jun 2024 18:46:48 -0400 Subject: [PATCH 035/147] WIP implementing metadata. --- CMakeLists.txt | 2 +- examples/CMakeLists.txt | 1 + examples/CSV/csv.cpp | 65 +++++ src/cpp/microstrain/common/serialization.hpp | 2 +- src/cpp/mip/definitions/commands_base.hpp | 1 - .../definitions/commands_3dm.hpp} | 0 .../definitions/commands_base.hpp} | 43 +-- .../mip/metadata/definitions/data_sensor.hpp | 67 +++++ src/cpp/mip/metadata/mip_all_definitions.hpp | 20 ++ src/cpp/mip/metadata/mip_definitions.hpp | 28 ++ src/cpp/mip/metadata/mip_metadata.hpp | 61 +++++ src/cpp/mip/metadata/structures.hpp | 140 ++++++++++ src/cpp/mip/metadata/utils.hpp | 122 +++++++++ src/cpp/mip/mip_metadata.hpp | 253 ------------------ 14 files changed, 531 insertions(+), 274 deletions(-) create mode 100644 examples/CSV/csv.cpp rename src/cpp/mip/{definitions/commands_3dm_meta.hpp => metadata/definitions/commands_3dm.hpp} (100%) rename src/cpp/mip/{definitions/commands_base_meta.hpp => metadata/definitions/commands_base.hpp} (56%) create mode 100644 src/cpp/mip/metadata/definitions/data_sensor.hpp create mode 100644 src/cpp/mip/metadata/mip_all_definitions.hpp create mode 100644 src/cpp/mip/metadata/mip_definitions.hpp create mode 100644 src/cpp/mip/metadata/mip_metadata.hpp create mode 100644 src/cpp/mip/metadata/structures.hpp create mode 100644 src/cpp/mip/metadata/utils.hpp delete mode 100644 src/cpp/mip/mip_metadata.hpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 26c0928c5..f365d75f2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.10) -set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_STANDARD 20) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_C_STANDARD 11) set(CMAKE_C_STANDARD_REQUIRED ON) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 3962f2a36..6769a8506 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -48,6 +48,7 @@ if(MIP_USE_SERIAL OR MIP_USE_TCP) add_mip_example(DeviceInfo "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/device_info.cpp") add_mip_example(WatchImu "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.cpp") add_mip_example(Threads "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/threading.cpp") + add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp") # Product-specific examples add_mip_example(GQ7_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") diff --git a/examples/CSV/csv.cpp b/examples/CSV/csv.cpp new file mode 100644 index 000000000..8f63bbb60 --- /dev/null +++ b/examples/CSV/csv.cpp @@ -0,0 +1,65 @@ + +#include "../example_utils.hpp" + +#include "definitions.hpp" + +#include + +#include +#include +#include + + +volatile sig_atomic_t stop_flag = false; +mip::Timestamp last_receive_time = 0; + +mip::Definitions mipdefs; + +void signal_handler(int signum) +{ + stop_flag = true; +} + + +void handleField(void*, const mip::FieldView& field, mip::Timestamp timestamp) +{ + printf("%lu: field 0x%02X%02X\n", timestamp, field.descriptorSet(), field.fieldDescriptor()); + last_receive_time = timestamp; +} + + +int main(int argc, const char* argv[]) +{ + std::unique_ptr utils; + try { + utils = handleCommonArgs(argc, argv); + } catch(const std::underflow_error& ex) { + return printCommonUsage(argv); + } catch(const std::exception& ex) { + fprintf(stderr, "Error: %s\n", ex.what()); + return 1; + } + + std::unique_ptr& device = utils->device; + + if(mip::CmdResult result = mip::commands_base::resume(*device); !result) + { + fprintf(stderr, "Error: Resume command failed: %d %s\n", result.value, result.name()); + return 1; + } + + mip::DispatchHandler handler; + device->registerFieldCallback<&handleField>(handler, 0xFF, mip::INVALID_FIELD_DESCRIPTOR); + + std::signal(SIGTERM, &signal_handler); + + while(!stop_flag) + { + device->update(100); + } + + printf("Stopped.\n"); + + return 0; +} + diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index b5aec0bc0..0fa2133fc 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -185,7 +185,7 @@ typename std::enable_if::value, size_t>::type template size_t insert(Serializer& serializer, const std::tuple& values) { - auto lambda = [&serializer](const auto&... args) { + auto lambda = [&serializer](const Ts&... args) { return insert(serializer, args...); }; diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index 83626b68c..6d7545633 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -3,7 +3,6 @@ #include "common.hpp" #include #include -#include #include #include diff --git a/src/cpp/mip/definitions/commands_3dm_meta.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp similarity index 100% rename from src/cpp/mip/definitions/commands_3dm_meta.hpp rename to src/cpp/mip/metadata/definitions/commands_3dm.hpp diff --git a/src/cpp/mip/definitions/commands_base_meta.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp similarity index 56% rename from src/cpp/mip/definitions/commands_base_meta.hpp rename to src/cpp/mip/metadata/definitions/commands_base.hpp index f8c1d16f0..0ea418d16 100644 --- a/src/cpp/mip/definitions/commands_base_meta.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -1,15 +1,15 @@ #pragma once -#include "commands_base.hpp" +#include -#include +#include -namespace mip +namespace mip::metadata { template<> -struct FieldInfo +struct MetadataForField { using Cmd = commands_base::Ping; using Rsp = Cmd::Response; @@ -23,21 +23,21 @@ struct FieldInfo template<> -struct FieldInfo +struct MetadataForField { using Cmd = commands_base::CommSpeed; - using Rsp = Cmd::Response; - - static constexpr inline const char* NAME = "CommSpeed"; - static constexpr inline const char* DOC_NAME = "Comm Port Speed"; - static constexpr CompositeDescriptor DESCRIPTOR = Cmd::DESCRIPTOR; + //using Rsp = Cmd::Response; + // + //static constexpr inline const char* NAME = "CommSpeed"; + //static constexpr inline const char* DOC_NAME = "Comm Port Speed"; + //static constexpr CompositeDescriptor DESCRIPTOR = Cmd::DESCRIPTOR; static constexpr inline std::initializer_list PARAMETERS = { - FUNCTION_PARAMETER, + utils::FUNCTION_SELECTOR_PARAM, { /* .name = */ "port", /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports.", - /* .type = */ ParameterInfo::Type::U8, + /* .type = */ {Type::U8}, /* .accessor = */ utils::access, /* .byte_offset = */ 1, /* .functions = */ {true, true, true, true, true, true}, @@ -45,19 +45,26 @@ struct FieldInfo { /* .name = */ "baud", /* .docs = */ "Port baud rate. Must be a supported rate.", - /* .type = */ ParameterInfo::Type::U32, + /* .type = */ {Type::U32}, /* .accessor = */ utils::access, /* .byte_offset = */ 2, /* .functions = */ {true,false,false,false,false}, }, }; + + static constexpr inline FieldInfo value = { + /* .name = */ "CommSpeed", + /* .title = */ "Comm Port Speed", + /* .docs = */ "Changes the comm port speed.", + /* .parameters = */ PARAMETERS, + /* .functions = */ {true,true,true,true,true}, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; }; -using CommandsBase = std::tuple< - FieldInfo, - FieldInfo, - void ->; +static constexpr inline + } // namespace mip diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp new file mode 100644 index 000000000..2429d211d --- /dev/null +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -0,0 +1,67 @@ +#pragma once + +#include + +#include +#include + +namespace mip::metadata +{ + +template<> +struct MetadataForField +{ + using Field = data_sensor::ScaledAccel; + + static constexpr inline FieldInfo value = { + /* .name = */ "CommSpeed", + /* .title = */ "Comm Port Speed", + /* .docs = */ "Changes the comm port speed.", + /* .parameters = */ { + { + /* .name = */ "scaled_accel", + /* .docs = */ "Scaled acceleration in [g]", + /* .type = */ {Type::STRUCT}, + /* .accessor = */ utils::access, + ///* .byte_offset = */ 0, + ///* .functions = */ {false, false, false, false, false}, + }, + }, + ///* .functions = */ {false,false,false,false,false}, + ///* .proprietary = */ false, + ///* .response = */ nullptr, + }; +}; + +template<> +struct MetadataForField +{ + using Field = data_sensor::ScaledGyro; + + static constexpr inline FieldInfo value = { + /* .name = */ "CommSpeed", + /* .title = */ "Comm Port Speed", + /* .docs = */ "Changes the comm port speed.", + /* .parameters = */ { + { + /* .name = */ "scaled_gyro", + /* .docs = */ "Scaled angular rate in [rad/s]", + /* .type = */ {Type::STRUCT}, + /* .accessor = */ utils::access, + ///* .byte_offset = */ 0, + ///* .functions = */ {false, false, false, false, false}, + }, + }, + ///* .functions = */ {false,false,false,false,false}, + ///* .proprietary = */ false, + ///* .response = */ nullptr, + }; +}; + + +static constexpr inline std::initializer_list ALL_SENSOR_DATA = { + &MetadataForField::value, + &MetadataForField::value, +}; + +} // namespace mip diff --git a/src/cpp/mip/metadata/mip_all_definitions.hpp b/src/cpp/mip/metadata/mip_all_definitions.hpp new file mode 100644 index 000000000..1aef49488 --- /dev/null +++ b/src/cpp/mip/metadata/mip_all_definitions.hpp @@ -0,0 +1,20 @@ + + +#include +#include +#include + + +namespace mip::metadata +{ + +static constexpr inline std::initializer_list< const std::initializer_list* > ALL_COMMANDS = { + &ALL_BASE_COMMANDS, +}; +static constexpr inline std::initializer_list< const std::initializer_list* > ALL_DATA = { + &ALL_SENSOR_DATA, +}; + + +} // namespace mip + diff --git a/src/cpp/mip/metadata/mip_definitions.hpp b/src/cpp/mip/metadata/mip_definitions.hpp new file mode 100644 index 000000000..f32bb448f --- /dev/null +++ b/src/cpp/mip/metadata/mip_definitions.hpp @@ -0,0 +1,28 @@ +#pragma once + +#include "mip_metadata.hpp" +#include "../mip_descriptors.hpp" + +#include +#include + + +namespace mip::metadata +{ + +class Definitions +{ +public: + const metadata::FieldInfo* findField(mip::CompositeDescriptor descriptor); + + std::span findDescriptorSet(uint8_t descriptorSet); + +private: + //std::vector> mFields; + +}; + + + + +} // namespace mip::metadata diff --git a/src/cpp/mip/metadata/mip_metadata.hpp b/src/cpp/mip/metadata/mip_metadata.hpp new file mode 100644 index 000000000..c82b4d994 --- /dev/null +++ b/src/cpp/mip/metadata/mip_metadata.hpp @@ -0,0 +1,61 @@ +#pragma once + +#include "structures.hpp" +#include "utils.hpp" + +#include +#include + + +namespace mip::metadata +{ + +// Type trait class to be specialized for each field type. +template +struct MetadataForField; + + + +// template struct ParamEnum; +// template<> struct ParamEnum : + + +///@brief Gets a reference to parameter 'I' in the struct for the given field. +/// +///@tparam I Index indicating which parameter to access. 0-based. +///@tparam FieldType Type of the MIP field struct. +/// +///@param field An instance of the field struct whose member variable will be accessed. +/// +///@returns A reference to member I of the given field. +/// +template +auto& get(typename EnableForFieldTypes::type& field) +{ + constexpr ParameterInfo& paramInfo = MetadataForField::PARAMETERS[I].type; + using T = typename utils::ParamEnum::type; + return *static_cast(paramInfo.accessor(&field)); +} + + +namespace utils +{ +} + + + +template +ParamType get(FieldType& field) +{ +} + +template +auto get(FieldType& field) +{ + const ParameterInfo& paramInfo = MetadataForField::PARAMETERS[ParameterIndex]; + + +} + + +} // namespace mip diff --git a/src/cpp/mip/metadata/structures.hpp b/src/cpp/mip/metadata/structures.hpp new file mode 100644 index 000000000..1d8f06d6c --- /dev/null +++ b/src/cpp/mip/metadata/structures.hpp @@ -0,0 +1,140 @@ +#pragma once + +#include + +#include +#include + + +namespace mip::metadata +{ + +struct EnumInfo; +struct BitfieldInfo; +struct UnionInfo; +struct StructInfo; +struct FieldInfo; +struct ParameterInfo; + + +enum class Type +{ + NONE = 0, ///< Invalid/unknown. + + BOOL, + U8, + S8, + U16, + S16, + U32, + S32, + U64, + S64, + FLOAT, + DOUBLE, + + ENUM, + BITFIELD, + STRUCT, + UNION, +}; + +struct TypeInfo +{ + //template + //TypeInfo(T Field::*member); + + Type type = Type::NONE; + + const void* infoPtr = nullptr; + //union + //{ + // const StructInfo *si; + // const EnumInfo *ei; + // const BitfieldInfo *bi; + // const UnionInfo *ui; + //}; +}; + +struct EnumInfo +{ + struct Entry + { + const char* name = nullptr; + uint32_t value = 0; + }; + + const char* name = nullptr; + const char* docs = nullptr; + Type type = Type::NONE; + std::initializer_list entries; +}; + +struct BitfieldInfo : public EnumInfo {}; + + +struct ParameterInfo; // Defined below + +struct StructInfo +{ + const char* name = nullptr; + const char* title = nullptr; + const char* docs = nullptr; + std::initializer_list parameters; +}; + + +struct FuncBits +{ + constexpr FuncBits() = default; + constexpr FuncBits(bool w, bool r, bool s, bool l, bool d, bool e=false) : bits(0x00) { write(w); read(r); save(s); load(l); reset(d); echo(e); } + + constexpr bool any() const { return bits > 0; } + + constexpr bool write() const { return bits & 0b00000001; } + constexpr bool read() const { return bits & 0b00000010; } + constexpr bool save() const { return bits & 0b00000100; } + constexpr bool load() const { return bits & 0b00001000; } + constexpr bool reset() const { return bits & 0b00010000; } + constexpr bool echo() const { return bits & 0b10000000; } + + constexpr FuncBits& write(bool w) { bits = (bits & 0b11111110) | (uint8_t(w)<<0); return *this; } + constexpr FuncBits& read (bool r) { bits = (bits & 0b11111101) | (uint8_t(r)<<1); return *this; } + constexpr FuncBits& save (bool s) { bits = (bits & 0b11111011) | (uint8_t(s)<<2); return *this; } + constexpr FuncBits& load (bool l) { bits = (bits & 0b11110111) | (uint8_t(l)<<3); return *this; } + constexpr FuncBits& reset(bool d) { bits = (bits & 0b11101111) | (uint8_t(d)<<4); return *this; } + constexpr FuncBits& echo (bool e) { bits = (bits & 0b01111111) | (uint8_t(e)<<7); return *this; } + + constexpr bool has(mip::FunctionSelector function) const { return (bits >> (static_cast(function) - static_cast(mip::FunctionSelector::WRITE))) & 1; } + + uint8_t bits = 0x00; +}; + + +struct FieldInfo : public StructInfo +{ + FuncBits functions = {false, false, false, false, false}; + bool proprietary = false; + FieldInfo* response = nullptr; +}; + + + +struct ParameterInfo +{ + using Accessor = void* (*)(void*); + + const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). + const char* docs = nullptr; ///< Human-readable documentation. + TypeInfo type; ///< Data type. + Accessor accessor = nullptr; ///< Obtains a reference to the member variable. + uint8_t byte_offset = 0; ///< Offset "on the wire" or in a serialized buffer, in bytes. + FuncBits functions; ///< This parameter is required for the specified function selectors. + uint8_t count = 1; ///< Number of elements. 0 if size is specified at runtime. + int8_t counter_idx = 0; ///< When count == 0, this specifies the parameter holding the runtime count, relative to this parameter's index. + int8_t union_index = 0; ///< When type is UNION, this specifies the parameter that controls which union member is active (the discriminator). + uint16_t union_value = 0; ///< When in a union, this specifies the value of the discriminator parameter that selects this member. +}; + + +} // namespace mip::metadata diff --git a/src/cpp/mip/metadata/utils.hpp b/src/cpp/mip/metadata/utils.hpp new file mode 100644 index 000000000..a3fb0ee82 --- /dev/null +++ b/src/cpp/mip/metadata/utils.hpp @@ -0,0 +1,122 @@ +#pragma once + +#include "structures.hpp" + + +namespace mip::metadata::utils +{ + +// +// Gets the "Type" enum value given a C++ template type. +// +template struct ParamType { static inline constexpr auto value = Type::NONE; }; + +template<> struct ParamType { static constexpr inline auto value = Type::BOOL; }; +template<> struct ParamType { static constexpr inline auto value = Type::U8; }; +template<> struct ParamType< int8_t, void> { static constexpr inline auto value = Type::S8; }; +template<> struct ParamType { static constexpr inline auto value = Type::U16; }; +template<> struct ParamType< int16_t, void> { static constexpr inline auto value = Type::S16; }; +template<> struct ParamType { static constexpr inline auto value = Type::U32; }; +template<> struct ParamType< int32_t, void> { static constexpr inline auto value = Type::S32; }; +template<> struct ParamType { static constexpr inline auto value = Type::U64; }; +template<> struct ParamType< int64_t, void> { static constexpr inline auto value = Type::S64; }; +template<> struct ParamType { static constexpr inline auto value = Type::FLOAT; }; +template<> struct ParamType { static constexpr inline auto value = Type::DOUBLE; }; +template struct ParamType, void> { static constexpr inline auto value = Type::BITFIELD; }; +template struct ParamType::value, T>::type> { static constexpr inline auto value = Type::ENUM; }; +template struct ParamType::type> { static constexpr inline auto value = Type::STRUCT; }; +template struct ParamType::value, T>::type> { static constexpr inline auto value = Type::UNION; }; + + +// +// Gets the template type given a compile-time "Type" enum value. +// Note: this only works with basic/built-in/arithmetic types, not structs/enums/etc. +// +template +struct ParamEnum { using type = void; }; + +template<> struct ParamEnum { using type = bool; }; +template<> struct ParamEnum { using type = uint8_t; }; +template<> struct ParamEnum { using type = int8_t; }; +template<> struct ParamEnum { using type = uint16_t; }; +template<> struct ParamEnum { using type = int16_t; }; +template<> struct ParamEnum { using type = uint32_t; }; +template<> struct ParamEnum { using type = int32_t; }; +template<> struct ParamEnum { using type = uint64_t; }; +template<> struct ParamEnum { using type = int64_t; }; +template<> struct ParamEnum { using type = float; }; +template<> struct ParamEnum { using type = double; }; + + +// Gets a void pointer to the member identified by Ptr, given an +// instance of field passed by void pointer. +template +void* access(void* p) +{ + return &(static_cast(p)->*Ptr); +} + + +static constexpr inline EnumInfo FUNCTION_SELECTOR_ENUM = { + .name = "FunctionSelector", + .docs = "", + .type = Type::U8, + .entries = { + { "WRITE", (uint8_t)FunctionSelector::WRITE }, + { "READ", (uint8_t)FunctionSelector::READ }, + { "SAVE", (uint8_t)FunctionSelector::SAVE }, + { "LOAD", (uint8_t)FunctionSelector::LOAD }, + { "DEFAULT", (uint8_t)FunctionSelector::RESET }, + } +}; + +inline void* accessFunctionSelector(void* p) { return static_cast(p); } + +static constexpr inline ParameterInfo FUNCTION_SELECTOR_PARAM = { + /* .name = */ "function", + /* .docs = */ "Standard MIP function selector", + /* .type = */ {Type::ENUM, (const void*)&FUNCTION_SELECTOR_ENUM}, + /* .accessor = */ accessFunctionSelector, + /* .byte_offset = */ 0, + /* .functions = */ {true,true,true,true,true}, + /* .count = default */ + /* .counter_idx = default */ + /* .union_index = default */ + /* .union_value = default */ +}; + +//template +//constexpr ParameterInfo makeFunctionSelectorParam() +//{ +// return { +// /* .name = */ "function", +// /* .docs = */ "Standard MIP function selector", +// /* .type = */ {Type::ENUM, &FUNCTION_SELECTOR_ENUM_INFO}, +// /* .accessor = */ utils::access, +// /* .byte_offset = */ 0, +// /* .functions = */ {true,true,true,true,true}, +// /* .count = default */ +// /* .counter_idx = default */ +// /* .union_index = default */ +// /* .union_value = default */ +// }; +//} + +//template +//struct FunctionSelectorParam +//{ +// static constexpr inline ParameterInfo value = { +// /* .name = */ "function", +// /* .docs = */ "Standard MIP function selector", +// /* .type = */ Type::ENUM, +// /* .accessor = */ utils::access, +// /* .byte_offset = */ 0, // Always the first parameter. +// /* .functions = */ {true,true,true,true,true}, +// /* .count = default */ +// /* .counter_idx = default */ +// /* .union_index = default */ +// /* .union_value = default */ +// }; +//}; + +} // namespace mip::metadata diff --git a/src/cpp/mip/mip_metadata.hpp b/src/cpp/mip/mip_metadata.hpp deleted file mode 100644 index c7342fed6..000000000 --- a/src/cpp/mip/mip_metadata.hpp +++ /dev/null @@ -1,253 +0,0 @@ -#pragma once - -#include - -#include "mip_serialization.hpp" -#include "mip_descriptors.hpp" - -namespace mip -{ - - - -struct FuncBits -{ - constexpr FuncBits() = default; - constexpr FuncBits(bool w, bool r, bool s, bool l, bool d, bool e=false) : bits(0x00) { write(w); read(r); save(s); load(l); reset(d); echo(e); } - - constexpr bool any() const { return bits > 0; } - - constexpr bool write() const { return bits & 0b00000001; } - constexpr bool read() const { return bits & 0b00000010; } - constexpr bool save() const { return bits & 0b00000100; } - constexpr bool load() const { return bits & 0b00001000; } - constexpr bool reset() const { return bits & 0b00010000; } - constexpr bool echo() const { return bits & 0b10000000; } - - constexpr FuncBits& write(bool w) { bits = (bits & 0b11111110) | (uint8_t(w)<<0); return *this; } - constexpr FuncBits& read (bool r) { bits = (bits & 0b11111101) | (uint8_t(r)<<1); return *this; } - constexpr FuncBits& save (bool s) { bits = (bits & 0b11111011) | (uint8_t(s)<<2); return *this; } - constexpr FuncBits& load (bool l) { bits = (bits & 0b11110111) | (uint8_t(l)<<3); return *this; } - constexpr FuncBits& reset(bool d) { bits = (bits & 0b11101111) | (uint8_t(d)<<4); return *this; } - constexpr FuncBits& echo (bool e) { bits = (bits & 0b01111111) | (uint8_t(e)<<7); return *this; } - - constexpr bool has(mip::FunctionSelector function) const { return (bits >> (static_cast(function) - static_cast(mip::FunctionSelector::WRITE))) & 1; } - - uint8_t bits = 0x00; -}; - - -struct StructInfo; - -// Type trait class to be specialized for each field type. -template -struct FieldInfo; - - -struct ParameterInfo -{ - enum class Type : uint8_t - { - NONE = 0, ///< Invalid/unknown. - - BOOL, - U8, - S8, - U16, - S16, - U32, - S32, - U64, - S64, - FLOAT, - DOUBLE, - - ENUM, - BITFIELD, - STRUCT, - UNION, - }; - - // struct TypeInfo - // { - // template - // TypeInfo(T Field::*member); - // - // Type type; - // uint8_t struct_offset = 0; - // StructInfo* - // }; - - using Accessor = void* (*)(void*); - - const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). - const char* docs = nullptr; ///< Human-readable documentation. - Type type = Type::NONE; ///< Data type. - Accessor accessor = nullptr; ///< Obtains a reference to the member variable. - uint8_t byte_offset = 0; ///< Offset "on the wire" or in a serialized buffer, in bytes. - FuncBits functions; ///< This parameter is required for the specified function selectors. - uint8_t count = 1; ///< Number of elements. 0 if size is specified at runtime. - int8_t counter_idx = 0; ///< When count == 0, this specifies the parameter holding the runtime count, relative to this parameter's index. - int8_t union_index = 0; ///< When type is UNION, this specifies the parameter that controls which union member is active (the discriminator). - uint16_t union_value = 0; ///< When in a union, this specifies the value of the discriminator parameter that selects this member. -}; - -template struct ParamType { static INLINE_VAR constexpr auto value = ParameterInfo::Type::NONE; }; - -template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::BOOL; }; -template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::U8; }; -template<> struct ParamType< int8_t, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::S8; }; -template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::U16; }; -template<> struct ParamType< int16_t, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::S16; }; -template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::U32; }; -template<> struct ParamType< int32_t, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::S32; }; -template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::U64; }; -template<> struct ParamType< int64_t, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::S64; }; -template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::FLOAT; }; -template<> struct ParamType { static constexpr INLINE_VAR auto value = ParameterInfo::Type::DOUBLE; }; -template struct ParamType, void> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::BITFIELD; }; -template struct ParamType::value, T>::type> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::ENUM; }; -template struct ParamType::type> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::STRUCT; }; -template struct ParamType::value, T>::type> { static constexpr INLINE_VAR auto value = ParameterInfo::Type::UNION; }; - -template -struct ParamEnum { using type = void; }; - -template<> struct ParamEnum { using type = uint8_t; }; -template<> struct ParamEnum { using type = int8_t; }; -template<> struct ParamEnum { using type = uint16_t; }; -template<> struct ParamEnum { using type = int16_t; }; -template<> struct ParamEnum { using type = uint32_t; }; -template<> struct ParamEnum { using type = int32_t; }; -template<> struct ParamEnum { using type = uint64_t; }; -template<> struct ParamEnum { using type = int64_t; }; -template<> struct ParamEnum { using type = float; }; -template<> struct ParamEnum { using type = double; }; - -// template struct ParamEnum; -// template<> struct ParamEnum : - - -///@brief Gets a reference to parameter 'I' in the struct for the given field. -/// -///@tparam I Index indicating which parameter to access. 0-based. -///@tparam FieldType Type of the MIP field struct. -/// -///@param field An instance of the field struct whose member variable will be accessed. -/// -///@returns A reference to member I of the given field. -/// -template -auto& get(typename EnableForFieldTypes::type& field) -{ - constexpr ParameterInfo& paramInfo = FieldInfo::PARAMETERS[I].type; - using T = ParamEnum::type; - return *static_cast(paramInfo.accessor(&field)); -} - - -namespace utils -{ - // Gets a void pointer to the member identified by Ptr, given an - // instance of field passed by void pointer. - template - void* access(void* p) - { - return &(static_cast(p)->*Ptr); - } - - // Converts a pointer to a struct to a pointer to FunctionSelector. - // Note: this assumes the function selector is the very first parameter, - // no non-empty base classes, etc. and is legal c++. - inline void* accessFunctionSelector(void* p) - { - return static_cast(p); - } -} - -// Function selector MUST be the first struct member (or not a member at all)! -static constexpr INLINE_VAR ParameterInfo FUNCTION_PARAMETER = { - /* .name = */ "function", - /* .docs = */ "Standard MIP function selector", - /* .type = */ ParameterInfo::Type::ENUM, - /* .accessor = */ utils::accessFunctionSelector, - /* .byte_offset = */ 0, - /* .functions = */ {true,true,true,true,true}, - /* .count = default */ - /* .counter_idx = default */ - /* .union_index = default */ - /* .union_value = default */ -}; - - -struct EnumInfo -{ - struct Entry - { - const char* name = nullptr; - uint32_t value = 0; - }; - - const char* name = nullptr; - const char* docs = nullptr; - ParameterInfo::Type type = ParameterInfo::Type::NONE; - std::initializer_list entries; -}; - -struct StructInfo -{ - const char* name = nullptr; - const char* title = nullptr; - const char* docs = nullptr; - std::initializer_list parameters; -}; - - - - -template -ParamType get(FieldType& field) -{ -} - -template -auto get(FieldType& field) -{ - const ParameterInfo& paramInfo = FieldInfo::PARAMETERS[ParameterIndex]; - - -} - - - -struct Example : public FieldStruct -{ - static constexpr INLINE_VAR std::initializer_list PARAMETERS = { - { - /*.name = */ "Enable", - /*.docs = */ "Enables the thing", - /*.type = */ ParameterInfo::Type::BOOL, - /*.accessor = */ nullptr,//[](void*)->void*{return nullptr;}, - /*.byte_offset = */ 0, - /*.functions = */ {true, false, false, false, false}, - }, - { - /*.name = */ "Count", - /*.docs = */ "Number of things", - /*.type = */ ParameterInfo::Type::U8, - /*.accessor = */ nullptr, //[](void*)->void*{return nullptr;}, - /*.struct_offset = */ 1, - /*.functions = */ {true, true, false, false, false}, - } - }; - - bool enable = false; - uint8_t count = 0; - - auto asTuple() { return std::make_tuple(std::ref(enable), std::ref(count)); } - auto asTuple() const { return std::make_tuple(enable, count); } -}; - - - -} // namespace mip From f6778ede2d4bacddf9250ddd09f85f0736fce03b Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 25 Jun 2024 12:21:26 -0400 Subject: [PATCH 036/147] Commit WIP. --- examples/CSV/csv.cpp | 8 +- .../mip/metadata/definitions/commands_3dm.hpp | 56 +++++++++++--- .../metadata/definitions/commands_base.hpp | 20 ++++- src/cpp/mip/metadata/definitions/common.hpp | 75 +++++++++++++++++++ .../mip/metadata/definitions/data_sensor.hpp | 8 +- src/cpp/mip/metadata/mip_all_definitions.hpp | 1 + src/cpp/mip/metadata/mip_metadata.hpp | 6 +- src/cpp/mip/metadata/structures.hpp | 19 ++--- 8 files changed, 161 insertions(+), 32 deletions(-) create mode 100644 src/cpp/mip/metadata/definitions/common.hpp diff --git a/examples/CSV/csv.cpp b/examples/CSV/csv.cpp index 8f63bbb60..fddf7ab2a 100644 --- a/examples/CSV/csv.cpp +++ b/examples/CSV/csv.cpp @@ -1,7 +1,7 @@ #include "../example_utils.hpp" -#include "definitions.hpp" +#include #include @@ -13,7 +13,7 @@ volatile sig_atomic_t stop_flag = false; mip::Timestamp last_receive_time = 0; -mip::Definitions mipdefs; +mip::metadata::Definitions mipdefs; void signal_handler(int signum) { @@ -23,7 +23,7 @@ void signal_handler(int signum) void handleField(void*, const mip::FieldView& field, mip::Timestamp timestamp) { - printf("%lu: field 0x%02X%02X\n", timestamp, field.descriptorSet(), field.fieldDescriptor()); + printf("%zu: field 0x%02X%02X\n", timestamp, field.descriptorSet(), field.fieldDescriptor()); last_receive_time = timestamp; } @@ -33,7 +33,7 @@ int main(int argc, const char* argv[]) std::unique_ptr utils; try { utils = handleCommonArgs(argc, argv); - } catch(const std::underflow_error& ex) { + } catch(const std::underflow_error&) { return printCommonUsage(argv); } catch(const std::exception& ex) { fprintf(stderr, "Error: %s\n", ex.what()); diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index cd0760ee6..a9297a6c3 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -1,18 +1,56 @@ -#include "commands_3dm.hpp" +#include -#include +#include -namespace mip -{ -namespace commands_3dm +namespace mip::metadata { template<> -struct FieldInfo +struct MetadataFor { - sta + using Cmd = commands_3dm::MessageFormat; + + static constexpr inline FieldInfo value = { + /* .name = */ "MessageFormat", + /* .title = */ "Message Format", + /* .docs = */ "Sets up the message format.", + /* .parameters = */ { + utils::FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "desc_set", + /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", + /* .type = */ {Type::U8}, + /* .accessor = */ utils::access, + /* .byte_offset = */ 1, + /* .functions = */ ALL_FUNCTIONS, + }, + { + /* .name = */ "desc_set", + /* .docs = */ "Number of descriptors (limited by payload size)", + /* .type = */ {Type::U8}, + /* .accessor = */ utils::access, + /* .byte_offset = */ 2, + /* .functions = */ ALL_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "List of descriptors and decimations.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .byte_offset = */ 3, + /* .functions = */ ALL_FUNCTIONS, + /* .count = */ 0, + /* .counter_idx = */ 2, + }, + }, + /* .functions = */ ALL_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; }; -} // namespace commands_3dm -} // namespace mip +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index 0ea418d16..dbb335b10 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -9,11 +9,21 @@ namespace mip::metadata { template<> -struct MetadataForField +struct MetadataFor { using Cmd = commands_base::Ping; using Rsp = Cmd::Response; + static constexpr inline FieldInfo value = { + /* .name = */ "CommSpeed", + /* .title = */ "Comm Port Speed", + /* .docs = */ "Changes the comm port speed.", + /* .parameters = */ { + }, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; static constexpr inline const char* NAME = "Ping"; static constexpr inline const char* DOC_NAME = "Ping"; static constexpr CompositeDescriptor DESCRIPTOR = Cmd::DESCRIPTOR; @@ -23,7 +33,7 @@ struct MetadataForField template<> -struct MetadataForField +struct MetadataFor { using Cmd = commands_base::CommSpeed; //using Rsp = Cmd::Response; @@ -64,7 +74,11 @@ struct MetadataForField }; -static constexpr inline +static constexpr inline std::initializer_list ALL_BASE_COMMANDS = { + &MetadataForField::value, + &MetadataForField::value, +}; + } // namespace mip diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp new file mode 100644 index 000000000..a26b6c649 --- /dev/null +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -0,0 +1,75 @@ +#pragma once + +#include +#include + +#include + + +namespace mip::metadata +{ + +template<> +struct MetadataFor +{ + using type = DescriptorRate; + + static constexpr inline StructInfo value = { + .name = "DescriptorRate", + .title = "Descriptor Rate", + .docs = "Descriptor rate information", + .parameters = { + { + .name = "descriptor", + .docs = "MIP data descriptor", + .type = {Type::U8}, + .accessor = utils::access, + .byte_offset = 0, + }, + { + .name = "decimation", + .docs = "Decimation from the base rate", + .type = {Type::U16}, + .accessor = utils::access, + .byte_offset = 1, + }, + } + }; +}; + +template<> +struct MetadataFor +{ + using type = Vector3f; + + static constexpr inline StructInfo value = { + .name = "Vector3f", + .title = "3D Vector", + .docs = "Represents a 3D vector of floats.", + .parameters = { + { + .name = "x", + .docs = "X axis", + .type = {Type::FLOAT}, + .accessor = nullptr, + .byte_offset = 0, + }, + { + .name = "y", + .docs = "Y axis", + .type = {Type::FLOAT}, + .accessor = nullptr, + .byte_offset = 4, + }, + { + .name = "z", + .docs = "Z axis", + .type = {Type::FLOAT}, + .accessor = nullptr, + .byte_offset = 8, + }, + }, + }; +}; + +} // namespace mip::metadata diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index 2429d211d..dc1a328d1 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -9,7 +9,7 @@ namespace mip::metadata { template<> -struct MetadataForField +struct MetadataFor { using Field = data_sensor::ScaledAccel; @@ -34,7 +34,7 @@ struct MetadataForField }; template<> -struct MetadataForField +struct MetadataFor { using Field = data_sensor::ScaledGyro; @@ -60,8 +60,8 @@ struct MetadataForField static constexpr inline std::initializer_list ALL_SENSOR_DATA = { - &MetadataForField::value, - &MetadataForField::value, + &MetadataFor::value, + &MetadataFor::value, }; } // namespace mip diff --git a/src/cpp/mip/metadata/mip_all_definitions.hpp b/src/cpp/mip/metadata/mip_all_definitions.hpp index 1aef49488..30ea2aa01 100644 --- a/src/cpp/mip/metadata/mip_all_definitions.hpp +++ b/src/cpp/mip/metadata/mip_all_definitions.hpp @@ -10,6 +10,7 @@ namespace mip::metadata static constexpr inline std::initializer_list< const std::initializer_list* > ALL_COMMANDS = { &ALL_BASE_COMMANDS, + &ALL_3DM_COMMANDS, }; static constexpr inline std::initializer_list< const std::initializer_list* > ALL_DATA = { &ALL_SENSOR_DATA, diff --git a/src/cpp/mip/metadata/mip_metadata.hpp b/src/cpp/mip/metadata/mip_metadata.hpp index c82b4d994..9b57a671b 100644 --- a/src/cpp/mip/metadata/mip_metadata.hpp +++ b/src/cpp/mip/metadata/mip_metadata.hpp @@ -12,7 +12,7 @@ namespace mip::metadata // Type trait class to be specialized for each field type. template -struct MetadataForField; +struct MetadataFor; @@ -32,7 +32,7 @@ struct MetadataForField; template auto& get(typename EnableForFieldTypes::type& field) { - constexpr ParameterInfo& paramInfo = MetadataForField::PARAMETERS[I].type; + constexpr ParameterInfo& paramInfo = MetadataFor::PARAMETERS[I].type; using T = typename utils::ParamEnum::type; return *static_cast(paramInfo.accessor(&field)); } @@ -52,7 +52,7 @@ ParamType get(FieldType& field) template auto get(FieldType& field) { - const ParameterInfo& paramInfo = MetadataForField::PARAMETERS[ParameterIndex]; + const ParameterInfo& paramInfo = MetadataFor::PARAMETERS[ParameterIndex]; } diff --git a/src/cpp/mip/metadata/structures.hpp b/src/cpp/mip/metadata/structures.hpp index 1d8f06d6c..f01ab2549 100644 --- a/src/cpp/mip/metadata/structures.hpp +++ b/src/cpp/mip/metadata/structures.hpp @@ -75,15 +75,6 @@ struct BitfieldInfo : public EnumInfo {}; struct ParameterInfo; // Defined below -struct StructInfo -{ - const char* name = nullptr; - const char* title = nullptr; - const char* docs = nullptr; - std::initializer_list parameters; -}; - - struct FuncBits { constexpr FuncBits() = default; @@ -109,8 +100,18 @@ struct FuncBits uint8_t bits = 0x00; }; +static constexpr inline FuncBits ALL_FUNCTIONS = {true,true,true,true,true}; +static constexpr inline FuncBits NO_FUNCTIONS = {false, false, false, false, false}; +struct StructInfo +{ + const char* name = nullptr; + const char* title = nullptr; + const char* docs = nullptr; + std::initializer_list parameters; +}; + struct FieldInfo : public StructInfo { FuncBits functions = {false, false, false, false, false}; From faa59a4fd7761fb3cdea375e73b2dac8ae353b6e Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 25 Jun 2024 18:18:04 -0400 Subject: [PATCH 037/147] WIP implementing metadata (CSV example runs but isn't useful yet). --- CMakeLists.txt | 2 +- examples/CMakeLists.txt | 1 + examples/CSV/csv.cpp | 40 ++++++++++++++++++- src/cpp/microstrain/common/CMakeLists.txt | 2 + src/cpp/microstrain/common/serialization.hpp | 8 ++++ .../connections/recording/CMakeLists.txt | 2 + .../connections/serial/CMakeLists.txt | 2 + .../connections/tcp/CMakeLists.txt | 2 + src/cpp/mip/CMakeLists.txt | 17 +++++++- .../mip/metadata/definitions/commands_3dm.hpp | 11 +++-- .../metadata/definitions/commands_base.hpp | 20 ++++------ .../mip/metadata/definitions/data_sensor.hpp | 2 + src/cpp/mip/metadata/mip_definitions.cpp | 39 ++++++++++++++++++ src/cpp/mip/metadata/mip_definitions.hpp | 32 ++++++++++++--- src/cpp/mip/metadata/structures.hpp | 1 + 15 files changed, 157 insertions(+), 24 deletions(-) create mode 100644 src/cpp/mip/metadata/mip_definitions.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index f365d75f2..e7f210c48 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.10) set(CMAKE_CXX_STANDARD 20) -set(CMAKE_CXX_STANDARD_REQUIRED ON) +#set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_C_STANDARD 11) set(CMAKE_C_STANDARD_REQUIRED ON) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 6769a8506..cd2ed0526 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -49,6 +49,7 @@ if(MIP_USE_SERIAL OR MIP_USE_TCP) add_mip_example(WatchImu "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.cpp") add_mip_example(Threads "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/threading.cpp") add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp") + target_compile_features(CsvExample PUBLIC cxx_std_20) # Product-specific examples add_mip_example(GQ7_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") diff --git a/examples/CSV/csv.cpp b/examples/CSV/csv.cpp index fddf7ab2a..2bad47d94 100644 --- a/examples/CSV/csv.cpp +++ b/examples/CSV/csv.cpp @@ -4,6 +4,7 @@ #include #include +#include #include #include @@ -23,13 +24,50 @@ void signal_handler(int signum) void handleField(void*, const mip::FieldView& field, mip::Timestamp timestamp) { - printf("%zu: field 0x%02X%02X\n", timestamp, field.descriptorSet(), field.fieldDescriptor()); + const mip::metadata::FieldInfo* info = mipdefs.findField(field.descriptor()); + if(info) + { + printf("%zu: %s(", timestamp, info->name); + size_t i = 0; + for(const auto& param : info->parameters) + { + if(i>0) + fputs(", ", stdout); + + switch(param.type.type) + { + case mip::metadata::Type::BOOL: printf("%d", microstrain::read(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::U8: printf("%u", microstrain::read(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::S8: printf("%d", microstrain::read< int8_t >(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::U16: printf("%u", microstrain::read(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::S16: printf("%d", microstrain::read< int16_t>(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::U32: printf("%u", microstrain::read(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::S32: printf("%d", microstrain::read< int32_t>(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::U64: printf("%lu", microstrain::read(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::S64: printf("%ld", microstrain::read< int64_t>(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::FLOAT: printf("%f", microstrain::read(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::DOUBLE: printf("%f", microstrain::read(field.payload()+param.byte_offset)); break; + case mip::metadata::Type::STRUCT: printf("{}"); break; + case mip::metadata::Type::ENUM: printf("%s", "enum"); break; + case mip::metadata::Type::BITFIELD: printf("%s", "bits"); break; + case mip::metadata::Type::UNION: printf("%s", "union"); break; + default: printf("?"); break; + } + ++i; + } + fputs(")\n", stdout); + } + else + printf("%zu: field 0x%02X%02X\n", timestamp, field.descriptorSet(), field.fieldDescriptor()); + last_receive_time = timestamp; } int main(int argc, const char* argv[]) { + mipdefs.registerDefinitions(mip::metadata::ALL_SENSOR_DATA); + std::unique_ptr utils; try { utils = handleCommonArgs(argc, argv); diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index a69ab92ae..443413ed1 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -8,3 +8,5 @@ target_sources(microstrain_common PUBLIC logging.hpp platform.hpp ) + +target_compile_features(microstrain_common PUBLIC cxx_std_11) diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index 0fa2133fc..05356bd6a 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -105,6 +105,14 @@ typename std::enable_if::value && sizeof(T)==8, size_t>::t return sizeof(T); } +template +T read(const uint8_t* buffer) +{ + T value; + read(buffer, value); + return value; +} + class Serializer { diff --git a/src/cpp/microstrain/connections/recording/CMakeLists.txt b/src/cpp/microstrain/connections/recording/CMakeLists.txt index 7484ebaf6..006fa7a77 100644 --- a/src/cpp/microstrain/connections/recording/CMakeLists.txt +++ b/src/cpp/microstrain/connections/recording/CMakeLists.txt @@ -7,3 +7,5 @@ add_library(microstrain_recording_connection ) target_link_libraries(microstrain_recording_connection PUBLIC microstrain_common) + +target_compile_features(microstrain_recording_connection PUBLIC cxx_std_11) diff --git a/src/cpp/microstrain/connections/serial/CMakeLists.txt b/src/cpp/microstrain/connections/serial/CMakeLists.txt index f16d5a4c3..2a4aec372 100644 --- a/src/cpp/microstrain/connections/serial/CMakeLists.txt +++ b/src/cpp/microstrain/connections/serial/CMakeLists.txt @@ -7,3 +7,5 @@ target_sources(microstrain_serial serial_connection.hpp ../connection.hpp ) + +target_compile_features(microstrain_serial PUBLIC cxx_std_11) diff --git a/src/cpp/microstrain/connections/tcp/CMakeLists.txt b/src/cpp/microstrain/connections/tcp/CMakeLists.txt index 0e5df794c..d4b8c64c5 100644 --- a/src/cpp/microstrain/connections/tcp/CMakeLists.txt +++ b/src/cpp/microstrain/connections/tcp/CMakeLists.txt @@ -7,3 +7,5 @@ target_sources(microstrain_socket tcp_connection.hpp ../connection.hpp ) + +target_compile_features(microstrain_socket PUBLIC cxx_std_11) diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index 9ec2e68b2..4cf715271 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -13,6 +13,8 @@ target_sources(mip PUBLIC mip_serialization.hpp ) +target_compile_features(mip PUBLIC cxx_std_11) + get_target_property(MIPDEFS mip definitions) set(MIPDEF_HEADERS ${MIPDEFS}) @@ -26,4 +28,17 @@ if(MICROSTRAIN_CMAKE_DEBUG) message("C++ definitions = ${MIPDEF_SOURCES}") endif() -target_sources(mip PUBLIC ${MIPDEF_SOURCES}) +set(META_SOURCES + metadata/mip_all_definitions.hpp + metadata/mip_definitions.hpp + metadata/mip_definitions.cpp + metadata/mip_metadata.hpp + metadata/structures.hpp + metadata/utils.hpp + metadata/definitions/commands_base.hpp + metadata/definitions/commands_3dm.hpp + metadata/definitions/data_sensor.hpp + metadata/definitions/common.hpp +) + +target_sources(mip PUBLIC ${MIPDEF_SOURCES} ${META_SOURCES}) diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index a9297a6c3..eb575c3b0 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -1,4 +1,6 @@ +#include "common.hpp" + #include #include @@ -9,7 +11,7 @@ namespace mip::metadata template<> struct MetadataFor { - using Cmd = commands_3dm::MessageFormat; + using type = commands_3dm::MessageFormat; static constexpr inline FieldInfo value = { /* .name = */ "MessageFormat", @@ -21,7 +23,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", /* .type = */ {Type::U8}, - /* .accessor = */ utils::access, + /* .accessor = */ utils::access, /* .byte_offset = */ 1, /* .functions = */ ALL_FUNCTIONS, }, @@ -29,7 +31,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8}, - /* .accessor = */ utils::access, + /* .accessor = */ utils::access, /* .byte_offset = */ 2, /* .functions = */ ALL_FUNCTIONS, /* .count = */ 1, @@ -39,13 +41,14 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "List of descriptors and decimations.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ utils::access, /* .byte_offset = */ 3, /* .functions = */ ALL_FUNCTIONS, /* .count = */ 0, /* .counter_idx = */ 2, }, }, + /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ ALL_FUNCTIONS, /* .proprietary = */ false, /* .response = */ nullptr, diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index dbb335b10..086288341 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -11,8 +11,7 @@ namespace mip::metadata template<> struct MetadataFor { - using Cmd = commands_base::Ping; - using Rsp = Cmd::Response; + using type = commands_base::Ping; static constexpr inline FieldInfo value = { /* .name = */ "CommSpeed", @@ -20,22 +19,18 @@ struct MetadataFor /* .docs = */ "Changes the comm port speed.", /* .parameters = */ { }, + /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, /* .proprietary = */ false, /* .response = */ nullptr, }; - static constexpr inline const char* NAME = "Ping"; - static constexpr inline const char* DOC_NAME = "Ping"; - static constexpr CompositeDescriptor DESCRIPTOR = Cmd::DESCRIPTOR; - - static constexpr inline std::initializer_list PARAMETERS = {}; }; template<> struct MetadataFor { - using Cmd = commands_base::CommSpeed; + using type = commands_base::CommSpeed; //using Rsp = Cmd::Response; // //static constexpr inline const char* NAME = "CommSpeed"; @@ -48,7 +43,7 @@ struct MetadataFor /* .name = */ "port", /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports.", /* .type = */ {Type::U8}, - /* .accessor = */ utils::access, + /* .accessor = */ utils::access, /* .byte_offset = */ 1, /* .functions = */ {true, true, true, true, true, true}, }, @@ -56,7 +51,7 @@ struct MetadataFor /* .name = */ "baud", /* .docs = */ "Port baud rate. Must be a supported rate.", /* .type = */ {Type::U32}, - /* .accessor = */ utils::access, + /* .accessor = */ utils::access, /* .byte_offset = */ 2, /* .functions = */ {true,false,false,false,false}, }, @@ -67,6 +62,7 @@ struct MetadataFor /* .title = */ "Comm Port Speed", /* .docs = */ "Changes the comm port speed.", /* .parameters = */ PARAMETERS, + /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true,true,true,true,true}, /* .proprietary = */ false, /* .response = */ nullptr, @@ -75,8 +71,8 @@ struct MetadataFor static constexpr inline std::initializer_list ALL_BASE_COMMANDS = { - &MetadataForField::value, - &MetadataForField::value, + &MetadataFor::value, + &MetadataFor::value, }; diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index dc1a328d1..bea7a3f56 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -27,6 +27,7 @@ struct MetadataFor ///* .functions = */ {false, false, false, false, false}, }, }, + /* .descriptor = */ Field::DESCRIPTOR, ///* .functions = */ {false,false,false,false,false}, ///* .proprietary = */ false, ///* .response = */ nullptr, @@ -52,6 +53,7 @@ struct MetadataFor ///* .functions = */ {false, false, false, false, false}, }, }, + /* .descriptor = */ Field::DESCRIPTOR, ///* .functions = */ {false,false,false,false,false}, ///* .proprietary = */ false, ///* .response = */ nullptr, diff --git a/src/cpp/mip/metadata/mip_definitions.cpp b/src/cpp/mip/metadata/mip_definitions.cpp new file mode 100644 index 000000000..093d07dec --- /dev/null +++ b/src/cpp/mip/metadata/mip_definitions.cpp @@ -0,0 +1,39 @@ + +#include "mip_definitions.hpp" + +namespace mip::metadata +{ + +void Definitions::registerField(const mip::metadata::FieldInfo* field) +{ + mFields.insert(field); +} + +void Definitions::registerDefinitions(std::initializer_list fields) +{ + mFields.insert(fields); +} + +//std::vector::const_iterator Definitions::findFieldIter(mip::CompositeDescriptor descriptor) const +//{ +// return std::lower_bound( +// mFields.begin(), mFields.end(), descriptor, +// [](const FieldInfo* info, CompositeDescriptor desc)->bool +// { +// return info->descriptor < desc; +// } +// ); +//} + +const FieldInfo* Definitions::findField(mip::CompositeDescriptor descriptor) const +{ + //auto it = findFieldIter(descriptor); + auto it = mFields.find(descriptor); + + if(it == mFields.end()) + return nullptr; + + return *it; +} + +} // namespace mip::metadata diff --git a/src/cpp/mip/metadata/mip_definitions.hpp b/src/cpp/mip/metadata/mip_definitions.hpp index f32bb448f..330be8a63 100644 --- a/src/cpp/mip/metadata/mip_definitions.hpp +++ b/src/cpp/mip/metadata/mip_definitions.hpp @@ -3,8 +3,8 @@ #include "mip_metadata.hpp" #include "../mip_descriptors.hpp" -#include -#include +#include +#include namespace mip::metadata @@ -13,13 +13,35 @@ namespace mip::metadata class Definitions { public: - const metadata::FieldInfo* findField(mip::CompositeDescriptor descriptor); + void registerField(const FieldInfo* field); + void registerDefinitions(std::initializer_list fields); - std::span findDescriptorSet(uint8_t descriptorSet); + const FieldInfo* findField(mip::CompositeDescriptor descriptor) const; + + //std::span findDescriptorSet(uint8_t descriptorSet) const; private: - //std::vector> mFields; + //std::vector::const_iterator findFieldIter(mip::CompositeDescriptor desc) const; + + struct Less + { + inline bool operator()(const FieldInfo *a, const FieldInfo *b) const + { + return a->descriptor < b->descriptor; + } + inline bool operator()(const FieldInfo *a, CompositeDescriptor desc) const + { + return a->descriptor < desc; + } + inline bool operator()(CompositeDescriptor desc, const FieldInfo *a) const + { + return desc < a->descriptor; + } + using is_transparent = void; + }; +private: + std::set mFields; }; diff --git a/src/cpp/mip/metadata/structures.hpp b/src/cpp/mip/metadata/structures.hpp index f01ab2549..bcdbd469c 100644 --- a/src/cpp/mip/metadata/structures.hpp +++ b/src/cpp/mip/metadata/structures.hpp @@ -114,6 +114,7 @@ struct StructInfo struct FieldInfo : public StructInfo { + CompositeDescriptor descriptor = {0x00, 0x00}; FuncBits functions = {false, false, false, false, false}; bool proprietary = false; FieldInfo* response = nullptr; From 7481868ffb062e7321dc88f2dea6b07ba2994760 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 27 Jun 2024 11:34:23 -0400 Subject: [PATCH 038/147] Stringify works for scaled accel data. --- examples/CMakeLists.txt | 2 +- examples/CSV/csv.cpp | 41 +-- examples/CSV/stringify.cpp | 254 ++++++++++++++++++ examples/CSV/stringify.hpp | 18 ++ src/cpp/microstrain/common/serialization.hpp | 19 +- .../mip/metadata/definitions/commands_3dm.hpp | 64 ++--- .../metadata/definitions/commands_base.hpp | 8 +- src/cpp/mip/metadata/definitions/common.hpp | 82 +++--- .../mip/metadata/definitions/data_sensor.hpp | 57 ++-- src/cpp/mip/metadata/mip_all_definitions.hpp | 9 +- src/cpp/mip/metadata/mip_definitions.cpp | 7 + src/cpp/mip/metadata/mip_definitions.hpp | 4 + src/cpp/mip/metadata/mip_metadata.hpp | 45 +++- src/cpp/mip/metadata/structures.hpp | 8 +- src/cpp/mip/metadata/utils.hpp | 62 ----- src/cpp/mip/mip_field.hpp | 8 + 16 files changed, 476 insertions(+), 212 deletions(-) create mode 100644 examples/CSV/stringify.cpp create mode 100644 examples/CSV/stringify.hpp diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index cd2ed0526..748762d2e 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -48,7 +48,7 @@ if(MIP_USE_SERIAL OR MIP_USE_TCP) add_mip_example(DeviceInfo "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/device_info.cpp") add_mip_example(WatchImu "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.cpp") add_mip_example(Threads "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/threading.cpp") - add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp") + add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") target_compile_features(CsvExample PUBLIC cxx_std_20) # Product-specific examples diff --git a/examples/CSV/csv.cpp b/examples/CSV/csv.cpp index 2bad47d94..1613a456d 100644 --- a/examples/CSV/csv.cpp +++ b/examples/CSV/csv.cpp @@ -1,10 +1,13 @@ #include "../example_utils.hpp" +#include "stringify.hpp" + #include #include #include +#include #include #include @@ -14,7 +17,7 @@ volatile sig_atomic_t stop_flag = false; mip::Timestamp last_receive_time = 0; -mip::metadata::Definitions mipdefs; +mip::metadata::Definitions mipdefs{mip::metadata::ALL_FIELDS}; void signal_handler(int signum) { @@ -24,41 +27,7 @@ void signal_handler(int signum) void handleField(void*, const mip::FieldView& field, mip::Timestamp timestamp) { - const mip::metadata::FieldInfo* info = mipdefs.findField(field.descriptor()); - if(info) - { - printf("%zu: %s(", timestamp, info->name); - size_t i = 0; - for(const auto& param : info->parameters) - { - if(i>0) - fputs(", ", stdout); - - switch(param.type.type) - { - case mip::metadata::Type::BOOL: printf("%d", microstrain::read(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::U8: printf("%u", microstrain::read(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::S8: printf("%d", microstrain::read< int8_t >(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::U16: printf("%u", microstrain::read(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::S16: printf("%d", microstrain::read< int16_t>(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::U32: printf("%u", microstrain::read(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::S32: printf("%d", microstrain::read< int32_t>(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::U64: printf("%lu", microstrain::read(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::S64: printf("%ld", microstrain::read< int64_t>(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::FLOAT: printf("%f", microstrain::read(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::DOUBLE: printf("%f", microstrain::read(field.payload()+param.byte_offset)); break; - case mip::metadata::Type::STRUCT: printf("{}"); break; - case mip::metadata::Type::ENUM: printf("%s", "enum"); break; - case mip::metadata::Type::BITFIELD: printf("%s", "bits"); break; - case mip::metadata::Type::UNION: printf("%s", "union"); break; - default: printf("?"); break; - } - ++i; - } - fputs(")\n", stdout); - } - else - printf("%zu: field 0x%02X%02X\n", timestamp, field.descriptorSet(), field.fieldDescriptor()); + std::printf("%zu: %s\n", timestamp, formatField(field).c_str()); last_receive_time = timestamp; } diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp new file mode 100644 index 000000000..2f8d4ef6c --- /dev/null +++ b/examples/CSV/stringify.cpp @@ -0,0 +1,254 @@ + + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + + +using namespace mip::metadata; + +extern Definitions mipdefs; + + +// std::string& appendFmt(std::string& base, const char* fmt, ...) +// { +// std::va_list args; +// va_start(args, fmt); +// int length = std::vsnprintf(nullptr, 0, fmt, args); +// va_end(args); +// +// if(length > 0) +// { +// size_t oldSize = base.length(); +// base.resize(oldSize + length); +// +// va_start(args, fmt); +// std::vsnprintf(base.data()+oldSize, length, fmt, args); +// va_end(args); +// +// base.resize(base.size()-1); // Remove extra terminating '\0' +// } +// } + + +// template +// std::string formatBasicType(const uint8_t* buffer, size_t length, size_t offset) +// { +// if(offset+sizeof(T) > length) +// return "?"; +// +// T value = microstrain::read(buffer); +// +// const char* fmt = nullptr; +// switch(utils::ParamType::value) +// { +// case Type::BOOL: +// return value ? "true" : "false"; +// +// case Type::U8: fmt = "%" PRIu8; break; +// case Type::S8: fmt = "%" PRIi8; break; +// case Type::U16: fmt = "%" PRIu16; break; +// case Type::S16: fmt = "%" PRIi16; break; +// case Type::U32: fmt = "%" PRIu32; break; +// case Type::S32: fmt = "%" PRIi32; break; +// case Type::U64: fmt = "%" PRIu64; break; +// case Type::S64: fmt = "%" PRIi64; break; +// +// case Type::FLOAT: fmt = "%f"; break; +// case Type::DOUBLE: fmt = "%f"; break; +// +// default: return "?"; +// } +// +// std::string tmp; +// return appendFmt(tmp, fmt, value); +// } + + + + +template +std::ostream& formatBasicType(std::ostream& ss, const uint8_t* buffer, size_t length, size_t offset) +{ + if(offset+sizeof(T) > length) + return ss << "?"; + + return ss << microstrain::read(buffer); +} + +static std::optional read(Type type, const uint8_t* buffer, size_t length, size_t offset) +{ + switch(type) + { + case Type::U8: return microstrain::extract(buffer, length, offset, false); + case Type::S8: return microstrain::extract< int8_t >(buffer, length, offset, false); + case Type::U16: return microstrain::extract(buffer, length, offset, false); + case Type::S16: return microstrain::extract< int32_t>(buffer, length, offset, false); + case Type::U32: return microstrain::extract(buffer, length, offset, false); + case Type::S32: return microstrain::extract< int64_t>(buffer, length, offset, false); + case Type::U64: return microstrain::extract(buffer, length, offset, false); + case Type::S64: return microstrain::extract< int64_t>(buffer, length, offset, false); + default: return std::nullopt; + } +} + +std::ostream& format(std::ostream& ss, const EnumInfo* info, const uint8_t* buffer, size_t length, size_t offset=0) +{ + if(!info) + return ss << ""; + + std::optional value = read(info->type, buffer, length, offset); + + if(!value) + return ss << "?"; + + auto it = std::find_if( + info->entries.begin(), info->entries.end(), + [value](const auto& entry){ return entry.value == value; } + ); + const char* name = (it != info->entries.end()) ? it->name : "?"; + + return ss << *value << '(' << name << ')'; +} + +std::ostream& format(std::ostream& ss, const BitfieldInfo* info, const uint8_t* buffer, size_t length, size_t offset) +{ + if(!info) + return ss << ""; + + std::optional value = read(info->type, buffer, length, offset); + if(!value) + return ss << "?"; + + ss << '{'; + size_t i=0; + for(const auto& entry : info->entries) + { + if(i > 0) + ss << ", "; + + ss << entry.name << '='; + + const size_t firstBit = std::countl_zero(entry.value); + ss << ((*value & entry.value) >> firstBit); + + i++; + } + ss << '}'; + return ss; +} + +std::ostream& format(std::ostream& ss, const StructInfo* info, const uint8_t* buffer, size_t length, size_t offset=0) +{ + if(!info) + return ss << ""; + + ss << '{'; + + size_t i=0; + for(const auto& param : info->parameters) + { + if(i > 0) + ss << ", "; + + ss << param.name << '='; + + switch(param.type.type) + { + case Type::NONE: + return ss << "-"; + + case Type::BOOL: formatBasicType(ss, buffer, length, param.byte_offset); break; + case Type::U8: formatBasicType(ss, buffer, length, param.byte_offset); break; + case Type::S8: formatBasicType< int8_t >(ss, buffer, length, param.byte_offset); break; + case Type::U16: formatBasicType(ss, buffer, length, param.byte_offset); break; + case Type::S16: formatBasicType< int16_t>(ss, buffer, length, param.byte_offset); break; + case Type::U32: formatBasicType(ss, buffer, length, param.byte_offset); break; + case Type::S32: formatBasicType< int32_t>(ss, buffer, length, param.byte_offset); break; + case Type::U64: formatBasicType(ss, buffer, length, param.byte_offset); break; + case Type::S64: formatBasicType< int64_t>(ss, buffer, length, param.byte_offset); break; + case Type::FLOAT: formatBasicType(ss, buffer, length, param.byte_offset); break; + case Type::DOUBLE: formatBasicType(ss, buffer, length, param.byte_offset); break; + + case Type::ENUM: + format( + ss, static_cast(param.type.infoPtr), + buffer, length, param.byte_offset + ); + break; + + case Type::BITFIELD: + if(!param.type.infoPtr) + ss << ""; + else if(param.byte_offset > length) + ss << "?"; + else + { + format( + ss, static_cast(param.type.infoPtr), + buffer, length, param.byte_offset + ); + } + break; + + case Type::STRUCT: + if(!param.type.infoPtr) + ss << ""; + else if(param.byte_offset > length) + ss << "{?}"; + else + { + format( + ss, static_cast(param.type.infoPtr), + buffer, length, param.byte_offset + ); + } + break; + + case Type::UNION: + ss << ""; + break; + } + + i++; + } + ss << '}'; + + return ss; +} + +std::ostream& format(std::ostream& ss, const mip::FieldView& field) +{ + const FieldInfo* info = mipdefs.findField(field.descriptor()); + + if(!info) + { + ss << "Unknown(%02X,%02x)["; + for(uint8_t i=0; iname; + format(ss, static_cast(info), field.payload(), field.payloadLength()); + } + return ss; +} + +std::string formatField(const mip::FieldView& field) +{ + std::stringstream ss; + + format(ss, field); + + return ss.str(); +} diff --git a/examples/CSV/stringify.hpp b/examples/CSV/stringify.hpp new file mode 100644 index 000000000..04823c02e --- /dev/null +++ b/examples/CSV/stringify.hpp @@ -0,0 +1,18 @@ +#pragma once + +#include + +namespace mip +{ + class FieldView; + + namespace metadata + { + class Definitions; + } +} + + +extern mip::metadata::Definitions mipdefs; + +std::string formatField(const mip::FieldView& field); diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index 05356bd6a..4efa5d473 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -5,7 +5,9 @@ #include #include - +#if __cpp_lib_optional >= 201606L +#include +#endif namespace microstrain { @@ -293,13 +295,26 @@ size_t extract(Serializer& serializer, const std::tuple -bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=true) +bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=false) { Serializer serializer(buffer, buffer_length, offset); extract(serializer, value); return exact_size ? serializer.noRemaining() : serializer.isOk(); } +// Returning by value (use read if length is guaranteed to be in range) +#if __cpp_lib_optional >= 201606L +template +std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bool exact_size=false) +{ + T value; + if(extract(value, buffer, length, offset, exact_size)) + return value; + else + return std::nullopt; +} +#endif + #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index eb575c3b0..7897a8cfd 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -13,41 +13,43 @@ struct MetadataFor { using type = commands_3dm::MessageFormat; + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "desc_set", + /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", + /* .type = */ {Type::U8}, + /* .accessor = */ utils::access, + /* .byte_offset = */ 1, + /* .functions = */ ALL_FUNCTIONS, + }, + { + /* .name = */ "desc_set", + /* .docs = */ "Number of descriptors (limited by payload size)", + /* .type = */ {Type::U8}, + /* .accessor = */ utils::access, + /* .byte_offset = */ 2, + /* .functions = */ ALL_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "List of descriptors and decimations.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .byte_offset = */ 3, + /* .functions = */ ALL_FUNCTIONS, + /* .count = */ 0, + /* .counter_idx = */ 2, + }, + }; + static constexpr inline FieldInfo value = { /* .name = */ "MessageFormat", /* .title = */ "Message Format", /* .docs = */ "Sets up the message format.", - /* .parameters = */ { - utils::FUNCTION_SELECTOR_PARAM, - { - /* .name = */ "desc_set", - /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", - /* .type = */ {Type::U8}, - /* .accessor = */ utils::access, - /* .byte_offset = */ 1, - /* .functions = */ ALL_FUNCTIONS, - }, - { - /* .name = */ "desc_set", - /* .docs = */ "Number of descriptors (limited by payload size)", - /* .type = */ {Type::U8}, - /* .accessor = */ utils::access, - /* .byte_offset = */ 2, - /* .functions = */ ALL_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ 0, - }, - { - /* .name = */ "descriptors", - /* .docs = */ "List of descriptors and decimations.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .byte_offset = */ 3, - /* .functions = */ ALL_FUNCTIONS, - /* .count = */ 0, - /* .counter_idx = */ 2, - }, - }, + /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ ALL_FUNCTIONS, /* .proprietary = */ false, diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index 086288341..06a86daab 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -14,9 +14,9 @@ struct MetadataFor using type = commands_base::Ping; static constexpr inline FieldInfo value = { - /* .name = */ "CommSpeed", - /* .title = */ "Comm Port Speed", - /* .docs = */ "Changes the comm port speed.", + /* .name = */ "Ping", + /* .title = */ "Ping", + /* .docs = */ "Pings the device.", /* .parameters = */ { }, /* .descriptor = */ type::DESCRIPTOR, @@ -38,7 +38,7 @@ struct MetadataFor //static constexpr CompositeDescriptor DESCRIPTOR = Cmd::DESCRIPTOR; static constexpr inline std::initializer_list PARAMETERS = { - utils::FUNCTION_SELECTOR_PARAM, + FUNCTION_SELECTOR_PARAM, { /* .name = */ "port", /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports.", diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index a26b6c649..70e97b2f8 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -14,26 +14,28 @@ struct MetadataFor { using type = DescriptorRate; + static constexpr inline ParameterInfo parameters[] = { + { + .name = "descriptor", + .docs = "MIP data descriptor", + .type = {Type::U8}, + .accessor = utils::access, + .byte_offset = 0, + }, + { + .name = "decimation", + .docs = "Decimation from the base rate", + .type = {Type::U16}, + .accessor = utils::access, + .byte_offset = 1, + }, + }; + static constexpr inline StructInfo value = { .name = "DescriptorRate", .title = "Descriptor Rate", .docs = "Descriptor rate information", - .parameters = { - { - .name = "descriptor", - .docs = "MIP data descriptor", - .type = {Type::U8}, - .accessor = utils::access, - .byte_offset = 0, - }, - { - .name = "decimation", - .docs = "Decimation from the base rate", - .type = {Type::U16}, - .accessor = utils::access, - .byte_offset = 1, - }, - } + .parameters = parameters, }; }; @@ -42,33 +44,35 @@ struct MetadataFor { using type = Vector3f; + static constexpr inline ParameterInfo parameters[] = { + { + .name = "x", + .docs = "X axis", + .type = {Type::FLOAT}, + .accessor = nullptr, + .byte_offset = 0, + }, + { + .name = "y", + .docs = "Y axis", + .type = {Type::FLOAT}, + .accessor = nullptr, + .byte_offset = 4, + }, + { + .name = "z", + .docs = "Z axis", + .type = {Type::FLOAT}, + .accessor = nullptr, + .byte_offset = 8, + }, + }; + static constexpr inline StructInfo value = { .name = "Vector3f", .title = "3D Vector", .docs = "Represents a 3D vector of floats.", - .parameters = { - { - .name = "x", - .docs = "X axis", - .type = {Type::FLOAT}, - .accessor = nullptr, - .byte_offset = 0, - }, - { - .name = "y", - .docs = "Y axis", - .type = {Type::FLOAT}, - .accessor = nullptr, - .byte_offset = 4, - }, - { - .name = "z", - .docs = "Z axis", - .type = {Type::FLOAT}, - .accessor = nullptr, - .byte_offset = 8, - }, - }, + .parameters = parameters, }; }; diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index bea7a3f56..855dfc207 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -1,6 +1,7 @@ #pragma once #include +#include "common.hpp" #include #include @@ -13,20 +14,22 @@ struct MetadataFor { using Field = data_sensor::ScaledAccel; - static constexpr inline FieldInfo value = { - /* .name = */ "CommSpeed", - /* .title = */ "Comm Port Speed", - /* .docs = */ "Changes the comm port speed.", - /* .parameters = */ { - { - /* .name = */ "scaled_accel", - /* .docs = */ "Scaled acceleration in [g]", - /* .type = */ {Type::STRUCT}, - /* .accessor = */ utils::access, - ///* .byte_offset = */ 0, - ///* .functions = */ {false, false, false, false, false}, - }, + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scaled_accel", + /* .docs = */ "Scaled acceleration in [g]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + ///* .byte_offset = */ 0, + ///* .functions = */ {false, false, false, false, false}, }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "ScaledAccel", + /* .title = */ "Scaled Accel", + /* .docs = */ "Acceleration", + /* .parameters = */ parameters, /* .descriptor = */ Field::DESCRIPTOR, ///* .functions = */ {false,false,false,false,false}, ///* .proprietary = */ false, @@ -39,20 +42,22 @@ struct MetadataFor { using Field = data_sensor::ScaledGyro; - static constexpr inline FieldInfo value = { - /* .name = */ "CommSpeed", - /* .title = */ "Comm Port Speed", - /* .docs = */ "Changes the comm port speed.", - /* .parameters = */ { - { - /* .name = */ "scaled_gyro", - /* .docs = */ "Scaled angular rate in [rad/s]", - /* .type = */ {Type::STRUCT}, - /* .accessor = */ utils::access, - ///* .byte_offset = */ 0, - ///* .functions = */ {false, false, false, false, false}, - }, + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scaled_gyro", + /* .docs = */ "Scaled angular rate in [rad/s]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + ///* .byte_offset = */ 0, + ///* .functions = */ {false, false, false, false, false}, }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "ScaledGyro", + /* .title = */ "Scaled Gyro", + /* .docs = */ "Angular rate of rotation.", + /* .parameters = */ parameters, /* .descriptor = */ Field::DESCRIPTOR, ///* .functions = */ {false,false,false,false,false}, ///* .proprietary = */ false, diff --git a/src/cpp/mip/metadata/mip_all_definitions.hpp b/src/cpp/mip/metadata/mip_all_definitions.hpp index 30ea2aa01..218674a4e 100644 --- a/src/cpp/mip/metadata/mip_all_definitions.hpp +++ b/src/cpp/mip/metadata/mip_all_definitions.hpp @@ -10,12 +10,19 @@ namespace mip::metadata static constexpr inline std::initializer_list< const std::initializer_list* > ALL_COMMANDS = { &ALL_BASE_COMMANDS, - &ALL_3DM_COMMANDS, + // &ALL_3DM_COMMANDS, }; static constexpr inline std::initializer_list< const std::initializer_list* > ALL_DATA = { &ALL_SENSOR_DATA, }; +static constexpr inline std::initializer_list< const std::initializer_list< const FieldInfo* >* > ALL_FIELDS = { + // Commands + &ALL_BASE_COMMANDS, + // &ALL_3DM_COMMANDS, + // Data + &ALL_SENSOR_DATA, +}; } // namespace mip diff --git a/src/cpp/mip/metadata/mip_definitions.cpp b/src/cpp/mip/metadata/mip_definitions.cpp index 093d07dec..ba57be9db 100644 --- a/src/cpp/mip/metadata/mip_definitions.cpp +++ b/src/cpp/mip/metadata/mip_definitions.cpp @@ -14,6 +14,13 @@ void Definitions::registerDefinitions(std::initializer_list f mFields.insert(fields); } +void Definitions::registerDefinitions( + const std::initializer_list< const std::initializer_list* >& fields) +{ + for(const auto* sublist : fields) + registerDefinitions(*sublist); +} + //std::vector::const_iterator Definitions::findFieldIter(mip::CompositeDescriptor descriptor) const //{ // return std::lower_bound( diff --git a/src/cpp/mip/metadata/mip_definitions.hpp b/src/cpp/mip/metadata/mip_definitions.hpp index 330be8a63..aeebd03ec 100644 --- a/src/cpp/mip/metadata/mip_definitions.hpp +++ b/src/cpp/mip/metadata/mip_definitions.hpp @@ -13,8 +13,12 @@ namespace mip::metadata class Definitions { public: + Definitions() = default; + Definitions(const std::initializer_list*>& fields) { registerDefinitions(fields); } + void registerField(const FieldInfo* field); void registerDefinitions(std::initializer_list fields); + void registerDefinitions(const std::initializer_list*>& fields); const FieldInfo* findField(mip::CompositeDescriptor descriptor) const; diff --git a/src/cpp/mip/metadata/mip_metadata.hpp b/src/cpp/mip/metadata/mip_metadata.hpp index 9b57a671b..041379fe7 100644 --- a/src/cpp/mip/metadata/mip_metadata.hpp +++ b/src/cpp/mip/metadata/mip_metadata.hpp @@ -10,11 +10,48 @@ namespace mip::metadata { -// Type trait class to be specialized for each field type. +// Type trait class to be specialized for each field/struct/etc. template struct MetadataFor; +template<> +struct MetadataFor +{ + using type = FunctionSelector; + + static constexpr EnumInfo::Entry entries[] = { + { "WRITE", (uint8_t)FunctionSelector::WRITE }, + { "READ", (uint8_t)FunctionSelector::READ }, + { "SAVE", (uint8_t)FunctionSelector::SAVE }, + { "LOAD", (uint8_t)FunctionSelector::LOAD }, + { "DEFAULT", (uint8_t)FunctionSelector::RESET }, + }; + + static constexpr inline EnumInfo value = { + .name = "FunctionSelector", + .docs = "", + .type = Type::U8, + .entries = entries, + }; +}; + +inline void* accessFunctionSelector(void* p) { return static_cast(p); } + +static constexpr inline ParameterInfo FUNCTION_SELECTOR_PARAM = { + /* .name = */ "function", + /* .docs = */ "Standard MIP function selector", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ accessFunctionSelector, + /* .byte_offset = */ 0, + /* .functions = */ {true,true,true,true,true}, + /* .count = default */ + /* .counter_idx = default */ + /* .union_index = default */ + /* .union_value = default */ +}; + + // template struct ParamEnum; // template<> struct ParamEnum : @@ -38,12 +75,6 @@ auto& get(typename EnableForFieldTypes::type& field) } -namespace utils -{ -} - - - template ParamType get(FieldType& field) { diff --git a/src/cpp/mip/metadata/structures.hpp b/src/cpp/mip/metadata/structures.hpp index bcdbd469c..b7c96d245 100644 --- a/src/cpp/mip/metadata/structures.hpp +++ b/src/cpp/mip/metadata/structures.hpp @@ -2,7 +2,7 @@ #include -#include +#include #include @@ -54,6 +54,8 @@ struct TypeInfo // const BitfieldInfo *bi; // const UnionInfo *ui; //}; + + bool isBasicType() const { return type <= Type::DOUBLE; } }; struct EnumInfo @@ -67,7 +69,7 @@ struct EnumInfo const char* name = nullptr; const char* docs = nullptr; Type type = Type::NONE; - std::initializer_list entries; + std::span entries; }; struct BitfieldInfo : public EnumInfo {}; @@ -109,7 +111,7 @@ struct StructInfo const char* name = nullptr; const char* title = nullptr; const char* docs = nullptr; - std::initializer_list parameters; + std::span parameters; }; struct FieldInfo : public StructInfo diff --git a/src/cpp/mip/metadata/utils.hpp b/src/cpp/mip/metadata/utils.hpp index a3fb0ee82..0c723c5c3 100644 --- a/src/cpp/mip/metadata/utils.hpp +++ b/src/cpp/mip/metadata/utils.hpp @@ -57,66 +57,4 @@ void* access(void* p) } -static constexpr inline EnumInfo FUNCTION_SELECTOR_ENUM = { - .name = "FunctionSelector", - .docs = "", - .type = Type::U8, - .entries = { - { "WRITE", (uint8_t)FunctionSelector::WRITE }, - { "READ", (uint8_t)FunctionSelector::READ }, - { "SAVE", (uint8_t)FunctionSelector::SAVE }, - { "LOAD", (uint8_t)FunctionSelector::LOAD }, - { "DEFAULT", (uint8_t)FunctionSelector::RESET }, - } -}; - -inline void* accessFunctionSelector(void* p) { return static_cast(p); } - -static constexpr inline ParameterInfo FUNCTION_SELECTOR_PARAM = { - /* .name = */ "function", - /* .docs = */ "Standard MIP function selector", - /* .type = */ {Type::ENUM, (const void*)&FUNCTION_SELECTOR_ENUM}, - /* .accessor = */ accessFunctionSelector, - /* .byte_offset = */ 0, - /* .functions = */ {true,true,true,true,true}, - /* .count = default */ - /* .counter_idx = default */ - /* .union_index = default */ - /* .union_value = default */ -}; - -//template -//constexpr ParameterInfo makeFunctionSelectorParam() -//{ -// return { -// /* .name = */ "function", -// /* .docs = */ "Standard MIP function selector", -// /* .type = */ {Type::ENUM, &FUNCTION_SELECTOR_ENUM_INFO}, -// /* .accessor = */ utils::access, -// /* .byte_offset = */ 0, -// /* .functions = */ {true,true,true,true,true}, -// /* .count = default */ -// /* .counter_idx = default */ -// /* .union_index = default */ -// /* .union_value = default */ -// }; -//} - -//template -//struct FunctionSelectorParam -//{ -// static constexpr inline ParameterInfo value = { -// /* .name = */ "function", -// /* .docs = */ "Standard MIP function selector", -// /* .type = */ Type::ENUM, -// /* .accessor = */ utils::access, -// /* .byte_offset = */ 0, // Always the first parameter. -// /* .functions = */ {true,true,true,true,true}, -// /* .count = default */ -// /* .counter_idx = default */ -// /* .union_index = default */ -// /* .union_value = default */ -// }; -//}; - } // namespace mip::metadata diff --git a/src/cpp/mip/mip_field.hpp b/src/cpp/mip/mip_field.hpp index 948372a6c..cf9214cd8 100644 --- a/src/cpp/mip/mip_field.hpp +++ b/src/cpp/mip/mip_field.hpp @@ -8,6 +8,10 @@ #include +#if __cpp_lib_span >= 202002L +#include +#endif + namespace mip { @@ -56,6 +60,10 @@ class FieldView : public C::mip_field_view uint8_t operator[](unsigned int index) const { return payload(index); } +#if __cpp_lib_span >= 202002L + std::span payloadSpan() const { return {payload(), payloadLength()}; } +#endif + ///@copydoc mip_field_is_valid bool isValid() const { return C::mip_field_is_valid(this); } From 690b195980625c4a21aafa8a7be2b47e5bd862c5 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 27 Jun 2024 12:16:51 -0400 Subject: [PATCH 039/147] Document stringification and add union handler function (WIP). --- examples/CSV/stringify.cpp | 220 ++++++++++++++++------------ src/cpp/mip/metadata/structures.hpp | 2 + 2 files changed, 132 insertions(+), 90 deletions(-) diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp index 2f8d4ef6c..1aa620b29 100644 --- a/examples/CSV/stringify.cpp +++ b/examples/CSV/stringify.cpp @@ -18,63 +18,16 @@ using namespace mip::metadata; extern Definitions mipdefs; -// std::string& appendFmt(std::string& base, const char* fmt, ...) -// { -// std::va_list args; -// va_start(args, fmt); -// int length = std::vsnprintf(nullptr, 0, fmt, args); -// va_end(args); -// -// if(length > 0) -// { -// size_t oldSize = base.length(); -// base.resize(oldSize + length); -// -// va_start(args, fmt); -// std::vsnprintf(base.data()+oldSize, length, fmt, args); -// va_end(args); -// -// base.resize(base.size()-1); // Remove extra terminating '\0' -// } -// } - - -// template -// std::string formatBasicType(const uint8_t* buffer, size_t length, size_t offset) -// { -// if(offset+sizeof(T) > length) -// return "?"; -// -// T value = microstrain::read(buffer); -// -// const char* fmt = nullptr; -// switch(utils::ParamType::value) -// { -// case Type::BOOL: -// return value ? "true" : "false"; -// -// case Type::U8: fmt = "%" PRIu8; break; -// case Type::S8: fmt = "%" PRIi8; break; -// case Type::U16: fmt = "%" PRIu16; break; -// case Type::S16: fmt = "%" PRIi16; break; -// case Type::U32: fmt = "%" PRIu32; break; -// case Type::S32: fmt = "%" PRIi32; break; -// case Type::U64: fmt = "%" PRIu64; break; -// case Type::S64: fmt = "%" PRIi64; break; -// -// case Type::FLOAT: fmt = "%f"; break; -// case Type::DOUBLE: fmt = "%f"; break; -// -// default: return "?"; -// } -// -// std::string tmp; -// return appendFmt(tmp, fmt, value); -// } - - - - +//////////////////////////////////////////////////////////////////////////////// +///@brief Format an arithmetic type (including bool) from buffer to a string. +/// +///@param ss Output stream +///@param buffer Data buffer +///@param length Length of data buffer +///@param offset Offset into data buffer where value is stored (may be out of range) +/// +///@returns ss +/// template std::ostream& formatBasicType(std::ostream& ss, const uint8_t* buffer, size_t length, size_t offset) { @@ -84,7 +37,18 @@ std::ostream& formatBasicType(std::ostream& ss, const uint8_t* buffer, size_t le return ss << microstrain::read(buffer); } -static std::optional read(Type type, const uint8_t* buffer, size_t length, size_t offset) +//////////////////////////////////////////////////////////////////////////////// +///@brief Read an integral value from the raw buffer. +/// +///@param type Real type of the data in the buffer. Used for size. +///@param buffer Data buffer +///@param length Length of data buffer +///@param offset Offset into data buffer where value is stored (may be out of range) +/// +///@returns A uint64_t containing the value. All smaller integers are converted to this type. +///@returns std::nullopt (no value) if the offset/size is beyond the end of the buffer. +/// +static std::optional readIntegralValue(Type type, const uint8_t* buffer, size_t length, size_t offset) { switch(type) { @@ -100,12 +64,23 @@ static std::optional read(Type type, const uint8_t* buffer, size_t len } } -std::ostream& format(std::ostream& ss, const EnumInfo* info, const uint8_t* buffer, size_t length, size_t offset=0) +//////////////////////////////////////////////////////////////////////////////// +///@brief Format enum from buffer to a string. +/// +///@param ss Output stream +///@param info Enum metadata (may be NULL) +///@param buffer Data buffer +///@param length Length of data buffer +///@param offset Offset into data buffer where value is stored +/// +///@returns ss +/// +std::ostream& formatEnum(std::ostream& ss, const EnumInfo* info, const uint8_t* buffer, size_t length, size_t offset= 0) { if(!info) return ss << ""; - std::optional value = read(info->type, buffer, length, offset); + std::optional value = readIntegralValue(info->type, buffer, length, offset); if(!value) return ss << "?"; @@ -119,12 +94,24 @@ std::ostream& format(std::ostream& ss, const EnumInfo* info, const uint8_t* buff return ss << *value << '(' << name << ')'; } -std::ostream& format(std::ostream& ss, const BitfieldInfo* info, const uint8_t* buffer, size_t length, size_t offset) +//////////////////////////////////////////////////////////////////////////////// +///@brief Format bitfield from buffer to a string. +/// +///@param ss Output stream +///@param info Bitfield metadata (may be NULL) +///@param buffer Data buffer +///@param length Length of data buffer +///@param offset Offset into data buffer where value is stored (may be out of range) +/// +///@returns ss +/// +std::ostream& formatBitfield(std::ostream& ss, const BitfieldInfo* info, const uint8_t* buffer, size_t length, size_t offset) { if(!info) return ss << ""; - std::optional value = read(info->type, buffer, length, offset); + std::optional value = readIntegralValue(info->type, buffer, length, offset); + if(!value) return ss << "?"; @@ -146,10 +133,59 @@ std::ostream& format(std::ostream& ss, const BitfieldInfo* info, const uint8_t* return ss; } -std::ostream& format(std::ostream& ss, const StructInfo* info, const uint8_t* buffer, size_t length, size_t offset=0) +//////////////////////////////////////////////////////////////////////////////// +///@brief Format union from buffer to a string. +/// +///@param ss Output stream +///@param info Union metadata (may be NULL) +///@param parent Struct metadata of the parent object (for parameter access). +///@param buffer Data buffer +///@param length Length of data buffer +///@param offset Offset into data buffer where value is stored (may be out of range) +/// +///@returns ss +/// +std::ostream& formatUnion(std::ostream& ss, const UnionInfo* info, const StructInfo& parent, const uint8_t* buffer, size_t length, size_t offset=0) +{ + if(!info) + return ss << ""; + if(offset > length) + return ss << "?"; + + ss << info->name << '{'; + + // Todo + // const ParameterInfo* param = nullptr; + // + // for(const auto& p : info->parameters) + // { + // if(p.union_index < parent.parameters.size()) + // { + // + // } + // } + + ss << '}'; + return ss; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Format struct from buffer to a string. +/// +///@param ss Output stream +///@param info Struct metadata (may be NULL) +///@param buffer Data buffer +///@param length Length of data buffer +///@param offset Offset into data buffer where value is stored (may be out of range) +/// +///@returns ss +/// +std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, const uint8_t* buffer, size_t length, size_t offset=0) { if(!info) return ss << ""; + if(offset > length) + return ss << "?"; ss << '{'; @@ -179,42 +215,31 @@ std::ostream& format(std::ostream& ss, const StructInfo* info, const uint8_t* bu case Type::DOUBLE: formatBasicType(ss, buffer, length, param.byte_offset); break; case Type::ENUM: - format( + formatEnum( ss, static_cast(param.type.infoPtr), buffer, length, param.byte_offset ); break; case Type::BITFIELD: - if(!param.type.infoPtr) - ss << ""; - else if(param.byte_offset > length) - ss << "?"; - else - { - format( - ss, static_cast(param.type.infoPtr), - buffer, length, param.byte_offset - ); - } + formatBitfield( + ss, static_cast(param.type.infoPtr), + buffer, length, param.byte_offset + ); break; case Type::STRUCT: - if(!param.type.infoPtr) - ss << ""; - else if(param.byte_offset > length) - ss << "{?}"; - else - { - format( - ss, static_cast(param.type.infoPtr), - buffer, length, param.byte_offset - ); - } + formatStruct( + ss, static_cast(param.type.infoPtr), + buffer, length, param.byte_offset + ); break; case Type::UNION: - ss << ""; + formatUnion( + ss, static_cast(param.type.infoPtr), *info, + buffer, length, param.byte_offset + ); break; } @@ -225,7 +250,15 @@ std::ostream& format(std::ostream& ss, const StructInfo* info, const uint8_t* bu return ss; } -std::ostream& format(std::ostream& ss, const mip::FieldView& field) +//////////////////////////////////////////////////////////////////////////////// +///@brief Format mip field from buffer to a string. +/// +///@param ss Output stream +///@param field FieldView containing data to print +/// +///@returns ss +/// +std::ostream& formatField(std::ostream& ss, const mip::FieldView& field) { const FieldInfo* info = mipdefs.findField(field.descriptor()); @@ -239,16 +272,23 @@ std::ostream& format(std::ostream& ss, const mip::FieldView& field) else { ss << info->name; - format(ss, static_cast(info), field.payload(), field.payloadLength()); + formatStruct(ss, static_cast(info), field.payload(), field.payloadLength()); } return ss; } +//////////////////////////////////////////////////////////////////////////////// +///@brief Format bitfield to a string. +/// +///@param field FieldView holding the buffer containing the field data. +/// +///@returns A human and machine-readable string. +/// std::string formatField(const mip::FieldView& field) { std::stringstream ss; - format(ss, field); + formatField(ss, field); return ss.str(); } diff --git a/src/cpp/mip/metadata/structures.hpp b/src/cpp/mip/metadata/structures.hpp index b7c96d245..ca68e7bb4 100644 --- a/src/cpp/mip/metadata/structures.hpp +++ b/src/cpp/mip/metadata/structures.hpp @@ -114,6 +114,8 @@ struct StructInfo std::span parameters; }; +struct UnionInfo : public StructInfo {}; + struct FieldInfo : public StructInfo { CompositeDescriptor descriptor = {0x00, 0x00}; From 777b660184e8f455e2d50f42a935c17b8320e3fb Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 27 Jun 2024 14:44:10 -0400 Subject: [PATCH 040/147] Fix missing functions for (de)serializing mip fields. --- src/c/mip/CMakeLists.txt | 2 + src/c/mip/definitions/commands_3dm.c | 4 +- src/c/mip/definitions/commands_aiding.c | 4 +- src/c/mip/definitions/commands_base.c | 4 +- src/c/mip/definitions/commands_filter.c | 4 +- src/c/mip/definitions/commands_gnss.c | 4 +- src/c/mip/definitions/commands_rtk.c | 4 +- src/c/mip/definitions/commands_system.c | 4 +- src/c/mip/definitions/data_filter.c | 4 +- src/c/mip/definitions/data_gnss.c | 4 +- src/c/mip/definitions/data_sensor.c | 4 +- src/c/mip/definitions/data_shared.c | 4 +- src/c/mip/definitions/data_system.c | 4 +- src/c/mip/mip_field.c | 63 ----------------------- src/c/mip/mip_field.h | 2 - src/c/mip/mip_serialization.c | 65 ++++++++++++++++++++++++ src/c/mip/mip_serialization.h | 22 ++++++++ src/cpp/mip/metadata/mip_definitions.hpp | 30 +++++------ src/cpp/mip/mip_all.hpp | 2 +- 19 files changed, 128 insertions(+), 106 deletions(-) create mode 100644 src/c/mip/mip_serialization.c create mode 100644 src/c/mip/mip_serialization.h diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index 03ce316a9..6c43e3377 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -23,6 +23,8 @@ set(MIP_SOURCES mip_result.c mip_result.h mip_types.h + mip_serialization.c + mip_serialization.h definitions/common.c definitions/common.h mip_all.h diff --git a/src/c/mip/definitions/commands_3dm.c b/src/c/mip/definitions/commands_3dm.c index 31ff47976..0035e5175 100644 --- a/src/c/mip/definitions/commands_3dm.c +++ b/src/c/mip/definitions/commands_3dm.c @@ -1,8 +1,8 @@ #include "commands_3dm.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/commands_aiding.c b/src/c/mip/definitions/commands_aiding.c index 0f797dc99..fc2ee182c 100644 --- a/src/c/mip/definitions/commands_aiding.c +++ b/src/c/mip/definitions/commands_aiding.c @@ -1,8 +1,8 @@ #include "commands_aiding.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/commands_base.c b/src/c/mip/definitions/commands_base.c index f93efd25d..1f474e5b9 100644 --- a/src/c/mip/definitions/commands_base.c +++ b/src/c/mip/definitions/commands_base.c @@ -1,8 +1,8 @@ #include "commands_base.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/commands_filter.c b/src/c/mip/definitions/commands_filter.c index 2cf4ebf68..2f783650c 100644 --- a/src/c/mip/definitions/commands_filter.c +++ b/src/c/mip/definitions/commands_filter.c @@ -1,8 +1,8 @@ #include "commands_filter.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/commands_gnss.c b/src/c/mip/definitions/commands_gnss.c index fe574356f..9e32ec9c1 100644 --- a/src/c/mip/definitions/commands_gnss.c +++ b/src/c/mip/definitions/commands_gnss.c @@ -1,8 +1,8 @@ #include "commands_gnss.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/commands_rtk.c b/src/c/mip/definitions/commands_rtk.c index 99225678c..3e6a43441 100644 --- a/src/c/mip/definitions/commands_rtk.c +++ b/src/c/mip/definitions/commands_rtk.c @@ -1,8 +1,8 @@ #include "commands_rtk.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/commands_system.c b/src/c/mip/definitions/commands_system.c index 1e6cf5b16..998a8cae8 100644 --- a/src/c/mip/definitions/commands_system.c +++ b/src/c/mip/definitions/commands_system.c @@ -1,8 +1,8 @@ #include "commands_system.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/data_filter.c b/src/c/mip/definitions/data_filter.c index 411495637..2aea2720f 100644 --- a/src/c/mip/definitions/data_filter.c +++ b/src/c/mip/definitions/data_filter.c @@ -1,8 +1,8 @@ #include "data_filter.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/data_gnss.c b/src/c/mip/definitions/data_gnss.c index 72162ba2b..177db782a 100644 --- a/src/c/mip/definitions/data_gnss.c +++ b/src/c/mip/definitions/data_gnss.c @@ -1,8 +1,8 @@ #include "data_gnss.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/data_sensor.c b/src/c/mip/definitions/data_sensor.c index c910d2d05..cfb5c95c5 100644 --- a/src/c/mip/definitions/data_sensor.c +++ b/src/c/mip/definitions/data_sensor.c @@ -1,8 +1,8 @@ #include "data_sensor.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/data_shared.c b/src/c/mip/definitions/data_shared.c index b01dcdd2d..ae8e978ed 100644 --- a/src/c/mip/definitions/data_shared.c +++ b/src/c/mip/definitions/data_shared.c @@ -1,8 +1,8 @@ #include "data_shared.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/definitions/data_system.c b/src/c/mip/definitions/data_system.c index c77f45ba4..7f1ee5cc0 100644 --- a/src/c/mip/definitions/data_system.c +++ b/src/c/mip/definitions/data_system.c @@ -1,8 +1,8 @@ #include "data_system.h" -#include "microstrain/common/serialization.h" -#include "../mip_interface.h" +#include +#include #include diff --git a/src/c/mip/mip_field.c b/src/c/mip/mip_field.c index 95c13bcfa..d2d11ce31 100644 --- a/src/c/mip/mip_field.c +++ b/src/c/mip/mip_field.c @@ -235,66 +235,3 @@ bool mip_field_next_in_packet(mip_field_view* field, const mip_packet_view* pack return mip_field_is_valid(field); } - - - -//////////////////////////////////////////////////////////////////////////////// -///@brief Initializer a serialization struct for creation of a new field at the -/// end of the packet. -/// -///@note Call microstrain_serializer_finiish_new_field after the data has been serialized. -/// -///@note Only one new field per packet can be in progress at a time. -/// -///@param serializer -///@param packet -/// Allocate the new field on the end of this packet. -///@param field_descriptor -/// Field descriptor of the new field. -/// -void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor) -{ - assert(packet); - - serializer->_buffer = NULL; - serializer->_buffer_size = 0; - serializer->_offset = 0; - - const int length = mip_packet_alloc_field(packet, field_descriptor, 0, &serializer->_buffer); - - if( length >= 0 ) - serializer->_buffer_size = length; -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Call this after a new field allocated by microstrain_serializer_init_new_field -/// has been written. -/// -/// This will either finish the field, or abort it if the serializer failed. -/// -///@param serializer Must be created from microstrain_serializer_init_new_field. -///@param packet Must be the original packet. -/// -void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet_view* packet) -{ - assert(packet); - - if(microstrain_serializer_is_ok(serializer) ) - { - assert(serializer->_offset <= MIP_FIELD_LENGTH_MAX); // Payload too long! - mip_packet_realloc_last_field(packet, serializer->_buffer, (uint8_t) serializer->_offset); - } - else if( serializer->_buffer ) - mip_packet_cancel_last_field(packet, serializer->_buffer); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Initialize a serialization struct from a microstrain field payload. -/// -///@param serializer -///@param field -/// -void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field_view* field) -{ - microstrain_serializer_init_extraction(serializer, mip_field_payload(field), mip_field_payload_length(field)); -} diff --git a/src/c/mip/mip_field.h b/src/c/mip/mip_field.h index 992b1e705..9b06d62de 100644 --- a/src/c/mip/mip_field.h +++ b/src/c/mip/mip_field.h @@ -118,8 +118,6 @@ bool mip_field_next_in_packet(mip_field_view* field, const mip_packet_view* pack //////////////////////////////////////////////////////////////////////////////// /// -//void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field* field); - #ifdef __cplusplus } // namespace mip } // namespace C diff --git a/src/c/mip/mip_serialization.c b/src/c/mip/mip_serialization.c new file mode 100644 index 000000000..bade7a119 --- /dev/null +++ b/src/c/mip/mip_serialization.c @@ -0,0 +1,65 @@ + +#include "mip_serialization.h" +#include "mip_offsets.h" + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Initializer a serialization struct for creation of a new field at the +/// end of the packet. +/// +///@note Call microstrain_serializer_finiish_new_field after the data has been serialized. +/// +///@note Only one new field per packet can be in progress at a time. +/// +///@param serializer +///@param packet +/// Allocate the new field on the end of this packet. +///@param field_descriptor +/// Field descriptor of the new field. +/// +void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor) +{ + assert(packet); + + serializer->_buffer = NULL; + serializer->_buffer_size = 0; + serializer->_offset = 0; + + const int length = mip_packet_alloc_field(packet, field_descriptor, 0, &serializer->_buffer); + + if( length >= 0 ) + serializer->_buffer_size = length; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Call this after a new field allocated by microstrain_serializer_init_new_field +/// has been written. +/// +/// This will either finish the field, or abort it if the serializer failed. +/// +///@param serializer Must be created from microstrain_serializer_init_new_field. +///@param packet Must be the original packet. +/// +void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet_view* packet) +{ + assert(packet); + + if(microstrain_serializer_is_ok(serializer) ) + { + assert(serializer->_offset <= MIP_FIELD_LENGTH_MAX); // Payload too long! + mip_packet_realloc_last_field(packet, serializer->_buffer, (uint8_t) serializer->_offset); + } + else if( serializer->_buffer ) + mip_packet_cancel_last_field(packet, serializer->_buffer); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Initialize a serialization struct from a microstrain field payload. +/// +///@param serializer +///@param field +/// +void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field_view* field) +{ + microstrain_serializer_init_extraction(serializer, mip_field_payload(field), mip_field_payload_length(field)); +} diff --git a/src/c/mip/mip_serialization.h b/src/c/mip/mip_serialization.h new file mode 100644 index 000000000..0d813fd2a --- /dev/null +++ b/src/c/mip/mip_serialization.h @@ -0,0 +1,22 @@ +#pragma once + +#include "mip_field.h" + +#include + + +#ifdef __cplusplus +namespace mip{ +namespace C { +extern "C" { +#endif + +void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor); +void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet_view* packet); +void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field_view* field); + +#ifdef __cplusplus +} // namespace mip +} // namespace C +} // extern "C" +#endif diff --git a/src/cpp/mip/metadata/mip_definitions.hpp b/src/cpp/mip/metadata/mip_definitions.hpp index aeebd03ec..93f16cb63 100644 --- a/src/cpp/mip/metadata/mip_definitions.hpp +++ b/src/cpp/mip/metadata/mip_definitions.hpp @@ -12,21 +12,6 @@ namespace mip::metadata class Definitions { -public: - Definitions() = default; - Definitions(const std::initializer_list*>& fields) { registerDefinitions(fields); } - - void registerField(const FieldInfo* field); - void registerDefinitions(std::initializer_list fields); - void registerDefinitions(const std::initializer_list*>& fields); - - const FieldInfo* findField(mip::CompositeDescriptor descriptor) const; - - //std::span findDescriptorSet(uint8_t descriptorSet) const; - -private: - //std::vector::const_iterator findFieldIter(mip::CompositeDescriptor desc) const; - struct Less { inline bool operator()(const FieldInfo *a, const FieldInfo *b) const @@ -44,8 +29,21 @@ class Definitions using is_transparent = void; }; + using Container = std::set; + +public: + Definitions() = default; + Definitions(const std::initializer_list*>& fields) { registerDefinitions(fields); } + + void registerField(const FieldInfo* field); + void registerDefinitions(std::initializer_list fields); + void registerDefinitions(const std::initializer_list*>& fields); + + const FieldInfo* findField(mip::CompositeDescriptor descriptor) const; + + private: - std::set mFields; + Container mFields; }; diff --git a/src/cpp/mip/mip_all.hpp b/src/cpp/mip/mip_all.hpp index e1037403b..54c63d45e 100644 --- a/src/cpp/mip/mip_all.hpp +++ b/src/cpp/mip/mip_all.hpp @@ -7,7 +7,7 @@ #include "mip_packet.hpp" #include "mip_parser.hpp" -#include "mip_descriptors.h" +#include "mip_descriptors.hpp" //MIP Commands #include "definitions/commands_aiding.hpp" From 119298d77640c449a83333e6162d0a44c0bb965a Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 27 Jun 2024 17:09:50 -0400 Subject: [PATCH 041/147] Remove byte_offset from parameters as this can't be determined when variable-length arrays exist. --- examples/CSV/stringify.cpp | 92 +++++++++---------- src/cpp/microstrain/common/platform.hpp | 7 ++ src/cpp/microstrain/common/serialization.hpp | 44 ++++----- .../mip/metadata/definitions/commands_3dm.hpp | 3 - .../metadata/definitions/commands_base.hpp | 2 - src/cpp/mip/metadata/definitions/common.hpp | 5 - src/cpp/mip/metadata/mip_metadata.hpp | 2 +- src/cpp/mip/metadata/structures.hpp | 1 - 8 files changed, 73 insertions(+), 83 deletions(-) diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp index 1aa620b29..013d973db 100644 --- a/examples/CSV/stringify.cpp +++ b/examples/CSV/stringify.cpp @@ -11,7 +11,11 @@ #include #include #include +#include +#if __cpp_lib_optional < 201606L +#error "Needs optional support" +#endif using namespace mip::metadata; @@ -29,12 +33,13 @@ extern Definitions mipdefs; ///@returns ss /// template -std::ostream& formatBasicType(std::ostream& ss, const uint8_t* buffer, size_t length, size_t offset) +std::ostream& formatBasicType(std::ostream& ss, microstrain::Serializer& serializer) { - if(offset+sizeof(T) > length) + T value; + if(serializer.extract(value)) + return ss << value; + else return ss << "?"; - - return ss << microstrain::read(buffer); } //////////////////////////////////////////////////////////////////////////////// @@ -48,18 +53,18 @@ std::ostream& formatBasicType(std::ostream& ss, const uint8_t* buffer, size_t le ///@returns A uint64_t containing the value. All smaller integers are converted to this type. ///@returns std::nullopt (no value) if the offset/size is beyond the end of the buffer. /// -static std::optional readIntegralValue(Type type, const uint8_t* buffer, size_t length, size_t offset) +static std::optional readIntegralValue(Type type, microstrain::Serializer& serializer) { switch(type) { - case Type::U8: return microstrain::extract(buffer, length, offset, false); - case Type::S8: return microstrain::extract< int8_t >(buffer, length, offset, false); - case Type::U16: return microstrain::extract(buffer, length, offset, false); - case Type::S16: return microstrain::extract< int32_t>(buffer, length, offset, false); - case Type::U32: return microstrain::extract(buffer, length, offset, false); - case Type::S32: return microstrain::extract< int64_t>(buffer, length, offset, false); - case Type::U64: return microstrain::extract(buffer, length, offset, false); - case Type::S64: return microstrain::extract< int64_t>(buffer, length, offset, false); + case Type::U8: return microstrain::extract(serializer); + case Type::S8: return microstrain::extract< int8_t >(serializer); + case Type::U16: return microstrain::extract(serializer); + case Type::S16: return microstrain::extract< int32_t>(serializer); + case Type::U32: return microstrain::extract(serializer); + case Type::S32: return microstrain::extract< int64_t>(serializer); + case Type::U64: return microstrain::extract(serializer); + case Type::S64: return microstrain::extract< int64_t>(serializer); default: return std::nullopt; } } @@ -75,12 +80,12 @@ static std::optional readIntegralValue(Type type, const uint8_t* buffe /// ///@returns ss /// -std::ostream& formatEnum(std::ostream& ss, const EnumInfo* info, const uint8_t* buffer, size_t length, size_t offset= 0) +std::ostream& formatEnum(std::ostream& ss, const EnumInfo* info, microstrain::Serializer& serializer) { if(!info) return ss << ""; - std::optional value = readIntegralValue(info->type, buffer, length, offset); + std::optional value = readIntegralValue(info->type, serializer); if(!value) return ss << "?"; @@ -105,12 +110,12 @@ std::ostream& formatEnum(std::ostream& ss, const EnumInfo* info, const uint8_t* /// ///@returns ss /// -std::ostream& formatBitfield(std::ostream& ss, const BitfieldInfo* info, const uint8_t* buffer, size_t length, size_t offset) +std::ostream& formatBitfield(std::ostream& ss, const BitfieldInfo* info, microstrain::Serializer& serializer) { if(!info) return ss << ""; - std::optional value = readIntegralValue(info->type, buffer, length, offset); + std::optional value = readIntegralValue(info->type, serializer); if(!value) return ss << "?"; @@ -145,11 +150,11 @@ std::ostream& formatBitfield(std::ostream& ss, const BitfieldInfo* info, const u /// ///@returns ss /// -std::ostream& formatUnion(std::ostream& ss, const UnionInfo* info, const StructInfo& parent, const uint8_t* buffer, size_t length, size_t offset=0) +std::ostream& formatUnion(std::ostream& ss, const UnionInfo* info, const StructInfo& parent, microstrain::Serializer& serializer) { if(!info) return ss << ""; - if(offset > length) + if(serializer.isOverrun()) return ss << "?"; ss << info->name << '{'; @@ -180,11 +185,11 @@ std::ostream& formatUnion(std::ostream& ss, const UnionInfo* info, const StructI /// ///@returns ss /// -std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, const uint8_t* buffer, size_t length, size_t offset=0) +std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, microstrain::Serializer& serializer) { if(!info) return ss << ""; - if(offset > length) + if(serializer.isOverrun()) return ss << "?"; ss << '{'; @@ -202,44 +207,32 @@ std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, const uint8 case Type::NONE: return ss << "-"; - case Type::BOOL: formatBasicType(ss, buffer, length, param.byte_offset); break; - case Type::U8: formatBasicType(ss, buffer, length, param.byte_offset); break; - case Type::S8: formatBasicType< int8_t >(ss, buffer, length, param.byte_offset); break; - case Type::U16: formatBasicType(ss, buffer, length, param.byte_offset); break; - case Type::S16: formatBasicType< int16_t>(ss, buffer, length, param.byte_offset); break; - case Type::U32: formatBasicType(ss, buffer, length, param.byte_offset); break; - case Type::S32: formatBasicType< int32_t>(ss, buffer, length, param.byte_offset); break; - case Type::U64: formatBasicType(ss, buffer, length, param.byte_offset); break; - case Type::S64: formatBasicType< int64_t>(ss, buffer, length, param.byte_offset); break; - case Type::FLOAT: formatBasicType(ss, buffer, length, param.byte_offset); break; - case Type::DOUBLE: formatBasicType(ss, buffer, length, param.byte_offset); break; + case Type::BOOL: formatBasicType(ss, serializer); break; + case Type::U8: formatBasicType(ss, serializer); break; + case Type::S8: formatBasicType< int8_t >(ss, serializer); break; + case Type::U16: formatBasicType(ss, serializer); break; + case Type::S16: formatBasicType< int16_t>(ss, serializer); break; + case Type::U32: formatBasicType(ss, serializer); break; + case Type::S32: formatBasicType< int32_t>(ss, serializer); break; + case Type::U64: formatBasicType(ss, serializer); break; + case Type::S64: formatBasicType< int64_t>(ss, serializer); break; + case Type::FLOAT: formatBasicType(ss, serializer); break; + case Type::DOUBLE: formatBasicType(ss, serializer); break; case Type::ENUM: - formatEnum( - ss, static_cast(param.type.infoPtr), - buffer, length, param.byte_offset - ); + formatEnum(ss, static_cast(param.type.infoPtr), serializer); break; case Type::BITFIELD: - formatBitfield( - ss, static_cast(param.type.infoPtr), - buffer, length, param.byte_offset - ); + formatBitfield(ss, static_cast(param.type.infoPtr), serializer); break; case Type::STRUCT: - formatStruct( - ss, static_cast(param.type.infoPtr), - buffer, length, param.byte_offset - ); + formatStruct(ss, static_cast(param.type.infoPtr), serializer); break; case Type::UNION: - formatUnion( - ss, static_cast(param.type.infoPtr), *info, - buffer, length, param.byte_offset - ); + formatUnion(ss, static_cast(param.type.infoPtr), *info, serializer); break; } @@ -272,7 +265,8 @@ std::ostream& formatField(std::ostream& ss, const mip::FieldView& field) else { ss << info->name; - formatStruct(ss, static_cast(info), field.payload(), field.payloadLength()); + microstrain::Serializer serializer(field.payload(), field.payloadLength()); + formatStruct(ss, static_cast(info), serializer); } return ss; } diff --git a/src/cpp/microstrain/common/platform.hpp b/src/cpp/microstrain/common/platform.hpp index 02065cf59..7afede680 100644 --- a/src/cpp/microstrain/common/platform.hpp +++ b/src/cpp/microstrain/common/platform.hpp @@ -14,3 +14,10 @@ #else #define IF_CONSTEXPR if #endif + +#if __cpp_lib_optional >= 201606L || __cplusplus >= 201703L +#define HAS_OPTIONAL +#endif +#if __cpp_lib_span >= 202002L +#define HAS_SPAN +#endif diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index 4efa5d473..c98464e29 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -3,11 +3,17 @@ #include #include +#include + #include #include -#if __cpp_lib_optional >= 201606L +#ifdef HAS_OPTIONAL #include #endif +#ifdef HAS_SPAN +#include +#endif + namespace microstrain { @@ -122,6 +128,9 @@ class Serializer Serializer() = default; Serializer(uint8_t* ptr, size_t capacity, size_t offset=0) : m_ptr(ptr), m_size(capacity), m_offset(offset) {} Serializer(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} +#ifdef HAS_SPAN + Serializer(std::span buffer, size_t offset=0) : m_ptr(const_cast(buffer.data())), m_size(buffer.size()), m_offset(offset) {} +#endif size_t capacity() const { return m_size; } size_t length() const { return m_size; } @@ -285,13 +294,6 @@ size_t extract(Serializer& serializer, const std::tuple -// typename std::enable_if::value, size_t>::type -// /*size_t*/ extract(Serializer& buffer, T& value) -// { -// return value.deserialize(buffer); -// } // Raw buffer template @@ -302,8 +304,18 @@ bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offse return exact_size ? serializer.noRemaining() : serializer.isOk(); } -// Returning by value (use read if length is guaranteed to be in range) -#if __cpp_lib_optional >= 201606L +// Returning by value (use read instead if length is guaranteed to be in range) +#ifdef HAS_OPTIONAL +template +std::optional extract(Serializer& serializer) +{ + T value; + if(extract(serializer, value)) + return value; + else + return std::nullopt; +} + template std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bool exact_size=false) { @@ -345,18 +357,6 @@ size_t extract(Serializer& serializer, T0 value0, Ts... values) #endif - -//template -//size_t extract(Buffer& buffer, Buffer::Counter counter) -//{ -// size_t size = extract(counter.count); -// -// if(counter.count > counter.max_count) -// buffer.invalidate(); -// -// return size; -//} - template size_t extract_count(Serializer& buffer, T& count, size_t max_count) { diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index 7897a8cfd..25929a257 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -20,7 +20,6 @@ struct MetadataFor /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", /* .type = */ {Type::U8}, /* .accessor = */ utils::access, - /* .byte_offset = */ 1, /* .functions = */ ALL_FUNCTIONS, }, { @@ -28,7 +27,6 @@ struct MetadataFor /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8}, /* .accessor = */ utils::access, - /* .byte_offset = */ 2, /* .functions = */ ALL_FUNCTIONS, /* .count = */ 1, /* .counter_idx = */ 0, @@ -38,7 +36,6 @@ struct MetadataFor /* .docs = */ "List of descriptors and decimations.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .byte_offset = */ 3, /* .functions = */ ALL_FUNCTIONS, /* .count = */ 0, /* .counter_idx = */ 2, diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index 06a86daab..3abe75dda 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -44,7 +44,6 @@ struct MetadataFor /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports.", /* .type = */ {Type::U8}, /* .accessor = */ utils::access, - /* .byte_offset = */ 1, /* .functions = */ {true, true, true, true, true, true}, }, { @@ -52,7 +51,6 @@ struct MetadataFor /* .docs = */ "Port baud rate. Must be a supported rate.", /* .type = */ {Type::U32}, /* .accessor = */ utils::access, - /* .byte_offset = */ 2, /* .functions = */ {true,false,false,false,false}, }, }; diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index 70e97b2f8..62d2e02b8 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -20,14 +20,12 @@ struct MetadataFor .docs = "MIP data descriptor", .type = {Type::U8}, .accessor = utils::access, - .byte_offset = 0, }, { .name = "decimation", .docs = "Decimation from the base rate", .type = {Type::U16}, .accessor = utils::access, - .byte_offset = 1, }, }; @@ -50,21 +48,18 @@ struct MetadataFor .docs = "X axis", .type = {Type::FLOAT}, .accessor = nullptr, - .byte_offset = 0, }, { .name = "y", .docs = "Y axis", .type = {Type::FLOAT}, .accessor = nullptr, - .byte_offset = 4, }, { .name = "z", .docs = "Z axis", .type = {Type::FLOAT}, .accessor = nullptr, - .byte_offset = 8, }, }; diff --git a/src/cpp/mip/metadata/mip_metadata.hpp b/src/cpp/mip/metadata/mip_metadata.hpp index 041379fe7..96c472d63 100644 --- a/src/cpp/mip/metadata/mip_metadata.hpp +++ b/src/cpp/mip/metadata/mip_metadata.hpp @@ -43,7 +43,7 @@ static constexpr inline ParameterInfo FUNCTION_SELECTOR_PARAM = { /* .docs = */ "Standard MIP function selector", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ accessFunctionSelector, - /* .byte_offset = */ 0, + ///* .byte_offset = */ 0, /* .functions = */ {true,true,true,true,true}, /* .count = default */ /* .counter_idx = default */ diff --git a/src/cpp/mip/metadata/structures.hpp b/src/cpp/mip/metadata/structures.hpp index ca68e7bb4..05e296762 100644 --- a/src/cpp/mip/metadata/structures.hpp +++ b/src/cpp/mip/metadata/structures.hpp @@ -134,7 +134,6 @@ struct ParameterInfo const char* docs = nullptr; ///< Human-readable documentation. TypeInfo type; ///< Data type. Accessor accessor = nullptr; ///< Obtains a reference to the member variable. - uint8_t byte_offset = 0; ///< Offset "on the wire" or in a serialized buffer, in bytes. FuncBits functions; ///< This parameter is required for the specified function selectors. uint8_t count = 1; ///< Number of elements. 0 if size is specified at runtime. int8_t counter_idx = 0; ///< When count == 0, this specifies the parameter holding the runtime count, relative to this parameter's index. From 5db02068e7da5e4547086ccc4600ba798d5833ad Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 27 Jun 2024 19:01:33 -0400 Subject: [PATCH 042/147] Fix mip namespace in microstrain/common/index.hpp. --- src/cpp/microstrain/common/index.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/cpp/microstrain/common/index.hpp b/src/cpp/microstrain/common/index.hpp index 3f31deb79..ffce9d709 100644 --- a/src/cpp/microstrain/common/index.hpp +++ b/src/cpp/microstrain/common/index.hpp @@ -3,7 +3,7 @@ #include #include -namespace mip +namespace microstrain { class Id; @@ -113,4 +113,4 @@ namespace mip template auto indexOrDefault(Container& container, Index index, Value default_) { return index.isValid(container.size()) ? container[index.index()] : default_; } -} // namespace mip +} // namespace microstrain From 9222c6927596cf12cb86064d46dbf4a6f665b52b Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 27 Jun 2024 19:02:50 -0400 Subject: [PATCH 043/147] Use Index/Id in counter references and add docs to enum entries. --- src/cpp/mip/metadata/mip_metadata.hpp | 18 +++++++++--------- src/cpp/mip/metadata/structures.hpp | 22 ++++++++++++---------- src/cpp/mip/metadata/utils.hpp | 5 +++++ 3 files changed, 26 insertions(+), 19 deletions(-) diff --git a/src/cpp/mip/metadata/mip_metadata.hpp b/src/cpp/mip/metadata/mip_metadata.hpp index 96c472d63..4b5ece288 100644 --- a/src/cpp/mip/metadata/mip_metadata.hpp +++ b/src/cpp/mip/metadata/mip_metadata.hpp @@ -21,11 +21,11 @@ struct MetadataFor using type = FunctionSelector; static constexpr EnumInfo::Entry entries[] = { - { "WRITE", (uint8_t)FunctionSelector::WRITE }, - { "READ", (uint8_t)FunctionSelector::READ }, - { "SAVE", (uint8_t)FunctionSelector::SAVE }, - { "LOAD", (uint8_t)FunctionSelector::LOAD }, - { "DEFAULT", (uint8_t)FunctionSelector::RESET }, + { (uint8_t)FunctionSelector::WRITE, "WRITE", "Applies a new setting." }, + { (uint8_t)FunctionSelector::READ, "READ", "Reads the current setting." }, + { (uint8_t)FunctionSelector::SAVE, "SAVE", "Saves the current setting as power-on setting." }, + { (uint8_t)FunctionSelector::LOAD, "LOAD", "Loads the power-on setting." }, + { (uint8_t)FunctionSelector::RESET, "DEFAULT", "Resets to the factory default setting." }, }; static constexpr inline EnumInfo value = { @@ -45,10 +45,10 @@ static constexpr inline ParameterInfo FUNCTION_SELECTOR_PARAM = { /* .accessor = */ accessFunctionSelector, ///* .byte_offset = */ 0, /* .functions = */ {true,true,true,true,true}, - /* .count = default */ - /* .counter_idx = default */ - /* .union_index = default */ - /* .union_value = default */ + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, }; diff --git a/src/cpp/mip/metadata/structures.hpp b/src/cpp/mip/metadata/structures.hpp index 05e296762..b8e0bd8cc 100644 --- a/src/cpp/mip/metadata/structures.hpp +++ b/src/cpp/mip/metadata/structures.hpp @@ -1,5 +1,6 @@ #pragma once +#include #include #include @@ -62,8 +63,9 @@ struct EnumInfo { struct Entry { - const char* name = nullptr; uint32_t value = 0; + const char* name = nullptr; + const char* docs = nullptr; }; const char* name = nullptr; @@ -130,15 +132,15 @@ struct ParameterInfo { using Accessor = void* (*)(void*); - const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). - const char* docs = nullptr; ///< Human-readable documentation. - TypeInfo type; ///< Data type. - Accessor accessor = nullptr; ///< Obtains a reference to the member variable. - FuncBits functions; ///< This parameter is required for the specified function selectors. - uint8_t count = 1; ///< Number of elements. 0 if size is specified at runtime. - int8_t counter_idx = 0; ///< When count == 0, this specifies the parameter holding the runtime count, relative to this parameter's index. - int8_t union_index = 0; ///< When type is UNION, this specifies the parameter that controls which union member is active (the discriminator). - uint16_t union_value = 0; ///< When in a union, this specifies the value of the discriminator parameter that selects this member. + const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). + const char* docs = nullptr; ///< Human-readable documentation. + TypeInfo type; ///< Data type. + Accessor accessor = nullptr; ///< Obtains a reference to the member variable. + FuncBits functions; ///< This parameter is required for the specified function selectors. + uint8_t count = 1; ///< Number of elements. This is a maximum value when counter_idx != 0. + microstrain::Id counter_param; ///< When valid, this specifies the parameter holding the runtime count, relative to this parameter's index. + microstrain::Id union_param; ///< When type is UNION, this specifies the parameter that controls which union member is active (the discriminator). + uint16_t union_value = 0; ///< When in a union, this specifies the value of the discriminator parameter that selects this member. }; diff --git a/src/cpp/mip/metadata/utils.hpp b/src/cpp/mip/metadata/utils.hpp index 0c723c5c3..199b44d5c 100644 --- a/src/cpp/mip/metadata/utils.hpp +++ b/src/cpp/mip/metadata/utils.hpp @@ -56,5 +56,10 @@ void* access(void* p) return &(static_cast(p)->*Ptr); } +template +void* access(void* p) +{ + return static_cast(p)->*Ptr; +} } // namespace mip::metadata From d8fed4c2760cdd5eee3e2aa3334f68a9b450e1cc Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 27 Jun 2024 19:03:31 -0400 Subject: [PATCH 044/147] Generator updates for 3dm commands [WIP]. --- .../mip/metadata/definitions/commands_3dm.hpp | 2938 ++++++++++++++++- 1 file changed, 2912 insertions(+), 26 deletions(-) diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index 25929a257..2687c61c3 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -1,4 +1,5 @@ + #include "common.hpp" #include @@ -8,6 +9,417 @@ namespace mip::metadata { + +template<> +struct MetadataFor +{ + using type = commands_3dm::PollImuMessage; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors in the descriptor list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 83, + /* .counter_idx = */ microstrain::Index(1) /* num_descriptors */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "PollImuMessage", + /* .title = */ "None", + /* .docs = */ "Poll the device for an IMU message with the specified format\n\nThis function polls for an IMU message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set IMU Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an IMU Data packet.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::PollGnssMessage; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors in the descriptor list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 83, + /* .counter_idx = */ microstrain::Index(1) /* num_descriptors */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "PollGnssMessage", + /* .title = */ "None", + /* .docs = */ "Poll the device for an GNSS message with the specified format\n\nThis function polls for a GNSS message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set GNSS Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a GNSS Data packet.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::PollFilterMessage; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors in the format list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 83, + /* .counter_idx = */ microstrain::Index(1) /* num_descriptors */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "PollFilterMessage", + /* .title = */ "None", + /* .docs = */ "Poll the device for an Estimation Filter message with the specified format\n\nThis function polls for an Estimation Filter message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Estimation Filter Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an Estimation Filter Data packet.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ImuMessageFormat; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 82, + /* .counter_idx = */ microstrain::Index(0) /* num_descriptors */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "ImuMessageFormat", + /* .title = */ "None", + /* .docs = */ "Set, read, or save the format of the IMU data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GpsMessageFormat; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 82, + /* .counter_idx = */ microstrain::Index(0) /* num_descriptors */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GpsMessageFormat", + /* .title = */ "None", + /* .docs = */ "Set, read, or save the format of the GNSS data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::FilterMessageFormat; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 82, + /* .counter_idx = */ microstrain::Index(0) /* num_descriptors */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "FilterMessageFormat", + /* .title = */ "None", + /* .docs = */ "Set, read, or save the format of the Estimation Filter data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ImuGetBaseRate; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + + }; + + static constexpr inline StructInfo value = { + /* .name = */ "ImuGetBaseRate", + /* .title = */ "Get IMU Data Base Rate", + /* .docs = */ "Get the base rate for the IMU data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the IMU Message Format Command to set streaming data at a specified rate.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GpsGetBaseRate; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GpsGetBaseRate", + /* .title = */ "Get GNSS Data Base Rate", + /* .docs = */ "Get the base rate for the GNSS data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the GNSS Message Format Command to set streaming data at a specified rate.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::FilterGetBaseRate; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + + }; + + static constexpr inline StructInfo value = { + /* .name = */ "FilterGetBaseRate", + /* .title = */ "Get Estimation Filter Data Base Rate", + /* .docs = */ "Get the base rate for the Estimation Filter data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the Estimation Filter Message Format Command to set streaming data at a specified rate.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::PollData; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "desc_set", + /* .docs = */ "Data descriptor set. Must be supported.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors in the format list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 82, + /* .counter_idx = */ microstrain::Index(2) /* num_descriptors */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "PollData", + /* .title = */ "None", + /* .docs = */ "Poll the device for a message with the specified descriptor set and format.\n\nThis function polls for a message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a normal Data packet.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetBaseRate; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "desc_set", + /* .docs = */ "This is the data descriptor set. It must be a supported descriptor.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GetBaseRate", + /* .title = */ "Get Data Base Rate", + /* .docs = */ "Get the base rate for the specified descriptor set in Hz.", + /* .parameters = */ parameters, + }; +}; + template<> struct MetadataFor { @@ -16,43 +428,2517 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "desc_set", - /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", - /* .type = */ {Type::U8}, - /* .accessor = */ utils::access, - /* .functions = */ ALL_FUNCTIONS, + /* .name = */ "desc_set", + /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, }, { - /* .name = */ "desc_set", - /* .docs = */ "Number of descriptors (limited by payload size)", - /* .type = */ {Type::U8}, - /* .accessor = */ utils::access, - /* .functions = */ ALL_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ 0, + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, }, { - /* .name = */ "descriptors", - /* .docs = */ "List of descriptors and decimations.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ ALL_FUNCTIONS, - /* .count = */ 0, - /* .counter_idx = */ 2, + /* .name = */ "descriptors", + /* .docs = */ "List of descriptors and decimations.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 82, + /* .counter_idx = */ microstrain::Index(1) /* num_descriptors */, + /* .union_index = */ {}, + /* .union_value = */ 0, }, }; - static constexpr inline FieldInfo value = { + static constexpr inline StructInfo value = { /* .name = */ "MessageFormat", - /* .title = */ "Message Format", - /* .docs = */ "Sets up the message format.", + /* .title = */ "None", + /* .docs = */ "Set, read, or save the format for a given data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::NmeaMessage::MessageID; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "GGA", "GPS System Fix Data. Source can be the Filter or GNSS1/2 datasets." }, + { 2, "GLL", "Geographic Position Lat/Lon. Source can be the Filter or GNSS1/2 datasets." }, + { 3, "GSV", "GNSS Satellites in View. Source must be either GNSS1 or GNSS2 datasets. The talker ID must be set to IGNORED." }, + { 4, "RMC", "Recommended Minimum Specific GNSS Data. Source can be the Filter or GNSS1/2 datasets." }, + { 5, "VTG", "Course over Ground. Source can be the Filter or GNSS1/2 datasets." }, + { 6, "HDT", "Heading, True. Source can be the Filter or GNSS1/2 datasets." }, + { 7, "ZDA", "Time & Date. Source must be the GNSS1 or GNSS2 datasets." }, + { 129, "PKRA", "Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED." }, + { 130, "PKRR", "Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "MessageID", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::NmeaMessage::TalkerID; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "IGNORED", "Talker ID cannot be changed." }, + { 1, "GNSS", "NMEA message will be produced with talker id 'GN'." }, + { 2, "GPS", "NMEA message will be produced with talker id 'GP'." }, + { 3, "GALILEO", "NMEA message will be produced with talker id 'GA'." }, + { 4, "GLONASS", "NMEA message will be produced with talker id 'GL'." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "TalkerID", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::NmeaMessage; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "message_id", + /* .docs = */ "NMEA sentence type.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "talker_id", + /* .docs = */ "NMEA talker ID. Ignored for proprietary sentences.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "source_desc_set", + /* .docs = */ "Data descriptor set where the data will be sourced. Available options depend on the sentence.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "decimation", + /* .docs = */ "Decimation from the base rate for source_desc_set. Frequency is limited to 10 Hz or the base rate, whichever is lower. Must be 0 when polling.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "NmeaMessage", + /* .title = */ "Nmeamessage", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::NmeaPollData; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "count", + /* .docs = */ "Number of format entries (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "format_entries", + /* .docs = */ "List of format entries.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 40, + /* .counter_idx = */ microstrain::Index(1) /* count */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "NmeaPollData", + /* .title = */ "None", + /* .docs = */ "Poll the device for a NMEA message with the specified format.\n\nThis function polls for a NMEA message using the provided format.\nIf the format is not provided, the device will attempt to use the\nstored format (set with the Set NMEA Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as normal NMEA messages.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::NmeaMessageFormat; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "count", + /* .docs = */ "Number of format entries (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "format_entries", + /* .docs = */ "List of format entries.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 40, + /* .counter_idx = */ microstrain::Index(0) /* count */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "NmeaMessageFormat", + /* .title = */ "None", + /* .docs = */ "Set, read, or save the NMEA message format.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::DeviceSettings; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + + }; + + static constexpr inline StructInfo value = { + /* .name = */ "DeviceSettings", + /* .title = */ "None", + /* .docs = */ "Save, Load, or Reset to Default the values for all device settings.\n\nWhen a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory.\n\nThis command should have a long timeout as it may take up to 1 second to complete.", /* .parameters = */ parameters, - /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ ALL_FUNCTIONS, - /* .proprietary = */ false, - /* .response = */ nullptr, }; }; +template<> +struct MetadataFor +{ + using type = commands_3dm::UartBaudrate; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "baud", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "UartBaudrate", + /* .title = */ "None", + /* .docs = */ "Read, Save, Load, or Reset to Default the baud rate of the main communication channel.\n\nFor all functions except 0x01 (use new settings), the new baud rate value is ignored.\nPlease see the device user manual for supported baud rates.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::FactoryStreaming::Action; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "OVERWRITE", "Replaces the message format(s), removing any existing descriptors." }, + { 1, "MERGE", "Merges support descriptors into existing format(s). May reorder descriptors." }, + { 2, "ADD", "Adds descriptors to the current message format(s) without changing existing descriptors. May result in duplicates." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Action", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::FactoryStreaming; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "action", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "reserved", + /* .docs = */ "Reserved. Set to 0x00.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "FactoryStreaming", + /* .title = */ "None", + /* .docs = */ "Configures the device for recording data for technical support.\n\nThis command will configure all available data streams to predefined\nformats designed to be used with technical support.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::DatastreamControl; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "desc_set", + /* .docs = */ "The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets.\nOn Generation 5 products, this must be one of the above legacy constants.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "enable", + /* .docs = */ "True or false to enable or disable the stream.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "DatastreamControl", + /* .title = */ "None", + /* .docs = */ "Enable/disable the selected data stream.\n\nEach data stream (descriptor set) can be enabled or disabled.\nThe default for the device is all streams enabled.\nFor all functions except 0x01 (use new setting),\nthe new enable flag value is ignored and can be omitted.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ConstellationSettings::ConstellationId; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "GPS", "GPS (G1-G32)" }, + { 1, "SBAS", "SBAS (S120-S158)" }, + { 2, "GALILEO", "GALILEO (E1-E36)" }, + { 3, "BeiDou", "BeiDou (B1-B37)" }, + { 5, "QZSS", "QZSS (Q1-Q5)" }, + { 6, "GLONASS", "GLONASS (R1-R32)" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "ConstellationId", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ConstellationSettings::OptionFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "L1SAIF", "Available only for QZSS" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "OptionFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ConstellationSettings::Settings; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "constellation_id", + /* .docs = */ "Constellation ID", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "enable", + /* .docs = */ "Enable/Disable constellation", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "reserved_channels", + /* .docs = */ "Minimum number of channels reserved for this constellation", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "max_channels", + /* .docs = */ "Maximum number of channels to use for this constallation", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "option_flags", + /* .docs = */ "Constellation option Flags", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Settings", + /* .title = */ "Settings", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ConstellationSettings; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "max_channels", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "config_count", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "settings", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 0, + /* .counter_idx = */ microstrain::Index(1) /* config_count */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "ConstellationSettings", + /* .title = */ "None", + /* .docs = */ "This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation.\n\nMaximum number of tracking channels to use (total for all constellations):\n0 to max_channels_available (from reply message)\n\nFor each constellation you wish to use, include a ConstellationSettings struct. Note the following:\n\nTotal number of tracking channels (sum of 'reserved_channels' for all constellations) must be <= 32:\n0 -> 32 Number of reserved channels\n0 -> 32 Max number of channels (>= reserved channels)\n\nThe factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3.\n\nWarning: SBAS functionality shall not be used in 'safety of life' applications!\nWarning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK.\nWarning: You cannot enable GLONASS and BeiDou at the same time.\nNote: Enabling SBAS and QZSS augments GPS accuracy.\nNote: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GnssSbasSettings::SBASOptions; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "enable_ranging", "Use SBAS pseudo-ranges in position solution" }, + { 2, "enable_corrections", "Use SBAS differential corrections" }, + { 4, "apply_integrity", "Use SBAS integrity information. If enabled, only GPS satellites for which integrity information is available will be used." }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "SBASOptions", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GnssSbasSettings; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable_sbas", + /* .docs = */ "0 - SBAS Disabled, 1 - SBAS enabled", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "sbas_options", + /* .docs = */ "SBAS options, see definition", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "num_included_prns", + /* .docs = */ "Number of SBAS PRNs to include in search (0 = include all)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "included_prns", + /* .docs = */ "List of specific SBAS PRNs to search for", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 39, + /* .counter_idx = */ microstrain::Index(2) /* num_included_prns */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GnssSbasSettings", + /* .title = */ "SBAS Settings", + /* .docs = */ "Configure the SBAS subsystem\n\n\n", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GnssAssistedFix::AssistedFixOption; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "NONE", "No assisted fix (default)" }, + { 1, "ENABLED", "Enable assisted fix" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "AssistedFixOption", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GnssAssistedFix; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "option", + /* .docs = */ "Assisted fix options", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "flags", + /* .docs = */ "Assisted fix flags (set to 0xFF)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GnssAssistedFix", + /* .title = */ "GNSS Assisted Fix Settings", + /* .docs = */ "Set the options for assisted GNSS fix.\n\nDevices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM.\nThese storage mechanisms are used to retain information about the last good GNSS fix. This can greatly reduces the TTFF (Time To First Fix) depending on the age of the stored information.\nThe TTFF can be as low as one second, or up to the equivalent of a cold start. There is a small increase in power used when enabling assisted fix.\n\nThe fastest fix will be obtained by supplying the device with a GNSS Assist Time Update message containing the current GPS time immediately after subsequent power up.\nThis allows the device to determine if the last GNSS information saved is still fresh enough to improve the TTFF.\n\nNOTE: Non-volatile GNSS memory is cleared when going from an enabled state to a disabled state.\nWARNING: The clearing operation results in an erase operation on the GNSS Flash. The flash has a limited durability of 100,000 write/erase cycles", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GnssTimeAssistance; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "tow", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Weeks since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "accuracy", + /* .docs = */ "Accuracy of time information [seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GnssTimeAssistance", + /* .title = */ "None", + /* .docs = */ "Provide the GNSS subsystem with initial time information.\n\nThis message is required immediately after power up if GNSS Assist was enabled when the device was powered off.\nThis will initialize the subsystem clock to help reduce the time to first fix (TTFF).", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ImuLowpassFilter; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "target_descriptor", + /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.\nSupported values are accel (0x04), gyro (0x05), mag (0x06), and\npressure (0x17), provided the data is supported by the device.\nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "enable", + /* .docs = */ "The target data will be filtered if this is true.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "manual", + /* .docs = */ "If false, the cutoff frequency is set to half of the\nstreaming rate as configured by the message format command.\nOtherwise, the cutoff frequency is set according to the\nfollowing 'frequency' parameter.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "frequency", + /* .docs = */ "-3dB cutoff frequency in Hz. Will not affect filtering if 'manual' is false.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "reserved", + /* .docs = */ "Reserved, set to 0x00.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "ImuLowpassFilter", + /* .title = */ "Advanced Low-Pass Filter Settings", + /* .docs = */ "Advanced configuration for the IMU data quantity low-pass filters.\n\nDeprecated, use the lowpass filter (0x0C,0x54) command instead.\n\nThe scaled data quantities are by default filtered through a single-pole IIR low-pass filter\nwhich is configured with a -3dB cutoff frequency of half the reporting frequency (set by\ndecimation factor in the IMU Message Format command) to prevent aliasing on a per data\nquantity basis. This advanced configuration command allows for the cutoff frequency to\nbe configured independently of the data reporting frequency as well as allowing for a\ncomplete bypass of the digital low-pass filter.\n\nPossible data descriptors:\n0x04 - Scaled accelerometer data\n0x05 - Scaled gyro data\n0x06 - Scaled magnetometer data (if applicable)\n0x17 - Scaled pressure data (if applicable)", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::PpsSource::Source; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "DISABLED", "PPS output is disabled. Not valid for PPS source command." }, + { 1, "RECEIVER_1", "PPS is provided by GNSS receiver 1." }, + { 2, "RECEIVER_2", "PPS is provided by GNSS receiver 2." }, + { 3, "GPIO", "PPS is provided to an external GPIO pin. Use the GPIO Setup command to choose and configure the pin." }, + { 4, "GENERATED", "PPS is generated from the system oscillator." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Source", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::PpsSource; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "source", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "PpsSource", + /* .title = */ "None", + /* .docs = */ "Controls the Pulse Per Second (PPS) source.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GpioConfig::Feature; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "UNUSED", "The pin is not used. It may be technically possible to read the pin state in this mode, but this is not guaranteed to be true of all devices or pins." }, + { 1, "GPIO", "General purpose input or output. Use this for direct control of pin output state or to stream the state of the pin." }, + { 2, "PPS", "Pulse per second input or output." }, + { 3, "ENCODER", "Motor encoder/odometer input." }, + { 4, "TIMESTAMP", "Precision Timestamping. Use with Event Trigger Configuration (0x0C,0x2E)." }, + { 5, "UART", "UART data or control lines." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Feature", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GpioConfig::Behavior; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "UNUSED", "Use 0 unless otherwise specified." }, + { 1, "GPIO_INPUT", "Pin will be an input. This can be used to stream or poll the value and is the default setting." }, + { 2, "GPIO_OUTPUT_LOW", "Pin is an output initially in the LOW state. This state will be restored during system startup if the configuration is saved." }, + { 3, "GPIO_OUTPUT_HIGH", "Pin is an output initially in the HIGH state. This state will be restored during system startup if the configuration is saved." }, + { 1, "PPS_INPUT", "Pin will receive the pulse-per-second signal. Only one pin can have this behavior. This will only work if the PPS Source command is configured to GPIO." }, + { 2, "PPS_OUTPUT", "Pin will transmit the pulse-per-second signal from the device." }, + { 1, "ENCODER_A", "Encoder 'A' quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence." }, + { 2, "ENCODER_B", "Encoder 'B' quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence." }, + { 1, "TIMESTAMP_RISING", "Rising edges will be timestamped." }, + { 2, "TIMESTAMP_FALLING", "Falling edges will be timestamped." }, + { 3, "TIMESTAMP_EITHER", "Both rising and falling edges will be timestamped." }, + { 33, "UART_PORT2_TX", "(0x21) UART port 2 transmit." }, + { 34, "UART_PORT2_RX", "(0x22) UART port 2 receive." }, + { 49, "UART_PORT3_TX", "(0x31) UART port 3 transmit." }, + { 50, "UART_PORT3_RX", "(0x32) UART port 3 receive." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Behavior", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GpioConfig::PinMode; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "open_drain", "The pin will be an open-drain output. The state will be either LOW or FLOATING instead of LOW or HIGH, respectively. This is used to connect multiple open-drain outputs from several devices. An internal or external pull-up resistor is typically used in combination. The maximum voltage of an open drain output is subject to the device maximum input voltage range found in the specifications." }, + { 2, "pulldown", "The pin will have an internal pull-down resistor enabled. This is useful for connecting inputs to signals which can only be pulled high such as mechanical switches. Cannot be used in combination with pull-up. See the device specifications for the resistance value." }, + { 4, "pullup", "The pin will have an internal pull-up resistor enabled. Useful for connecting inputs to signals which can only be pulled low such as mechanical switches, or in combination with an open drain output. Cannot be used in combination with pull-down. See the device specifications for the resistance value. Use of this mode may restrict the maximum allowed input voltage. See the device datasheet for details." }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "PinMode", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GpioConfig; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "pin", + /* .docs = */ "GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "feature", + /* .docs = */ "Determines how the pin will be used.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "behavior", + /* .docs = */ "Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.)", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "pin_mode", + /* .docs = */ "GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GpioConfig", + /* .title = */ "GPIO Configuration", + /* .docs = */ "Configures the user GPIO pins on the connector for use with several built-in functions or for general input or output.\n\nGPIO pins are device-dependent. Some features are only available on\ncertain pins. Some behaviors require specific configurations.\nConsult the device user manual for restrictions and default settings.\n\nTo avoid glitches on GPIOs configured as an output in a mode other than\nGPIO, always configure the relevant function before setting up the pin\nwith this command. Otherwise, the pin state will be undefined between\nthis command and the one to set up the feature. For input pins, use\nthis command first so the state is well-defined when the feature is\ninitialized.\n\nSome configurations can only be active on one pin at a time. If such\nconfiguration is applied to a second pin, the second one will take\nprecedence and the original pin's configuration will be reset.\n", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GpioState; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "pin", + /* .docs = */ "GPIO pin number counting from 1. Cannot be 0.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, false, false, false, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "state", + /* .docs = */ "The pin state.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GpioState", + /* .title = */ "GPIO State", + /* .docs = */ "Allows the state of the pin to be read or controlled.\n\nThis command serves two purposes: 1) To allow reading the state of a pin via command,\nrather than polling a data quantity, and 2) to provide a way to set the output state\nwithout also having to specify the operating mode.\n\nThe state read back from the pin is the physical state of the pin, rather than a\nconfiguration value. The state can be read regardless of its configuration as long as\nthe device supports GPIO input on that pin. If the pin is set to an output, the read\nvalue would match the output value.\n\nWhile the state of a pin can always be set, it will only have an observable effect if\nthe pin is set to output mode.\n\nThis command does not support saving, loading, or resetting the state. Instead, use the\nGPIO Configuration command, which allows the initial state to be configured.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::Odometer::Mode; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "DISABLED", "Encoder is disabled." }, + { 2, "QUADRATURE", "Quadrature encoder mode." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Mode", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::Odometer; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "mode", + /* .docs = */ "Mode setting.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "scaling", + /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "Uncertainty in encoder counts to distance translation (1-sigma value) [m/m].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Odometer", + /* .title = */ "Odometer Settings", + /* .docs = */ "Configures the hardware odometer interface.\n", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventSupport::Query; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "TRIGGER_TYPES", "Query the supported trigger types and max count for each." }, + { 2, "ACTION_TYPES", "Query the supported action types and max count for each." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Query", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventSupport::Info; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "type", + /* .docs = */ "Trigger or action type, as defined in the respective setup command.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "count", + /* .docs = */ "This is the maximum number of instances supported for this type.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Info", + /* .title = */ "Info", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventSupport; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "query", + /* .docs = */ "What type of information to retrieve.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GetEventSupport", + /* .title = */ "Get Supported Events", + /* .docs = */ "Lists the available trigger or action types.\n\nThere are a limited number of trigger and action slots available\nin the device. Up to M triggers and N actions can be configured at once\nin slots 1..M and 1..N respectively. M and N are identified by the\nmax_instances field in the response with the appropriate query selector.\n\nEach slot can be configured as one of a variety of different types of\ntriggers or actions. The supported types are enumerated in the response\nto this command. Additionally, there is a limit on the number of a given\ntype. In other words, while the device may support M triggers in total,\nonly a few of them maybe usable as a given type. This limit helps optimize\ndevice resources. The limit is identified in the count field.\n\nAll of the information in this command is available in the user manual.\nThis command provides a programmatic method for obtaining the information.\n", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventControl::Mode; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "DISABLED", "Trigger is disabled." }, + { 1, "ENABLED", "Trigger is enabled and will work normally." }, + { 2, "TEST", "Forces the trigger to the active state for testing purposes." }, + { 3, "TEST_PULSE", "Trigger is forced to the active state for one event cycle only. After the test cycle, the mode reverts to the previous state (either enabled or disabled)." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Mode", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventControl; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "instance", + /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "mode", + /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "EventControl", + /* .title = */ "Event Control", + /* .docs = */ "Enables or disables event triggers.\n\nTriggers can be disabled, enabled, and tested. While disabled, a trigger will\nnot evaluate its logic and effective behave like no trigger is configured.\nA disabled trigger will not activate any actions. Triggers are disabled by default.\n\nUse this command to enable (or disable) a trigger, or to place it into a test mode.\nWhen in test mode, the trigger logic is disabled but the output is forced to\nthe active state, meaning that it will behave as if the trigger logic is satisfied\nand any associated actions will execute.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventTriggerStatus::Status; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "active", "True if the trigger is currently active (either due to its logic or being in test mode)." }, + { 2, "enabled", "True if the trigger is enabled." }, + { 4, "test", "True if the trigger is in test mode." }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "Status", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventTriggerStatus::Entry; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "type", + /* .docs = */ "Configured trigger type.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "status", + /* .docs = */ "Trigger status.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Entry", + /* .title = */ "Entry", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventTriggerStatus; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "requested_count", + /* .docs = */ "Number of entries requested. If 0, requests all trigger slots.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "requested_instances", + /* .docs = */ "List of trigger instances to query.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 20, + /* .counter_idx = */ microstrain::Index(0) /* requested_count */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GetEventTriggerStatus", + /* .title = */ "Get Trigger Status", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventActionStatus::Entry; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "action_type", + /* .docs = */ "Configured action type.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "trigger_id", + /* .docs = */ "Associated trigger instance.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Entry", + /* .title = */ "Entry", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventActionStatus; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "requested_count", + /* .docs = */ "Number of entries requested. If 0, requests all action slots.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "requested_instances", + /* .docs = */ "List of action instances to query.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 20, + /* .counter_idx = */ microstrain::Index(0) /* requested_count */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GetEventActionStatus", + /* .title = */ "Get Action Status", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventTrigger::GpioParams::Mode; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "DISABLED", "The pin will have no effect and the trigger will never activate." }, + { 1, "WHILE_HIGH", "The trigger will be active while the pin is high." }, + { 2, "WHILE_LOW", "The trigger will be active while the pin is low." }, + { 4, "EDGE", "Use if the pin is configured for timestamping via the 3DM Gpio Configuration command (0x0C41)." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Mode", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventTrigger::GpioParams; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "pin", + /* .docs = */ "GPIO pin number.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "mode", + /* .docs = */ "How the pin state affects the trigger.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GpioParams", + /* .title = */ "Gpioparams", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventTrigger::ThresholdParams::Type; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "WINDOW", "Window comparison. Trigger is active if low_thres <= value <= high_thres. If the thresholds are reversed, the trigger is active when value < high_thres or value > low_thres." }, + { 2, "INTERVAL", "Trigger at evenly-spaced intervals. Normally used with time fields to trigger periodically. Trigger is active when (value % interval) <= int_thres. If the thresholds are reversed (high_thres < low_thres) then the trigger is active when (value % low_thres) > high_thres." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Type", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventTrigger::ThresholdParams; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "desc_set", + /* .docs = */ "Descriptor set of target data quantity.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "field_desc", + /* .docs = */ "Field descriptor of target data quantity.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "param_id", + /* .docs = */ "1-based index of the target parameter within the MIP field. E.g. for Scaled Accel (0x80,0x04) a value of 2 would represent the Y axis.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "type", + /* .docs = */ "Determines the type of comparison.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "", + /* .docs = */ "", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "", + /* .docs = */ "", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "ThresholdParams", + /* .title = */ "Thresholdparams", + /* .docs = */ "Comparison of a supported MIP field parameter against a set of thresholds.\n\nTriggers when a data quantity meets the comparison criteria. The comparison can be either\na window comparison with high and low thresholds or a periodic interval.\n\nThe data quantity is identified by the MIP descriptor set, field descriptor, and parameter number.\nE.g. Scaled acceleration in the Z direction is specified with desc_set=0x80 (sensor data),\nfield_desc=0x04 (scaled accel), and param_id=3 (the third parameter and Z axis).\n\nThe window comparison can be used for a variety of purposes, such as disabling\na robot's drive motors if it tips over. In this case, a window comparison could\nbe set up to monitor the roll angle, (0x80,0x0C,3). The lower threshold would be set\nto -pi/2 radians and the upper threshold to pi/2 radians.\n\nThe interval trigger can be used to perform an action periodically if used with\na time field. E.g. to execute the action every 16 ms, set an interval comparison on\nthe GPS time of week parameter (0x80,0xD3,1) with high_thres set to 0.016. The lower\nthreshold determines how long the trigger is active within the 16-ms period.\n\nEither comparison type can be inverted by reversing the threshold values; setting\nlow_thres > high_thres will result in the reverse condition.\n", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventTrigger::CombinationParams; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "logic_table", + /* .docs = */ "The last column of a truth table describing the output given the state of each input.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "input_triggers", + /* .docs = */ "List of trigger IDs for inputs. Use 0 for unused inputs.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 4, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "CombinationParams", + /* .title = */ "Combinationparams", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventTrigger::Type; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "NONE", "No trigger selected. The state will always be inactive." }, + { 1, "GPIO", "Trigger based on the state of a GPIO pin. See GpioParams." }, + { 2, "THRESHOLD", "Compare a data quantity against a high and low threshold. See ThresholdParams." }, + { 3, "COMBINATION", "Logical combination of two or more triggers. See CombinationParams." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Type", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventTrigger::Parameters; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "gpio", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "threshold", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "combination", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Parameters", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventTrigger; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "instance", + /* .docs = */ "Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "type", + /* .docs = */ "Type of trigger to configure.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "parameters", + /* .docs = */ "", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "EventTrigger", + /* .title = */ "Event Trigger Configuration", + /* .docs = */ "Configures various types of event triggers.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventAction::GpioParams::Mode; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "DISABLED", "Pin state will not be changed." }, + { 1, "ACTIVE_HIGH", "Pin will be set high when the trigger is active and low otherwise." }, + { 2, "ACTIVE_LOW", "Pin will be set low when the trigger is active and high otherwise." }, + { 5, "ONESHOT_HIGH", "Pin will be set high each time the trigger activates. It will not be set low." }, + { 6, "ONESHOT_LOW", "Pin will be set low each time the trigger activates. It will not be set high." }, + { 7, "TOGGLE", "Pin will change to the opposite state each time the trigger activates." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Mode", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventAction::GpioParams; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "pin", + /* .docs = */ "GPIO pin number.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "mode", + /* .docs = */ "Behavior of the pin.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GpioParams", + /* .title = */ "Gpioparams", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventAction::MessageParams; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "desc_set", + /* .docs = */ "MIP data descriptor set.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "decimation", + /* .docs = */ "Decimation from the base rate.\nIf 0, a packet is emitted each time the trigger activates.\nOtherwise, packets will be streamed while the trigger is active.\nThe internal decimation counter is reset if the trigger deactivates.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "num_fields", + /* .docs = */ "Number of mip fields in the packet. Limited to 12.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "List of field descriptors.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 20, + /* .counter_idx = */ microstrain::Index(2) /* num_fields */, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "MessageParams", + /* .title = */ "Messageparams", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventAction::Type; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "NONE", "No action. Parameters should be empty." }, + { 1, "GPIO", "Control the state of a GPIO pin. See GpioParameters." }, + { 2, "MESSAGE", "Output a data packet. See MessageParameters." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Type", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventAction::Parameters; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "gpio", + /* .docs = */ "Gpio parameters, if type == GPIO. Ignore otherwise.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "message", + /* .docs = */ "Message parameters, if type == MESSAGE. Ignore otherwise.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Parameters", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::EventAction; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "instance", + /* .docs = */ "Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "trigger", + /* .docs = */ "Trigger ID number.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "type", + /* .docs = */ "Type of action to configure.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "parameters", + /* .docs = */ "", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "EventAction", + /* .title = */ "Event Action Configuration", + /* .docs = */ "Configures various types of event actions.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::AccelBias; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "bias", + /* .docs = */ "accelerometer bias in the sensor frame (x,y,z) [g]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "AccelBias", + /* .title = */ "Configure Accel Bias", + /* .docs = */ "Configures the user specified accelerometer bias\n\nThe user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GyroBias; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "bias", + /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "GyroBias", + /* .title = */ "Configure Gyro Bias", + /* .docs = */ "Configures the user specified gyroscope bias\n\nThe user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::CaptureGyroBias; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "averaging_time_ms", + /* .docs = */ "Averaging time [milliseconds]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "CaptureGyroBias", + /* .title = */ "Capture Gyro Bias", + /* .docs = */ "Samples gyro for a specified time range and writes the averaged result to the Gyro Bias vector in RAM\n\nThe device will average the gyro output for the duration of 'averaging_time_ms.' To store the resulting vector\nin non-volatile memory, use the Set Gyro Bias command.\nIMPORTANT: The device must be stationary and experiencing minimum vibration for the duration of 'averaging_time_ms'\nAveraging Time range: 1000 to 30,000", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::MagHardIronOffset; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "offset", + /* .docs = */ "hard iron offset in the sensor frame (x,y,z) [Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "MagHardIronOffset", + /* .title = */ "Magnetometer Hard Iron Offset", + /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::MagSoftIronMatrix; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "offset", + /* .docs = */ "soft iron matrix [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "MagSoftIronMatrix", + /* .title = */ "Magnetometer Soft Iron Matrix", + /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \begin{bmatrix} 0 & 1 & 2 \\ 3 & 4 & 5 \\ 6 & 7 & 8 \end{bmatrix} EQEND\n", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ConingScullingEnable; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "If true, coning and sculling compensation is enabled.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "ConingScullingEnable", + /* .title = */ "Coning and Sculling Enable", + /* .docs = */ "Controls the Coning and Sculling Compenstation setting.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::Sensor2VehicleTransformEuler; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "roll", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "pitch", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "yaw", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Sensor2VehicleTransformEuler", + /* .title = */ "Sensor to Vehicle Frame Transformation Euler", + /* .docs = */ "Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, Roll Euler angles.\nThese are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference,\nand describe the transformation of vectors from the sensor body frame to the vehicle frame.
\nNote: This is the transformation, the inverse of the rotation defined in our legacy products.
\nThe transformation may be stored in the device as a matrix or quaternion. When Euler angles are read back from the device, they may not\nbe exactly equal to the Euler angles used to set the transformation, but they are functionally equivalent, such that they result in the same transformation.
\n

\nThis transformation to the vehicle frame will be applied to the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\nComplementary Filter Orientation
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::Sensor2VehicleTransformQuaternion; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "q", + /* .docs = */ "Unit length quaternion representing transform [w, i, j, k]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Sensor2VehicleTransformQuaternion", + /* .title = */ "Sensor to Vehicle Frame Transformation Quaternion", + /* .docs = */ "Set the sensor to vehicle frame transformation using unit length quaternion.\n\nNote: This is the transformation, the inverse of the rotation.\n\nThis quaternion describes the transformation of vectors from the sensor body frame to the vehicle frame of reference, and satisfies the following relationship:
\n\nEQSTART p^{veh} = q^{-1} p^{sen} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the transformation.
\nEQSTART p^{sen} = (0, v^{sen}_x, v^{sen}_y, v^{sen}_z) EQEND and EQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART p^{veh} = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
\n\nThe transformation may be stored in the device as a matrix or a quaternion. When the quaternion is read back from the device, it may not\nbe exactly equal to the quaternion used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::Sensor2VehicleTransformDcm; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "dcm", + /* .docs = */ "3 x 3 direction cosine matrix, stored in row-major order", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Sensor2VehicleTransformDcm", + /* .title = */ "Sensor to Vehicle Frame Transformation Direction Cosine Matrix", + /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.\n\nThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
\nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
\n\nWhere:
\n\nEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND\nThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not\nbe exactly equal to array used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ComplementaryFilter; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "pitch_roll_enable", + /* .docs = */ "Enable Pitch/Roll corrections", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "heading_enable", + /* .docs = */ "Enable Heading corrections (only available on devices with magnetometer)", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "pitch_roll_time_constant", + /* .docs = */ "Time constant associated with the pitch/roll corrections [s]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "heading_time_constant", + /* .docs = */ "Time constant associated with the heading corrections [s]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "ComplementaryFilter", + /* .title = */ "Complementary filter settings", + /* .docs = */ "Configure the settings for the complementary filter which produces the following (0x80) descriptor set values: attitude matrix (0x80,09), quaternion (0x80,0A), and Euler angle (0x80,0C) outputs.\n\nThe filter can be configured to correct for pitch and roll using the accelerometer (with the assumption that linear acceleration is minimal),\nand to correct for heading using the magnetometer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field).\nPitch/roll and heading corrections each have their own configurable time constants, with a valid range of 1-1000 seconds. The default time constant is 10 seconds.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::SensorRangeType; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "ALL", "Only allowed for SAVE, LOAD, and DEFAULT function selectors." }, + { 1, "ACCEL", "Accelerometer. Range is specified in g." }, + { 2, "GYRO", "Gyroscope. Range is specified in degrees/s." }, + { 3, "MAG", "Magnetometer. Range is specified in Gauss." }, + { 4, "PRESS", "Pressure sensor. Range is specified in hPa." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "SensorRangeType", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::SensorRange; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "sensor", + /* .docs = */ "Which type of sensor will get the new range value.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "setting", + /* .docs = */ "Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "SensorRange", + /* .title = */ "Sensor Range", + /* .docs = */ "Changes the IMU sensor gain.\n\nThis allows you to optimize the range to get the best accuracy and performance\nwhile minimizing over-range events.\n\nUse the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine\nthe appropriate setting value for your application. Using values other than\nthose specified may result in a NACK or inaccurate measurement data.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::CalibratedSensorRanges::Entry; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "setting", + /* .docs = */ "The value used in the 3DM Sensor Range command and response.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "range", + /* .docs = */ "The actual range value. Units depend on the sensor type.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Entry", + /* .title = */ "Entry", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::CalibratedSensorRanges; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "sensor", + /* .docs = */ "The sensor to query. Cannot be ALL.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "CalibratedSensorRanges", + /* .title = */ "Get Calibrated Sensor Ranges", + /* .docs = */ "Returns the supported sensor ranges which may be used with the 3DM Sensor Range (0x0C,0x52) command.\n\nThe response includes an array of (u8, float) pairs which map each allowed setting\nto the corresponding maximum range in physical units. See SensorRangeType for units.", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::LowpassFilter; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "desc_set", + /* .docs = */ "Descriptor set of the quantity to be filtered.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "field_desc", + /* .docs = */ "Field descriptor of the quantity to be filtered.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "enable", + /* .docs = */ "The filter will be enabled if this is true.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "manual", + /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + { + /* .name = */ "frequency", + /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .counter_idx = */ {}, + /* .union_index = */ {}, + /* .union_value = */ 0, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "LowpassFilter", + /* .title = */ "Low-pass anti-aliasing filter", + /* .docs = */ "This command controls the low-pass anti-aliasing filter supported data quantities.\n\nSee the device user manual for data quantities which support the anti-aliasing filter.\n\nIf set to automatic mode, the frequency will track half of the transmission rate\nof the target descriptor according to the configured message format (0x0C,0x0F).\nFor example, if scaled accel (0x80,0x04) is set to stream at 100 Hz, the filter would\nbe set to 50 Hz. Changing the message format to 200 Hz would automatically adjust the\nfilter to 100 Hz.\n\nFor WRITE, SAVE, LOAD, and DEFAULT function selectors, the descriptor set and/or field descriptor\nmay be 0x00 to set, save, load, or reset the setting for all supported descriptors. The\nfield descriptor must be 0x00 if the descriptor set is 0x00.\n", + /* .parameters = */ parameters, + }; +}; + + } // namespace mip::metadata From 5a2215e1363f7b4aa949e62afd7b8211e69cfbeb Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 28 Jun 2024 19:08:31 -0400 Subject: [PATCH 045/147] Generator updates for commands & array support [WIP]. --- examples/CSV/csv.cpp | 5 +- examples/CSV/stringify.cpp | 126 +- src/cpp/microstrain/common/index.hpp | 7 + src/cpp/microstrain/common/serialization.hpp | 19 +- .../mip/metadata/definitions/commands_3dm.hpp | 2338 ++++++++--------- .../metadata/definitions/commands_base.hpp | 545 +++- src/cpp/mip/metadata/definitions/common.hpp | 144 +- src/cpp/mip/metadata/mip_all_definitions.hpp | 4 +- src/cpp/mip/metadata/mip_metadata.hpp | 128 +- src/cpp/mip/metadata/structures.hpp | 84 +- src/cpp/mip/metadata/utils.hpp | 2 + 11 files changed, 1994 insertions(+), 1408 deletions(-) diff --git a/examples/CSV/csv.cpp b/examples/CSV/csv.cpp index 1613a456d..d39bc3a7f 100644 --- a/examples/CSV/csv.cpp +++ b/examples/CSV/csv.cpp @@ -56,7 +56,10 @@ int main(int argc, const char* argv[]) } mip::DispatchHandler handler; - device->registerFieldCallback<&handleField>(handler, 0xFF, mip::INVALID_FIELD_DESCRIPTOR); + device->registerFieldCallback<&handleField>(handler, 0x00, mip::INVALID_FIELD_DESCRIPTOR); + + mip::commands_base::BaseDeviceInfo info; + mip::commands_base::getDeviceInfo(*device, &info); std::signal(SIGTERM, &signal_handler); diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp index 013d973db..f1308ddef 100644 --- a/examples/CSV/stringify.cpp +++ b/examples/CSV/stringify.cpp @@ -6,12 +6,11 @@ #include #include -#include -#include -#include #include #include +#include #include +#include #if __cpp_lib_optional < 201606L #error "Needs optional support" @@ -174,6 +173,13 @@ std::ostream& formatUnion(std::ostream& ss, const UnionInfo* info, const StructI return ss; } +//static constexpr inline size_t MAX_PARAM_REFS = 5; +//struct Offset +//{ +// microstrain::Index paramId = {}; +// size_t offset = 0; +//}; + //////////////////////////////////////////////////////////////////////////////// ///@brief Format struct from buffer to a string. /// @@ -192,51 +198,92 @@ std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, microstrain if(serializer.isOverrun()) return ss << "?"; + // Keep track of the offset of each parameter so we can go back and look up array sizes, etc. + constexpr size_t MAX_PARAMETERS = 20; + std::array offsets; + assert(info->parameters.size() <= MAX_PARAMETERS); // Increase MAX_PARAMETERS if this trips. + + //std::array offsets; + //size_t nextOffsetIndex = 0; + //microstrain::Index firstVariadicParam; + + //const size_t baseOffset = serializer.offset(); + ss << '{'; - size_t i=0; - for(const auto& param : info->parameters) + for(size_t i=0; iparameters.size(); i++) { + const auto& param = info->parameters[i]; if(i > 0) ss << ", "; ss << param.name << '='; - switch(param.type.type) + // Save offset of each parameter (necessary due to nested structs, etc. and variable length arrays). + offsets[i] = serializer.offset(); + + uint8_t count = param.count.count; + if(param.count.hasCounter()) { - case Type::NONE: - return ss << "-"; - - case Type::BOOL: formatBasicType(ss, serializer); break; - case Type::U8: formatBasicType(ss, serializer); break; - case Type::S8: formatBasicType< int8_t >(ss, serializer); break; - case Type::U16: formatBasicType(ss, serializer); break; - case Type::S16: formatBasicType< int16_t>(ss, serializer); break; - case Type::U32: formatBasicType(ss, serializer); break; - case Type::S32: formatBasicType< int32_t>(ss, serializer); break; - case Type::U64: formatBasicType(ss, serializer); break; - case Type::S64: formatBasicType< int64_t>(ss, serializer); break; - case Type::FLOAT: formatBasicType(ss, serializer); break; - case Type::DOUBLE: formatBasicType(ss, serializer); break; - - case Type::ENUM: - formatEnum(ss, static_cast(param.type.infoPtr), serializer); - break; - - case Type::BITFIELD: - formatBitfield(ss, static_cast(param.type.infoPtr), serializer); - break; - - case Type::STRUCT: - formatStruct(ss, static_cast(param.type.infoPtr), serializer); - break; - - case Type::UNION: - formatUnion(ss, static_cast(param.type.infoPtr), *info, serializer); - break; + assert(param.count.paramIdx.isValid(i)); // Array size can't come after the array + + const ParameterInfo& counter = info->parameters[param.count.paramIdx.index()]; + const size_t counterOffset = offsets[param.count.paramIdx.index()]; + + const size_t oldOffset = serializer.setOffset(counterOffset); + std::optional counterValue = readIntegralValue(counter.type.type, serializer); + serializer.setOffset(oldOffset); + + if(!counterValue) + { + serializer.invalidate(); + ss << "[?]"; + continue; + } + + count = *counterValue; } + if(param.count.count != 1) + ss << '['; - i++; + for(uint8_t j=0; j(ss, serializer); break; + case Type::U8: formatBasicType(ss, serializer); break; + case Type::S8: formatBasicType< int8_t >(ss, serializer); break; + case Type::U16: formatBasicType(ss, serializer); break; + case Type::S16: formatBasicType< int16_t>(ss, serializer); break; + case Type::U32: formatBasicType(ss, serializer); break; + case Type::S32: formatBasicType< int32_t>(ss, serializer); break; + case Type::U64: formatBasicType(ss, serializer); break; + case Type::S64: formatBasicType< int64_t>(ss, serializer); break; + case Type::FLOAT: formatBasicType(ss, serializer); break; + case Type::DOUBLE: formatBasicType(ss, serializer); break; + + case Type::ENUM: + formatEnum(ss, static_cast(param.type.infoPtr), serializer); + break; + + case Type::BITFIELD: + formatBitfield(ss, static_cast(param.type.infoPtr), serializer); + break; + + case Type::STRUCT: + formatStruct(ss, static_cast(param.type.infoPtr), serializer); + break; + + case Type::UNION: + formatUnion(ss, static_cast(param.type.infoPtr), *info, serializer); + break; + } + } + if(param.count.count != 1) + ss << ']'; } ss << '}'; @@ -257,9 +304,10 @@ std::ostream& formatField(std::ostream& ss, const mip::FieldView& field) if(!info) { - ss << "Unknown(%02X,%02x)["; + ss << std::showbase << std::hex << std::setfill('0'); + ss << "Unknown(" << std::setw(2) << (int)field.descriptorSet() << "," << std::setw(2) << (int)field.fieldDescriptor() << ")[" << std::noshowbase; for(uint8_t i=0; i(Index other) const { return m_index > other.m_index; } + bool operator<=(Index other) const { return m_index <= other.m_index; } + bool operator>=(Index other) const { return m_index >= other.m_index; } + bool operator==(Index other) const { return m_index == other.m_index; } + bool operator!=(Index other) const { return m_index != other.m_index; } + private: unsigned int m_index; }; diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index c98464e29..b12f57e97 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -158,12 +158,15 @@ class Serializer template bool extract(Ts&... values); - template - struct Counter - { - T& count; - size_t max_count = 0; - }; + // Sets a new offset and returns the old value. + size_t setOffset(size_t offset) { std::swap(m_offset, offset); return offset; } + + //template + //struct Counter + //{ + // T& count; + // size_t max_count = 0; + //}; private: uint8_t* m_ptr = nullptr; @@ -376,10 +379,10 @@ size_t extract_count(Serializer& buffer, T* count, size_t max_count) { return ex template -bool Serializer::insert(const Ts&... values) { return microstrain::insert(*this, values...); } +bool Serializer::insert(const Ts&... values) { microstrain::insert(*this, values...); return isOk(); } template -bool Serializer::extract(Ts&... values) { return microstrain::extract(*this, values...); } +bool Serializer::extract(Ts&... values) { microstrain::extract(*this, values...); return isOk(); } } // namespace microstrain diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index 2687c61c3..c348e9b23 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -18,37 +18,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "suppress_ack", - /* .docs = */ "Suppress the usual ACK/NACK reply.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "num_descriptors", - /* .docs = */ "Number of descriptors in the descriptor list.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "descriptors", - /* .docs = */ "Descriptor list.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 83, - /* .counter_idx = */ microstrain::Index(1) /* num_descriptors */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors in the descriptor list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, + /* .condition = */ {}, }, }; @@ -68,37 +62,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "suppress_ack", - /* .docs = */ "Suppress the usual ACK/NACK reply.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "num_descriptors", - /* .docs = */ "Number of descriptors in the descriptor list.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors in the descriptor list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "descriptors", - /* .docs = */ "Descriptor list.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 83, - /* .counter_idx = */ microstrain::Index(1) /* num_descriptors */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "descriptors", + /* .docs = */ "Descriptor list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, + /* .condition = */ {}, }, }; @@ -118,37 +106,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "suppress_ack", - /* .docs = */ "Suppress the usual ACK/NACK reply.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "num_descriptors", - /* .docs = */ "Number of descriptors in the format list.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors in the format list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "descriptors", - /* .docs = */ "Descriptor format list.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 83, - /* .counter_idx = */ microstrain::Index(1) /* num_descriptors */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, + /* .condition = */ {}, }, }; @@ -168,26 +150,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "num_descriptors", - /* .docs = */ "Number of descriptors", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "descriptors", - /* .docs = */ "Descriptor format list.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 82, - /* .counter_idx = */ microstrain::Index(0) /* num_descriptors */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, + /* .condition = */ {}, }, }; @@ -207,26 +185,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "num_descriptors", - /* .docs = */ "Number of descriptors", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "descriptors", - /* .docs = */ "Descriptor format list.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 82, - /* .counter_idx = */ microstrain::Index(0) /* num_descriptors */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, + /* .condition = */ {}, }, }; @@ -246,26 +220,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "num_descriptors", - /* .docs = */ "Number of descriptors (limited by payload size)", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "descriptors", - /* .docs = */ "", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 82, - /* .counter_idx = */ microstrain::Index(0) /* num_descriptors */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "descriptors", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, + /* .condition = */ {}, }, }; @@ -339,48 +309,40 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "desc_set", - /* .docs = */ "Data descriptor set. Must be supported.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "suppress_ack", - /* .docs = */ "Suppress the usual ACK/NACK reply.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "num_descriptors", - /* .docs = */ "Number of descriptors in the format list.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "descriptors", - /* .docs = */ "Descriptor format list.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 82, - /* .counter_idx = */ microstrain::Index(2) /* num_descriptors */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "desc_set", + /* .docs = */ "Data descriptor set. Must be supported.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors in the format list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {82, microstrain::Index(2) /* num_descriptors */}, + /* .condition = */ {}, }, }; @@ -400,15 +362,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "desc_set", - /* .docs = */ "This is the data descriptor set. It must be a supported descriptor.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "desc_set", + /* .docs = */ "This is the data descriptor set. It must be a supported descriptor.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -428,37 +388,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "desc_set", - /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "desc_set", + /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "num_descriptors", - /* .docs = */ "Number of descriptors (limited by payload size)", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "descriptors", - /* .docs = */ "List of descriptors and decimations.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 82, - /* .counter_idx = */ microstrain::Index(1) /* num_descriptors */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "descriptors", + /* .docs = */ "List of descriptors and decimations.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {82, microstrain::Index(1) /* num_descriptors */}, + /* .condition = */ {}, }, }; @@ -525,48 +479,40 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "message_id", - /* .docs = */ "NMEA sentence type.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "talker_id", - /* .docs = */ "NMEA talker ID. Ignored for proprietary sentences.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "source_desc_set", - /* .docs = */ "Data descriptor set where the data will be sourced. Available options depend on the sentence.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "decimation", - /* .docs = */ "Decimation from the base rate for source_desc_set. Frequency is limited to 10 Hz or the base rate, whichever is lower. Must be 0 when polling.", - /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "message_id", + /* .docs = */ "NMEA sentence type.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "talker_id", + /* .docs = */ "NMEA talker ID. Ignored for proprietary sentences.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "source_desc_set", + /* .docs = */ "Data descriptor set where the data will be sourced. Available options depend on the sentence.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "decimation", + /* .docs = */ "Decimation from the base rate for source_desc_set. Frequency is limited to 10 Hz or the base rate, whichever is lower. Must be 0 when polling.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -586,37 +532,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "suppress_ack", - /* .docs = */ "Suppress the usual ACK/NACK reply.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "suppress_ack", + /* .docs = */ "Suppress the usual ACK/NACK reply.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "count", - /* .docs = */ "Number of format entries (limited by payload size)", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "count", + /* .docs = */ "Number of format entries (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "format_entries", - /* .docs = */ "List of format entries.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 40, - /* .counter_idx = */ microstrain::Index(1) /* count */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "format_entries", + /* .docs = */ "List of format entries.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {40, microstrain::Index(1) /* count */}, + /* .condition = */ {}, }, }; @@ -636,26 +576,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "count", - /* .docs = */ "Number of format entries (limited by payload size)", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "count", + /* .docs = */ "Number of format entries (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "format_entries", - /* .docs = */ "List of format entries.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 40, - /* .counter_idx = */ microstrain::Index(0) /* count */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "format_entries", + /* .docs = */ "List of format entries.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {40, microstrain::Index(0) /* count */}, + /* .condition = */ {}, }, }; @@ -693,15 +629,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "baud", - /* .docs = */ "", - /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "baud", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -741,26 +675,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "action", - /* .docs = */ "", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "action", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "reserved", - /* .docs = */ "Reserved. Set to 0x00.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "reserved", + /* .docs = */ "Reserved. Set to 0x00.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -780,26 +710,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "desc_set", - /* .docs = */ "The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets.\nOn Generation 5 products, this must be one of the above legacy constants.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "desc_set", + /* .docs = */ "The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets.\nOn Generation 5 products, this must be one of the above legacy constants.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "enable", - /* .docs = */ "True or false to enable or disable the stream.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "enable", + /* .docs = */ "True or false to enable or disable the stream.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -859,59 +785,49 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "constellation_id", - /* .docs = */ "Constellation ID", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "enable", - /* .docs = */ "Enable/Disable constellation", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "reserved_channels", - /* .docs = */ "Minimum number of channels reserved for this constellation", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "max_channels", - /* .docs = */ "Maximum number of channels to use for this constallation", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "option_flags", - /* .docs = */ "Constellation option Flags", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "constellation_id", + /* .docs = */ "Constellation ID", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "enable", + /* .docs = */ "Enable/Disable constellation", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved_channels", + /* .docs = */ "Minimum number of channels reserved for this constellation", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "max_channels", + /* .docs = */ "Maximum number of channels to use for this constallation", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "option_flags", + /* .docs = */ "Constellation option Flags", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -931,37 +847,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "max_channels", - /* .docs = */ "", - /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "max_channels", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "config_count", - /* .docs = */ "", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "config_count", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "settings", - /* .docs = */ "", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 0, - /* .counter_idx = */ microstrain::Index(1) /* config_count */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "settings", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {0, microstrain::Index(1) /* config_count */}, + /* .condition = */ {}, }, }; @@ -1001,48 +911,40 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "enable_sbas", - /* .docs = */ "0 - SBAS Disabled, 1 - SBAS enabled", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "sbas_options", - /* .docs = */ "SBAS options, see definition", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "num_included_prns", - /* .docs = */ "Number of SBAS PRNs to include in search (0 = include all)", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "included_prns", - /* .docs = */ "List of specific SBAS PRNs to search for", - /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 39, - /* .counter_idx = */ microstrain::Index(2) /* num_included_prns */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "enable_sbas", + /* .docs = */ "0 - SBAS Disabled, 1 - SBAS enabled", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sbas_options", + /* .docs = */ "SBAS options, see definition", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "num_included_prns", + /* .docs = */ "Number of SBAS PRNs to include in search (0 = include all)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "included_prns", + /* .docs = */ "List of specific SBAS PRNs to search for", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {39, microstrain::Index(2) /* num_included_prns */}, + /* .condition = */ {}, }, }; @@ -1081,26 +983,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "option", - /* .docs = */ "Assisted fix options", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "option", + /* .docs = */ "Assisted fix options", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "flags", - /* .docs = */ "Assisted fix flags (set to 0xFF)", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "flags", + /* .docs = */ "Assisted fix flags (set to 0xFF)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1120,37 +1018,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "tow", - /* .docs = */ "GPS Time of week [seconds]", - /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "tow", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "week_number", - /* .docs = */ "GPS Weeks since 1980 [weeks]", - /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "week_number", + /* .docs = */ "GPS Weeks since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "accuracy", - /* .docs = */ "Accuracy of time information [seconds]", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "accuracy", + /* .docs = */ "Accuracy of time information [seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1170,59 +1062,49 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "target_descriptor", - /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.\nSupported values are accel (0x04), gyro (0x05), mag (0x06), and\npressure (0x17), provided the data is supported by the device.\nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "enable", - /* .docs = */ "The target data will be filtered if this is true.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "manual", - /* .docs = */ "If false, the cutoff frequency is set to half of the\nstreaming rate as configured by the message format command.\nOtherwise, the cutoff frequency is set according to the\nfollowing 'frequency' parameter.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "frequency", - /* .docs = */ "-3dB cutoff frequency in Hz. Will not affect filtering if 'manual' is false.", - /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "reserved", - /* .docs = */ "Reserved, set to 0x00.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "target_descriptor", + /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.\nSupported values are accel (0x04), gyro (0x05), mag (0x06), and\npressure (0x17), provided the data is supported by the device.\nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "enable", + /* .docs = */ "The target data will be filtered if this is true.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "manual", + /* .docs = */ "If false, the cutoff frequency is set to half of the\nstreaming rate as configured by the message format command.\nOtherwise, the cutoff frequency is set according to the\nfollowing 'frequency' parameter.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "-3dB cutoff frequency in Hz. Will not affect filtering if 'manual' is false.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "Reserved, set to 0x00.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1264,15 +1146,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "source", - /* .docs = */ "", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "source", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1367,48 +1247,40 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "pin", - /* .docs = */ "GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "feature", - /* .docs = */ "Determines how the pin will be used.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "behavior", - /* .docs = */ "Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.)", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "pin_mode", - /* .docs = */ "GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "pin", + /* .docs = */ "GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "feature", + /* .docs = */ "Determines how the pin will be used.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "behavior", + /* .docs = */ "Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.)", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pin_mode", + /* .docs = */ "GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1428,26 +1300,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "pin", - /* .docs = */ "GPIO pin number counting from 1. Cannot be 0.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, false, false, false, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "pin", + /* .docs = */ "GPIO pin number counting from 1. Cannot be 0.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "state", - /* .docs = */ "The pin state.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "state", + /* .docs = */ "The pin state.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1486,37 +1354,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "mode", - /* .docs = */ "Mode setting.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "mode", + /* .docs = */ "Mode setting.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "scaling", - /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "scaling", + /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "uncertainty", - /* .docs = */ "Uncertainty in encoder counts to distance translation (1-sigma value) [m/m].", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "uncertainty", + /* .docs = */ "Uncertainty in encoder counts to distance translation (1-sigma value) [m/m].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1554,26 +1416,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "type", - /* .docs = */ "Trigger or action type, as defined in the respective setup command.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "type", + /* .docs = */ "Trigger or action type, as defined in the respective setup command.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "count", - /* .docs = */ "This is the maximum number of instances supported for this type.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "count", + /* .docs = */ "This is the maximum number of instances supported for this type.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1593,15 +1451,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "query", - /* .docs = */ "What type of information to retrieve.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "query", + /* .docs = */ "What type of information to retrieve.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1642,26 +1498,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "instance", - /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "instance", + /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "mode", - /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "mode", + /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1700,26 +1552,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "type", - /* .docs = */ "Configured trigger type.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "type", + /* .docs = */ "Configured trigger type.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "status", - /* .docs = */ "Trigger status.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "status", + /* .docs = */ "Trigger status.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1739,26 +1587,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "requested_count", - /* .docs = */ "Number of entries requested. If 0, requests all trigger slots.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "requested_count", + /* .docs = */ "Number of entries requested. If 0, requests all trigger slots.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "requested_instances", - /* .docs = */ "List of trigger instances to query.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 20, - /* .counter_idx = */ microstrain::Index(0) /* requested_count */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "requested_instances", + /* .docs = */ "List of trigger instances to query.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {20, microstrain::Index(0) /* requested_count */}, + /* .condition = */ {}, }, }; @@ -1777,26 +1621,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "action_type", - /* .docs = */ "Configured action type.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "action_type", + /* .docs = */ "Configured action type.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "trigger_id", - /* .docs = */ "Associated trigger instance.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "trigger_id", + /* .docs = */ "Associated trigger instance.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1816,26 +1656,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "requested_count", - /* .docs = */ "Number of entries requested. If 0, requests all action slots.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "requested_count", + /* .docs = */ "Number of entries requested. If 0, requests all action slots.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "requested_instances", - /* .docs = */ "List of action instances to query.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 20, - /* .counter_idx = */ microstrain::Index(0) /* requested_count */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "requested_instances", + /* .docs = */ "List of action instances to query.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ {20, microstrain::Index(0) /* requested_count */}, + /* .condition = */ {}, }, }; @@ -1875,26 +1711,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "pin", - /* .docs = */ "GPIO pin number.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "pin", + /* .docs = */ "GPIO pin number.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "mode", - /* .docs = */ "How the pin state affects the trigger.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "mode", + /* .docs = */ "How the pin state affects the trigger.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -1932,70 +1764,76 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "desc_set", - /* .docs = */ "Descriptor set of target data quantity.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "field_desc", - /* .docs = */ "Field descriptor of target data quantity.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "param_id", - /* .docs = */ "1-based index of the target parameter within the MIP field. E.g. for Scaled Accel (0x80,0x04) a value of 2 would represent the Y axis.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "type", - /* .docs = */ "Determines the type of comparison.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "", - /* .docs = */ "", - /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "", - /* .docs = */ "", - /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "desc_set", + /* .docs = */ "Descriptor set of target data quantity.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "field_desc", + /* .docs = */ "Field descriptor of target data quantity.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "param_id", + /* .docs = */ "1-based index of the target parameter within the MIP field. E.g. for Scaled Accel (0x80,0x04) a value of 2 would represent the Y axis.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "type", + /* .docs = */ "Determines the type of comparison.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "low_thres", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::WINDOW)} /* type == WINDOW */, + }, + { + /* .name = */ "int_thres", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::INTERVAL)} /* type == INTERVAL */, + }, + { + /* .name = */ "high_thres", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::WINDOW)} /* type == WINDOW */, + }, + { + /* .name = */ "interval", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::INTERVAL)} /* type == INTERVAL */, }, }; @@ -2014,26 +1852,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "logic_table", - /* .docs = */ "The last column of a truth table describing the output given the state of each input.", - /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "logic_table", + /* .docs = */ "The last column of a truth table describing the output given the state of each input.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "input_triggers", - /* .docs = */ "List of trigger IDs for inputs. Use 0 for unused inputs.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 4, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "input_triggers", + /* .docs = */ "List of trigger IDs for inputs. Use 0 for unused inputs.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2073,37 +1907,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "gpio", - /* .docs = */ "", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "gpio", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* type */, static_cast(commands_3dm::EventTrigger::Type::GPIO)} /* type == GPIO */, }, { - /* .name = */ "threshold", - /* .docs = */ "", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "threshold", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* type */, static_cast(commands_3dm::EventTrigger::Type::THRESHOLD)} /* type == THRESHOLD */, }, { - /* .name = */ "combination", - /* .docs = */ "", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "combination", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* type */, static_cast(commands_3dm::EventTrigger::Type::COMBINATION)} /* type == COMBINATION */, }, }; @@ -2123,37 +1951,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "instance", - /* .docs = */ "Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "instance", + /* .docs = */ "Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "type", - /* .docs = */ "Type of trigger to configure.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "type", + /* .docs = */ "Type of trigger to configure.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "parameters", - /* .docs = */ "", - /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "parameters", + /* .docs = */ "", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2195,26 +2017,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "pin", - /* .docs = */ "GPIO pin number.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "pin", + /* .docs = */ "GPIO pin number.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "mode", - /* .docs = */ "Behavior of the pin.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "mode", + /* .docs = */ "Behavior of the pin.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2233,48 +2051,40 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "desc_set", - /* .docs = */ "MIP data descriptor set.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "decimation", - /* .docs = */ "Decimation from the base rate.\nIf 0, a packet is emitted each time the trigger activates.\nOtherwise, packets will be streamed while the trigger is active.\nThe internal decimation counter is reset if the trigger deactivates.", - /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "num_fields", - /* .docs = */ "Number of mip fields in the packet. Limited to 12.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "descriptors", - /* .docs = */ "List of field descriptors.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 20, - /* .counter_idx = */ microstrain::Index(2) /* num_fields */, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "desc_set", + /* .docs = */ "MIP data descriptor set.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "decimation", + /* .docs = */ "Decimation from the base rate.\nIf 0, a packet is emitted each time the trigger activates.\nOtherwise, packets will be streamed while the trigger is active.\nThe internal decimation counter is reset if the trigger deactivates.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "num_fields", + /* .docs = */ "Number of mip fields in the packet. Limited to 12.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "List of field descriptors.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ {20, microstrain::Index(2) /* num_fields */}, + /* .condition = */ {}, }, }; @@ -2313,26 +2123,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "gpio", - /* .docs = */ "Gpio parameters, if type == GPIO. Ignore otherwise.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "gpio", + /* .docs = */ "Gpio parameters, if type == GPIO. Ignore otherwise.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(2) /* type */, static_cast(commands_3dm::EventAction::Type::GPIO)} /* type == GPIO */, }, { - /* .name = */ "message", - /* .docs = */ "Message parameters, if type == MESSAGE. Ignore otherwise.", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "message", + /* .docs = */ "Message parameters, if type == MESSAGE. Ignore otherwise.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(2) /* type */, static_cast(commands_3dm::EventAction::Type::MESSAGE)} /* type == MESSAGE */, }, }; @@ -2352,48 +2158,40 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "instance", - /* .docs = */ "Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "trigger", - /* .docs = */ "Trigger ID number.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "type", - /* .docs = */ "Type of action to configure.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "parameters", - /* .docs = */ "", - /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "instance", + /* .docs = */ "Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "trigger", + /* .docs = */ "Trigger ID number.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "type", + /* .docs = */ "Type of action to configure.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "parameters", + /* .docs = */ "", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2413,15 +2211,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "bias", - /* .docs = */ "accelerometer bias in the sensor frame (x,y,z) [g]", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "bias", + /* .docs = */ "accelerometer bias in the sensor frame (x,y,z) [g]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2441,15 +2237,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "bias", - /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "bias", + /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2469,15 +2263,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "averaging_time_ms", - /* .docs = */ "Averaging time [milliseconds]", - /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "averaging_time_ms", + /* .docs = */ "Averaging time [milliseconds]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2497,15 +2289,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "offset", - /* .docs = */ "hard iron offset in the sensor frame (x,y,z) [Gauss]", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "offset", + /* .docs = */ "hard iron offset in the sensor frame (x,y,z) [Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2525,15 +2315,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "offset", - /* .docs = */ "soft iron matrix [dimensionless]", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "offset", + /* .docs = */ "soft iron matrix [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2553,15 +2341,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "enable", - /* .docs = */ "If true, coning and sculling compensation is enabled.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "enable", + /* .docs = */ "If true, coning and sculling compensation is enabled.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2581,37 +2367,31 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "roll", - /* .docs = */ "[radians]", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "roll", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "pitch", - /* .docs = */ "[radians]", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "pitch", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "yaw", - /* .docs = */ "[radians]", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "yaw", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2631,15 +2411,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "q", - /* .docs = */ "Unit length quaternion representing transform [w, i, j, k]", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "q", + /* .docs = */ "Unit length quaternion representing transform [w, i, j, k]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2659,15 +2437,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "dcm", - /* .docs = */ "3 x 3 direction cosine matrix, stored in row-major order", - /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "dcm", + /* .docs = */ "3 x 3 direction cosine matrix, stored in row-major order", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2687,48 +2463,40 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "pitch_roll_enable", - /* .docs = */ "Enable Pitch/Roll corrections", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "heading_enable", - /* .docs = */ "Enable Heading corrections (only available on devices with magnetometer)", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "pitch_roll_time_constant", - /* .docs = */ "Time constant associated with the pitch/roll corrections [s]", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "heading_time_constant", - /* .docs = */ "Time constant associated with the heading corrections [s]", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "pitch_roll_enable", + /* .docs = */ "Enable Pitch/Roll corrections", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading_enable", + /* .docs = */ "Enable Heading corrections (only available on devices with magnetometer)", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pitch_roll_time_constant", + /* .docs = */ "Time constant associated with the pitch/roll corrections [s]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading_time_constant", + /* .docs = */ "Time constant associated with the heading corrections [s]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2770,26 +2538,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "sensor", - /* .docs = */ "Which type of sensor will get the new range value.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "sensor", + /* .docs = */ "Which type of sensor will get the new range value.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "setting", - /* .docs = */ "Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "setting", + /* .docs = */ "Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2808,26 +2572,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - /* .name = */ "setting", - /* .docs = */ "The value used in the 3DM Sensor Range command and response.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "setting", + /* .docs = */ "The value used in the 3DM Sensor Range command and response.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, { - /* .name = */ "range", - /* .docs = */ "The actual range value. Units depend on the sensor type.", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "range", + /* .docs = */ "The actual range value. Units depend on the sensor type.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2847,15 +2607,13 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "sensor", - /* .docs = */ "The sensor to query. Cannot be ALL.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "sensor", + /* .docs = */ "The sensor to query. Cannot be ALL.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, }, }; @@ -2875,59 +2633,49 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "desc_set", - /* .docs = */ "Descriptor set of the quantity to be filtered.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "field_desc", - /* .docs = */ "Field descriptor of the quantity to be filtered.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "enable", - /* .docs = */ "The filter will be enabled if this is true.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "manual", - /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, - }, - { - /* .name = */ "frequency", - /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", - /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "desc_set", + /* .docs = */ "Descriptor set of the quantity to be filtered.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "field_desc", + /* .docs = */ "Field descriptor of the quantity to be filtered.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "enable", + /* .docs = */ "The filter will be enabled if this is true.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "manual", + /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false}, + /* .count = */ 1, + /* .condition = */ {}, }, }; diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index 3abe75dda..b18b18b0b 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -1,24 +1,320 @@ -#pragma once + + +#include "common.hpp" #include #include - namespace mip::metadata { + template<> struct MetadataFor { using type = commands_base::Ping; + static constexpr inline ParameterInfo parameters[] = { + + }; + static constexpr inline FieldInfo value = { - /* .name = */ "Ping", + /* .name = */ "commands_base::Ping", /* .title = */ "Ping", - /* .docs = */ "Pings the device.", - /* .parameters = */ { + /* .docs = */ "Test Communications with a device.\n\nThe Device will respond with an ACK, if present and operating correctly.\n\nIf the device is not in a normal operating mode, it may NACK.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::SetIdle; + + static constexpr inline ParameterInfo parameters[] = { + + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::SetIdle", + /* .title = */ "Set to idle", + /* .docs = */ "Turn off all device data streams.\n\nThe Device will respond with an ACK, if present and operating correctly.\nThis command will suspend streaming (if enabled) or wake the device from sleep (if sleeping) to allow it to respond to status and setup commands.\nYou may restore the device mode by issuing the Resume command.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::BaseDeviceInfo; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "firmware_version", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "model_name", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "model_number", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "serial_number", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "lot_number", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "device_options", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "BaseDeviceInfo", + /* .title = */ "Base Device Info", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::GetDeviceInfo::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "device_info", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::GetDeviceInfo::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::GetDeviceInfo; + + static constexpr inline ParameterInfo parameters[] = { + + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::GetDeviceInfo", + /* .title = */ "Get device information", + /* .docs = */ "Get the device ID strings and firmware version number.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::GetDeviceDescriptors::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "descriptors", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::GetDeviceDescriptors::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::GetDeviceDescriptors; + + static constexpr inline ParameterInfo parameters[] = { + + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::GetDeviceDescriptors", + /* .title = */ "Get device descriptors", + /* .docs = */ "Get the command and data descriptors supported by the device.\n\nReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.\nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::BuiltInTest::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "result", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::BuiltInTest::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::BuiltInTest; + + static constexpr inline ParameterInfo parameters[] = { + + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::BuiltInTest", + /* .title = */ "Built in test", + /* .docs = */ "Run the device Built-In Test (BIT).\n\nThe Built-In Test command always returns a 32 bit value.\nA value of 0 means that all tests passed.\nA non-zero value indicates that not all tests passed.\nReference the device user manual to decode the result.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::Resume; + + static constexpr inline ParameterInfo parameters[] = { + + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::Resume", + /* .title = */ "Resume", + /* .docs = */ "Take the device out of idle mode.\n\nThe device responds with ACK upon success.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::GetExtendedDescriptors::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "descriptors", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::GetExtendedDescriptors::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, /* .proprietary = */ false, @@ -26,53 +322,254 @@ struct MetadataFor }; }; +template<> +struct MetadataFor +{ + using type = commands_base::GetExtendedDescriptors; + + static constexpr inline ParameterInfo parameters[] = { + + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::GetExtendedDescriptors", + /* .title = */ "Get device descriptors (extended)", + /* .docs = */ "Get the command and data descriptors supported by the device.\n\nReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.\nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::ContinuousBit::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "result", + /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::ContinuousBit::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::ContinuousBit; + + static constexpr inline ParameterInfo parameters[] = { + + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::ContinuousBit", + /* .title = */ "Continuous built-in test", + /* .docs = */ "Report result of continuous built-in test.\n\nThis test is non-disruptive but is not as thorough as the commanded BIT.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::CommSpeed::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "port", + /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "baud", + /* .docs = */ "Port baud rate. Must be a supported rate.", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::CommSpeed::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; template<> struct MetadataFor { using type = commands_base::CommSpeed; - //using Rsp = Cmd::Response; - // - //static constexpr inline const char* NAME = "CommSpeed"; - //static constexpr inline const char* DOC_NAME = "Comm Port Speed"; - //static constexpr CompositeDescriptor DESCRIPTOR = Cmd::DESCRIPTOR; - static constexpr inline std::initializer_list PARAMETERS = { + static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { /* .name = */ "port", - /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports.", - /* .type = */ {Type::U8}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, }, { /* .name = */ "baud", /* .docs = */ "Port baud rate. Must be a supported rate.", - /* .type = */ {Type::U32}, - /* .accessor = */ utils::access, - /* .functions = */ {true,false,false,false,false}, + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, }, }; static constexpr inline FieldInfo value = { - /* .name = */ "CommSpeed", + /* .name = */ "commands_base::CommSpeed", /* .title = */ "Comm Port Speed", - /* .docs = */ "Changes the comm port speed.", - /* .parameters = */ PARAMETERS, + /* .docs = */ "Controls the baud rate of a specific port on the device.\n\nPlease see the device user manual for supported baud rates on each port.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", + /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true,true,true,true,true}, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::GpsTimeUpdate::FieldId; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "WEEK_NUMBER", "Week number." }, + { 2, "TIME_OF_WEEK", "Time of week in seconds." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "field_id", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_base::GpsTimeUpdate; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "field_id", + /* .docs = */ "Determines how to interpret value.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "value", + /* .docs = */ "Week number or time of week, depending on the field_id.", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::GpsTimeUpdate", + /* .title = */ "GPS Time Update Command", + /* .docs = */ "Set device internal GPS time\nWhen combined with a PPS input signal applied to the I/O connector, this command enables complete synchronization of data outputs\nwith an external time base, such as GPS system time. Since the hardware PPS synchronization can only detect the fractional number of seconds when pulses arrive,\ncomplete synchronization requires that the user provide the whole number of seconds via this command. After achieving PPS synchronization, this command should be sent twice: once to set the time-of-week and once to set the week number. PPS synchronization can be verified by monitoring the time sync status message (0xA0, 0x02) or the valid flags of any shared external timestamp (0x--, D7) data field.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, false, false, false, false, true}, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_base::SoftReset; + + static constexpr inline ParameterInfo parameters[] = { + + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_base::SoftReset", + /* .title = */ "Reset device", + /* .docs = */ "Resets the device.\n\nDevice responds with ACK and immediately resets.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, /* .proprietary = */ false, /* .response = */ nullptr, }; }; -static constexpr inline std::initializer_list ALL_BASE_COMMANDS = { +static constexpr inline std::initializer_list ALL_COMMANDS_BASE = { &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, }; +} // namespace mip::metadata -} // namespace mip diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index 62d2e02b8..d856895c9 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -37,36 +37,164 @@ struct MetadataFor }; }; -template<> -struct MetadataFor +//template<> +//struct MetadataFor +//{ +// using type = Vector3f; +// +// static constexpr inline ParameterInfo parameters[] = { +// { +// .name = "x", +// .docs = "X axis", +// .type = {Type::FLOAT}, +// .accessor = nullptr, +// }, +// { +// .name = "y", +// .docs = "Y axis", +// .type = {Type::FLOAT}, +// .accessor = nullptr, +// }, +// { +// .name = "z", +// .docs = "Z axis", +// .type = {Type::FLOAT}, +// .accessor = nullptr, +// }, +// }; +// +// static constexpr inline StructInfo value = { +// .name = "Vector3f", +// .title = "3D Vector", +// .docs = "Represents a 3D vector of floats.", +// .parameters = parameters, +// }; +//}; + + +template +struct MetadataFor> { - using type = Vector3f; + using type = Vector; static constexpr inline ParameterInfo parameters[] = { { .name = "x", .docs = "X axis", - .type = {Type::FLOAT}, + .type = {utils::ParamType::value}, .accessor = nullptr, }, { .name = "y", .docs = "Y axis", - .type = {Type::FLOAT}, + .type = {utils::ParamType::value}, .accessor = nullptr, }, { .name = "z", .docs = "Z axis", + .type = {utils::ParamType::value}, + .accessor = nullptr, + }, + { + .name = "w", + .docs = "W axis", + .type = {utils::ParamType::value}, + .accessor = nullptr, + }, + }; + + + static constexpr inline StructInfo values_f[] = { + { + .name = "Vector2f", + .title = "Vector2f", + .docs = "2-dimensional vector of floats", + .parameters = {parameters, 2} + }, + { + .name = "Vector3f", + .title = "Vector3f", + .docs = "3-dimensional vector of floats", + .parameters = {parameters, 3} + }, + { + .name = "Vector4f", + .title = "Vector4f", + .docs = "4-dimensional vector of floats", + .parameters = {parameters, 4} + }, + }; + static constexpr inline StructInfo values_d[] = { + { + .name = "Vector2d", + .title = "Vector2d", + .docs = "2-dimensional vector of doubles", + .parameters = {parameters, 2} + }, + { + .name = "Vector3d", + .title = "Vector3d", + .docs = "3-dimensional vector of doubles", + .parameters = {parameters, 3} + }, + { + .name = "Vector4d", + .title = "Vector4d", + .docs = "4-dimensional vector of doubles", + .parameters = {parameters, 4} + }, + }; + + static_assert(std::is_floating_point_v, "Expected either float or double"); + static_assert(N >= 2 && N <= 4, "N should be in the range [2,4]."); + + static constexpr inline const StructInfo& value = std::is_same_v ? values_d[N-2] : values_f[N-2]; +}; + + +template<> +struct MetadataFor +{ + using type = Matrix3f; + + static constexpr inline ParameterInfo parameters[] = { + { + .name = "m", + .docs = "Matrix data", .type = {Type::FLOAT}, .accessor = nullptr, + .count = 3, + }, + }; + + static constexpr inline StructInfo value = { + .name = "Matrix3f", + .title = "3x3 Float Matrix", + .docs = "Represents a 3D matrix of floats.", + .parameters = parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = Matrix3d; + + static constexpr inline ParameterInfo parameters[] = { + { + .name = "m", + .docs = "Matrix data", + .type = {Type::DOUBLE}, + .accessor = nullptr, + .count = 3, }, }; static constexpr inline StructInfo value = { - .name = "Vector3f", - .title = "3D Vector", - .docs = "Represents a 3D vector of floats.", + .name = "Matrix3f", + .title = "3x3 Double Matrix", + .docs = "Represents a 3D matrix of doubles.", .parameters = parameters, }; }; diff --git a/src/cpp/mip/metadata/mip_all_definitions.hpp b/src/cpp/mip/metadata/mip_all_definitions.hpp index 218674a4e..f26d80ab3 100644 --- a/src/cpp/mip/metadata/mip_all_definitions.hpp +++ b/src/cpp/mip/metadata/mip_all_definitions.hpp @@ -9,7 +9,7 @@ namespace mip::metadata { static constexpr inline std::initializer_list< const std::initializer_list* > ALL_COMMANDS = { - &ALL_BASE_COMMANDS, + &ALL_COMMANDS_BASE, // &ALL_3DM_COMMANDS, }; static constexpr inline std::initializer_list< const std::initializer_list* > ALL_DATA = { @@ -18,7 +18,7 @@ static constexpr inline std::initializer_list< const std::initializer_list* > ALL_FIELDS = { // Commands - &ALL_BASE_COMMANDS, + &ALL_COMMANDS_BASE, // &ALL_3DM_COMMANDS, // Data &ALL_SENSOR_DATA, diff --git a/src/cpp/mip/metadata/mip_metadata.hpp b/src/cpp/mip/metadata/mip_metadata.hpp index 4b5ece288..7d7552737 100644 --- a/src/cpp/mip/metadata/mip_metadata.hpp +++ b/src/cpp/mip/metadata/mip_metadata.hpp @@ -39,16 +39,13 @@ struct MetadataFor inline void* accessFunctionSelector(void* p) { return static_cast(p); } static constexpr inline ParameterInfo FUNCTION_SELECTOR_PARAM = { - /* .name = */ "function", - /* .docs = */ "Standard MIP function selector", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ accessFunctionSelector, - ///* .byte_offset = */ 0, - /* .functions = */ {true,true,true,true,true}, - /* .count = */ 1, - /* .counter_idx = */ {}, - /* .union_index = */ {}, - /* .union_value = */ 0, + /* .name = */ "function", + /* .docs = */ "Standard MIP function selector", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ accessFunctionSelector, + /* .functions = */ {true,true,true,true,true}, + /* .count = */ 1, + /* .condition = */ {}, }; @@ -75,18 +72,103 @@ auto& get(typename EnableForFieldTypes::type& field) } -template -ParamType get(FieldType& field) -{ -} - -template -auto get(FieldType& field) -{ - const ParameterInfo& paramInfo = MetadataFor::PARAMETERS[ParameterIndex]; - - -} - +//template +//ParamType get(FieldType& field) +//{ +//} +// +//template +//auto get(FieldType& field) +//{ +// const ParameterInfo& paramInfo = MetadataFor::PARAMETERS[ParameterIndex]; +// +// +//} + + +//class Analyzer +//{ +//public: +// Analyzer(microstrain::Serializer serializer) : m_serializer(serializer) {} +// +// bool analyze(const StructInfo& info) +// { +// size_t nextOffsetEntry = 0; +// +// for(const ParameterInfo& param : info.parameters) +// { +// if(param.count.paramIdx.isValid(info.parameters.size())) +// { +// +// } +// } +// } +//private: +// size_t getOffsetForParameter(const ParameterInfo* parameters, size_t index) const +// { +// for(size_t i=0; i m_offsets; +//}; +// +// +// +//constexpr size_t getParameterOffset(microstrain::Serializer serializer, microstrain::Index parameterId) +//{ +// const auto& parameters = MetadataFor::parameters; +// if(parameterId.isValid(parameters.size())) +// return -1; +// +// size_t offset = 0; +// +// for(auto i=microstrain::Index(0); i(info)->type); + + case Type::BITFIELD: + if(!info) + return 0; + return sizeForBasicType(static_cast(info)->type); + + default: + return 0; + } +} +constexpr size_t sizeForBasicType(const TypeInfo& type) { return sizeForBasicType(type.type, type.infoPtr); } + struct ParameterInfo { + struct Count + { + constexpr Count() = default; + constexpr Count(uint8_t n) : count(n) {} + constexpr Count(uint8_t n, microstrain::Id id) : count(n), paramIdx(id) {} + + uint8_t count = 1; ///< Fixed size if paramIdx unassigned. + microstrain::Id paramIdx = {}; ///< If assigned, specifies parameter that holds the actual runtime count. + + constexpr bool isFixed() const { return count > 0 && !paramIdx.isAssigned(); } + constexpr bool hasCounter() const { return paramIdx.isAssigned(); } + }; + + struct Condition + { + enum class Type : uint8_t + { + NONE = 0, ///< No condition, member always valid + ENUM = 1, ///< Enum value selector (e.g. for parameters in unions) + //PRODUCT = 2, ///< Depends on product variant (TBD) + //OPTIONAL = 2, ///< Parameter can be omitted (TBD) + }; + + Type type = Type::NONE; ///< Type of condition. + microstrain::Id paramIdx = {}; ///< Index of enum parameter identifying whether this parameter is enabled. + uint16_t value = 0; ///< Value of the enum parameter which activates this parameter. + + constexpr bool hasCondition() const { return type != Type::NONE; } + }; + using Accessor = void* (*)(void*); const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). @@ -137,10 +207,8 @@ struct ParameterInfo TypeInfo type; ///< Data type. Accessor accessor = nullptr; ///< Obtains a reference to the member variable. FuncBits functions; ///< This parameter is required for the specified function selectors. - uint8_t count = 1; ///< Number of elements. This is a maximum value when counter_idx != 0. - microstrain::Id counter_param; ///< When valid, this specifies the parameter holding the runtime count, relative to this parameter's index. - microstrain::Id union_param; ///< When type is UNION, this specifies the parameter that controls which union member is active (the discriminator). - uint16_t union_value = 0; ///< When in a union, this specifies the value of the discriminator parameter that selects this member. + Count count; ///< Number of instances for arrays. + Condition condition; ///< For conditionally-enabled parameters like those in unions. }; diff --git a/src/cpp/mip/metadata/utils.hpp b/src/cpp/mip/metadata/utils.hpp index 199b44d5c..46e5a6f94 100644 --- a/src/cpp/mip/metadata/utils.hpp +++ b/src/cpp/mip/metadata/utils.hpp @@ -11,6 +11,7 @@ namespace mip::metadata::utils // template struct ParamType { static inline constexpr auto value = Type::NONE; }; +template<> struct ParamType { static constexpr inline auto value = Type::CHAR; }; template<> struct ParamType { static constexpr inline auto value = Type::BOOL; }; template<> struct ParamType { static constexpr inline auto value = Type::U8; }; template<> struct ParamType< int8_t, void> { static constexpr inline auto value = Type::S8; }; @@ -35,6 +36,7 @@ template struct ParamType:: template struct ParamEnum { using type = void; }; +template<> struct ParamEnum { using type = char; }; template<> struct ParamEnum { using type = bool; }; template<> struct ParamEnum { using type = uint8_t; }; template<> struct ParamEnum { using type = int8_t; }; From 26f0c238cce28696c04e66e7d69ad95cddd072eb Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 2 Jul 2024 12:37:09 -0400 Subject: [PATCH 046/147] Make Formatter class as the precursor to a parameter iteration class. Implement union formatting [WIP]. --- CMakeLists.txt | 2 +- examples/CSV/stringify.cpp | 178 +++++++++++++++++++++++++------------ 2 files changed, 121 insertions(+), 59 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e7f210c48..f365d75f2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.10) set(CMAKE_CXX_STANDARD 20) -#set(CMAKE_CXX_STANDARD_REQUIRED ON) +set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_C_STANDARD 11) set(CMAKE_C_STANDARD_REQUIRED ON) diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp index f1308ddef..5627d17d0 100644 --- a/examples/CSV/stringify.cpp +++ b/examples/CSV/stringify.cpp @@ -4,6 +4,7 @@ #include +#include #include #include #include @@ -21,6 +22,26 @@ using namespace mip::metadata; extern Definitions mipdefs; +struct Formatter +{ + static constexpr size_t MAX_PARAMETERS = 20; + + microstrain::Serializer serializer; + std::ostream& ss; + std::array offsets; + + std::ostream& formatEnum(const EnumInfo* info); + std::ostream& formatBitfield(const BitfieldInfo* info); + std::ostream& formatUnion(const UnionInfo* info, const StructInfo& parent, size_t offset_index); + std::ostream& formatStruct(const StructInfo* info, size_t offset_index=0); + + void formatParameter(const ParameterInfo& param, const StructInfo& parent, size_t offset_index=0); + + template + std::ostream& formatBasicType(); +}; + + //////////////////////////////////////////////////////////////////////////////// ///@brief Format an arithmetic type (including bool) from buffer to a string. /// @@ -32,7 +53,7 @@ extern Definitions mipdefs; ///@returns ss /// template -std::ostream& formatBasicType(std::ostream& ss, microstrain::Serializer& serializer) +std::ostream& Formatter::formatBasicType() { T value; if(serializer.extract(value)) @@ -79,7 +100,7 @@ static std::optional readIntegralValue(Type type, microstrain::Seriali /// ///@returns ss /// -std::ostream& formatEnum(std::ostream& ss, const EnumInfo* info, microstrain::Serializer& serializer) +std::ostream& Formatter::formatEnum(const EnumInfo* info) { if(!info) return ss << ""; @@ -109,7 +130,7 @@ std::ostream& formatEnum(std::ostream& ss, const EnumInfo* info, microstrain::Se /// ///@returns ss /// -std::ostream& formatBitfield(std::ostream& ss, const BitfieldInfo* info, microstrain::Serializer& serializer) +std::ostream& Formatter::formatBitfield(const BitfieldInfo* info) { if(!info) return ss << ""; @@ -137,6 +158,45 @@ std::ostream& formatBitfield(std::ostream& ss, const BitfieldInfo* info, microst return ss; } +void Formatter::formatParameter(const mip::metadata::ParameterInfo ¶m, const StructInfo& parent, size_t offset_index) +{ + switch(param.type.type) + { + case Type::NONE: + ss << "-"; + break; + + case Type::CHAR: formatBasicType(); break; + case Type::BOOL: formatBasicType(); break; + case Type::U8: formatBasicType(); break; + case Type::S8: formatBasicType< int8_t >(); break; + case Type::U16: formatBasicType(); break; + case Type::S16: formatBasicType< int16_t>(); break; + case Type::U32: formatBasicType(); break; + case Type::S32: formatBasicType< int32_t>(); break; + case Type::U64: formatBasicType(); break; + case Type::S64: formatBasicType< int64_t>(); break; + case Type::FLOAT: formatBasicType(); break; + case Type::DOUBLE: formatBasicType(); break; + + case Type::ENUM: + formatEnum(static_cast(param.type.infoPtr)); + break; + + case Type::BITFIELD: + formatBitfield(static_cast(param.type.infoPtr)); + break; + + case Type::STRUCT: + formatStruct(static_cast(param.type.infoPtr), offset_index); + break; + + case Type::UNION: + formatUnion(static_cast(param.type.infoPtr), parent, offset_index); + break; + } +} + //////////////////////////////////////////////////////////////////////////////// ///@brief Format union from buffer to a string. /// @@ -149,7 +209,7 @@ std::ostream& formatBitfield(std::ostream& ss, const BitfieldInfo* info, microst /// ///@returns ss /// -std::ostream& formatUnion(std::ostream& ss, const UnionInfo* info, const StructInfo& parent, microstrain::Serializer& serializer) +std::ostream& Formatter::formatUnion(const UnionInfo* info, const StructInfo& parent, size_t offset_index) { if(!info) return ss << ""; @@ -158,16 +218,31 @@ std::ostream& formatUnion(std::ostream& ss, const UnionInfo* info, const StructI ss << info->name << '{'; - // Todo - // const ParameterInfo* param = nullptr; - // - // for(const auto& p : info->parameters) - // { - // if(p.union_index < parent.parameters.size()) - // { - // - // } - // } + for(const auto& param : info->parameters) + { + // Enum condition, where the active union member depends on a previous parameter's value. + if(param.condition.type == ParameterInfo::Condition::Type::ENUM) + { + // Parameter index is within the parent's parameter array. + assert(param.condition.paramIdx.isValid(parent.parameters.size())); + const ParameterInfo &discriminant = parent.parameters[param.condition.paramIdx.index()]; + + // Index is within the offset array relative to the parent. + assert(offset_index+param.condition.paramIdx.index() < MAX_PARAMETERS); + const uint8_t offset = offsets[offset_index+param.condition.paramIdx.index()]; + + // Read value from serializer (jump back to the correct parameter offset, then back). + const size_t oldOffset = serializer.setOffset(offset); + std::optional value = readIntegralValue(discriminant.type.type, serializer); + serializer.setOffset(oldOffset); + + // If value was read successfully and it matches the condition value then display it. + if(value.has_value() && *value == param.condition.value) + { + formatParameter(param, parent, offset_index); + } + } + } ss << '}'; return ss; @@ -191,7 +266,7 @@ std::ostream& formatUnion(std::ostream& ss, const UnionInfo* info, const StructI /// ///@returns ss /// -std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, microstrain::Serializer& serializer) +std::ostream& Formatter::formatStruct(const StructInfo* info, size_t offset_index) { if(!info) return ss << ""; @@ -199,8 +274,6 @@ std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, microstrain return ss << "?"; // Keep track of the offset of each parameter so we can go back and look up array sizes, etc. - constexpr size_t MAX_PARAMETERS = 20; - std::array offsets; assert(info->parameters.size() <= MAX_PARAMETERS); // Increase MAX_PARAMETERS if this trips. //std::array offsets; @@ -209,6 +282,12 @@ std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, microstrain //const size_t baseOffset = serializer.offset(); + // Entry in 'offsets' representing the first parameter of this struct. + assert(offset_index + info->parameters.size() <= MAX_PARAMETERS); + // size_t base_index = offset_index; + // num_offsets += info->parameters.size(); + // Ensure there are enough entries in the offsets array. + ss << '{'; for(size_t i=0; iparameters.size(); i++) @@ -219,8 +298,11 @@ std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, microstrain ss << param.name << '='; - // Save offset of each parameter (necessary due to nested structs, etc. and variable length arrays). - offsets[i] = serializer.offset(); + // Save offset of each parameter in case it's an array count or union discriminator. + // This will clobber the offsets of nested structs (within this one), but those + // offsets won't be needed again. Only basic types can be counters or discriminators + // so only those parameters might need to be read later on. + offsets[offset_index+i] = (uint8_t)serializer.offset(); uint8_t count = param.count.count; if(param.count.hasCounter()) @@ -228,7 +310,11 @@ std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, microstrain assert(param.count.paramIdx.isValid(i)); // Array size can't come after the array const ParameterInfo& counter = info->parameters[param.count.paramIdx.index()]; - const size_t counterOffset = offsets[param.count.paramIdx.index()]; + const size_t counterOffset = offsets[offset_index+param.count.paramIdx.index()]; + + // Counters must be arithmetic types and can't be arrays. + assert(counter.type.isBasicType()); + assert(counter.count.count == 1 && !counter.count.hasCounter()); const size_t oldOffset = serializer.setOffset(counterOffset); std::optional counterValue = readIntegralValue(counter.type.type, serializer); @@ -241,49 +327,20 @@ std::ostream& formatStruct(std::ostream& ss, const StructInfo* info, microstrain continue; } - count = *counterValue; + count = (uint8_t)*counterValue; } if(param.count.count != 1) - ss << '['; + ss << (param.type.type == Type::CHAR ? '"' : '['); for(uint8_t j=0; j(ss, serializer); break; - case Type::U8: formatBasicType(ss, serializer); break; - case Type::S8: formatBasicType< int8_t >(ss, serializer); break; - case Type::U16: formatBasicType(ss, serializer); break; - case Type::S16: formatBasicType< int16_t>(ss, serializer); break; - case Type::U32: formatBasicType(ss, serializer); break; - case Type::S32: formatBasicType< int32_t>(ss, serializer); break; - case Type::U64: formatBasicType(ss, serializer); break; - case Type::S64: formatBasicType< int64_t>(ss, serializer); break; - case Type::FLOAT: formatBasicType(ss, serializer); break; - case Type::DOUBLE: formatBasicType(ss, serializer); break; - - case Type::ENUM: - formatEnum(ss, static_cast(param.type.infoPtr), serializer); - break; - - case Type::BITFIELD: - formatBitfield(ss, static_cast(param.type.infoPtr), serializer); - break; - - case Type::STRUCT: - formatStruct(ss, static_cast(param.type.infoPtr), serializer); - break; - - case Type::UNION: - formatUnion(ss, static_cast(param.type.infoPtr), *info, serializer); - break; - } + if(j > 0 && param.type.type != Type::CHAR) + ss << ", "; + + formatParameter(param, *info, offset_index+i); } if(param.count.count != 1) - ss << ']'; + ss << (param.type.type == Type::CHAR ? '"' : ']'); } ss << '}'; @@ -313,8 +370,13 @@ std::ostream& formatField(std::ostream& ss, const mip::FieldView& field) else { ss << info->name; - microstrain::Serializer serializer(field.payload(), field.payloadLength()); - formatStruct(ss, static_cast(info), serializer); + + Formatter formatter = { + microstrain::Serializer(field.payload(), field.payloadLength()), + ss, + }; + + formatter.formatStruct(static_cast(info)); } return ss; } From 6707a27edba298e5b2a1ee6e0d04372acb99e1eb Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 2 Jul 2024 19:22:31 -0400 Subject: [PATCH 047/147] Import updates from MipGenerator and fix formatBasicType to not print u8(0) as '\0'. --- examples/CSV/csv.cpp | 2 +- examples/CSV/stringify.cpp | 8 +- .../mip/metadata/definitions/commands_3dm.hpp | 2303 ++++++++- .../metadata/definitions/commands_aiding.hpp | 1081 +++++ .../metadata/definitions/commands_base.hpp | 54 +- .../metadata/definitions/commands_filter.hpp | 4141 +++++++++++++++++ .../metadata/definitions/commands_gnss.hpp | 331 ++ .../mip/metadata/definitions/commands_rtk.hpp | 770 +++ .../metadata/definitions/commands_system.hpp | 80 + .../mip/metadata/definitions/data_filter.hpp | 2877 ++++++++++++ .../mip/metadata/definitions/data_gnss.hpp | 3812 +++++++++++++++ .../mip/metadata/definitions/data_sensor.hpp | 821 +++- .../mip/metadata/definitions/data_shared.hpp | 381 ++ .../mip/metadata/definitions/data_system.hpp | 157 + src/cpp/mip/metadata/mip_all_definitions.hpp | 38 +- src/cpp/mip/metadata/mip_definitions.cpp | 18 +- 16 files changed, 16552 insertions(+), 322 deletions(-) create mode 100644 src/cpp/mip/metadata/definitions/commands_aiding.hpp create mode 100644 src/cpp/mip/metadata/definitions/commands_filter.hpp create mode 100644 src/cpp/mip/metadata/definitions/commands_gnss.hpp create mode 100644 src/cpp/mip/metadata/definitions/commands_rtk.hpp create mode 100644 src/cpp/mip/metadata/definitions/commands_system.hpp create mode 100644 src/cpp/mip/metadata/definitions/data_filter.hpp create mode 100644 src/cpp/mip/metadata/definitions/data_gnss.hpp create mode 100644 src/cpp/mip/metadata/definitions/data_shared.hpp create mode 100644 src/cpp/mip/metadata/definitions/data_system.hpp diff --git a/examples/CSV/csv.cpp b/examples/CSV/csv.cpp index d39bc3a7f..7988f91d7 100644 --- a/examples/CSV/csv.cpp +++ b/examples/CSV/csv.cpp @@ -35,7 +35,7 @@ void handleField(void*, const mip::FieldView& field, mip::Timestamp timestamp) int main(int argc, const char* argv[]) { - mipdefs.registerDefinitions(mip::metadata::ALL_SENSOR_DATA); + mipdefs.registerDefinitions(mip::metadata::ALL_FIELDS); std::unique_ptr utils; try { diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp index 5627d17d0..ccd904a98 100644 --- a/examples/CSV/stringify.cpp +++ b/examples/CSV/stringify.cpp @@ -56,10 +56,14 @@ template std::ostream& Formatter::formatBasicType() { T value; - if(serializer.extract(value)) + if(!serializer.extract(value)) + return ss << "?"; + if constexpr(std::is_same_v) return ss << value; + else if constexpr(std::is_same_v) + return ss << std::boolalpha << value; else - return ss << "?"; + return ss << (int)value; } //////////////////////////////////////////////////////////////////////////////// diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index c348e9b23..df5f7dd75 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -1,4 +1,4 @@ - +#pragma once #include "common.hpp" @@ -16,13 +16,12 @@ struct MetadataFor using type = commands_3dm::PollImuMessage; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "suppress_ack", /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -31,7 +30,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors in the descriptor list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -40,17 +39,21 @@ struct MetadataFor /* .docs = */ "Descriptor list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "PollImuMessage", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::PollImuMessage", /* .title = */ "None", /* .docs = */ "Poll the device for an IMU message with the specified format\n\nThis function polls for an IMU message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set IMU Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an IMU Data packet.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -60,13 +63,12 @@ struct MetadataFor using type = commands_3dm::PollGnssMessage; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "suppress_ack", /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -75,7 +77,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors in the descriptor list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -84,17 +86,21 @@ struct MetadataFor /* .docs = */ "Descriptor list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "PollGnssMessage", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::PollGnssMessage", /* .title = */ "None", /* .docs = */ "Poll the device for an GNSS message with the specified format\n\nThis function polls for a GNSS message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set GNSS Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a GNSS Data packet.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -104,13 +110,12 @@ struct MetadataFor using type = commands_3dm::PollFilterMessage; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "suppress_ack", /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -119,7 +124,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors in the format list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -128,17 +133,59 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "PollFilterMessage", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::PollFilterMessage", /* .title = */ "None", /* .docs = */ "Poll the device for an Estimation Filter message with the specified format\n\nThis function polls for an Estimation Filter message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Estimation Filter Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an Estimation Filter Data packet.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ImuMessageFormat::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ImuMessageFormat::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -154,7 +201,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -163,17 +210,59 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "ImuMessageFormat", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ImuMessageFormat", /* .title = */ "None", /* .docs = */ "Set, read, or save the format of the IMU data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GpsMessageFormat::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "Descriptor format list.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GpsMessageFormat::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -189,7 +278,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -198,17 +287,59 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GpsMessageFormat", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GpsMessageFormat", /* .title = */ "None", /* .docs = */ "Set, read, or save the format of the GNSS data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::FilterMessageFormat::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::FilterMessageFormat::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -224,7 +355,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -233,71 +364,159 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "FilterMessageFormat", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::FilterMessageFormat", /* .title = */ "None", /* .docs = */ "Set, read, or save the format of the Estimation Filter data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_3dm::ImuGetBaseRate; + using type = commands_3dm::ImuGetBaseRate::Response; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "rate", + /* .docs = */ "[hz]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ImuGetBaseRate::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; +}; - static constexpr inline StructInfo value = { - /* .name = */ "ImuGetBaseRate", +template<> +struct MetadataFor +{ + using type = commands_3dm::ImuGetBaseRate; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ImuGetBaseRate", /* .title = */ "Get IMU Data Base Rate", /* .docs = */ "Get the base rate for the IMU data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the IMU Message Format Command to set streaming data at a specified rate.", - /* .parameters = */ parameters, + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_3dm::GpsGetBaseRate; + using type = commands_3dm::GpsGetBaseRate::Response; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "rate", + /* .docs = */ "[hz]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GpsGetBaseRate::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; +}; - static constexpr inline StructInfo value = { - /* .name = */ "GpsGetBaseRate", +template<> +struct MetadataFor +{ + using type = commands_3dm::GpsGetBaseRate; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GpsGetBaseRate", /* .title = */ "Get GNSS Data Base Rate", /* .docs = */ "Get the base rate for the GNSS data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the GNSS Message Format Command to set streaming data at a specified rate.", - /* .parameters = */ parameters, + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_3dm::FilterGetBaseRate; + using type = commands_3dm::FilterGetBaseRate::Response; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "rate", + /* .docs = */ "[hz]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::FilterGetBaseRate::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; +}; - static constexpr inline StructInfo value = { - /* .name = */ "FilterGetBaseRate", +template<> +struct MetadataFor +{ + using type = commands_3dm::FilterGetBaseRate; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::FilterGetBaseRate", /* .title = */ "Get Estimation Filter Data Base Rate", /* .docs = */ "Get the base rate for the Estimation Filter data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the Estimation Filter Message Format Command to set streaming data at a specified rate.", - /* .parameters = */ parameters, + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -307,13 +526,12 @@ struct MetadataFor using type = commands_3dm::PollData; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "desc_set", /* .docs = */ "Data descriptor set. Must be supported.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -322,7 +540,7 @@ struct MetadataFor /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -331,7 +549,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors in the format list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -340,17 +558,59 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {82, microstrain::Index(2) /* num_descriptors */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "PollData", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::PollData", /* .title = */ "None", /* .docs = */ "Poll the device for a message with the specified descriptor set and format.\n\nThis function polls for a message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a normal Data packet.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetBaseRate::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "desc_set", + /* .docs = */ "Echoes the parameter in the command.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "rate", + /* .docs = */ "Base rate in Hz (0 = variable, unknown, or user-defined rate. Data will be sent when received).", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GetBaseRate::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -360,7 +620,6 @@ struct MetadataFor using type = commands_3dm::GetBaseRate; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "desc_set", /* .docs = */ "This is the data descriptor set. It must be a supported descriptor.", @@ -372,11 +631,62 @@ struct MetadataFor }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GetBaseRate", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GetBaseRate", /* .title = */ "Get Data Base Rate", /* .docs = */ "Get the base rate for the specified descriptor set in Hz.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::MessageFormat::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "desc_set", + /* .docs = */ "Echoes the descriptor set from the command.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "num_descriptors", + /* .docs = */ "Number of descriptors in the list.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "descriptors", + /* .docs = */ "List of descriptors and decimations.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {82, microstrain::Index(1) /* num_descriptors */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::MessageFormat::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -401,7 +711,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -410,17 +720,21 @@ struct MetadataFor /* .docs = */ "List of descriptors and decimations.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {82, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "MessageFormat", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::MessageFormat", /* .title = */ "None", /* .docs = */ "Set, read, or save the format for a given data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -530,13 +844,12 @@ struct MetadataFor using type = commands_3dm::NmeaPollData; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "suppress_ack", /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -545,7 +858,7 @@ struct MetadataFor /* .docs = */ "Number of format entries (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -554,17 +867,59 @@ struct MetadataFor /* .docs = */ "List of format entries.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {40, microstrain::Index(1) /* count */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "NmeaPollData", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::NmeaPollData", /* .title = */ "None", /* .docs = */ "Poll the device for a NMEA message with the specified format.\n\nThis function polls for a NMEA message using the provided format.\nIf the format is not provided, the device will attempt to use the\nstored format (set with the Set NMEA Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as normal NMEA messages.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::NmeaMessageFormat::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "count", + /* .docs = */ "Number of format entries (limited by payload size)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "format_entries", + /* .docs = */ "List of format entries.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {40, microstrain::Index(0) /* count */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::NmeaMessageFormat::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -580,7 +935,7 @@ struct MetadataFor /* .docs = */ "Number of format entries (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -589,17 +944,21 @@ struct MetadataFor /* .docs = */ "List of format entries.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {40, microstrain::Index(0) /* count */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "NmeaMessageFormat", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::NmeaMessageFormat", /* .title = */ "None", /* .docs = */ "Set, read, or save the NMEA message format.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -613,11 +972,44 @@ struct MetadataFor }; - static constexpr inline StructInfo value = { - /* .name = */ "DeviceSettings", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::DeviceSettings", /* .title = */ "None", /* .docs = */ "Save, Load, or Reset to Default the values for all device settings.\n\nWhen a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory.\n\nThis command should have a long timeout as it may take up to 1 second to complete.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {false, false, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::UartBaudrate::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "baud", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::UartBaudrate::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -633,17 +1025,21 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "UartBaudrate", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::UartBaudrate", /* .title = */ "None", /* .docs = */ "Read, Save, Load, or Reset to Default the baud rate of the main communication channel.\n\nFor all functions except 0x01 (use new settings), the new baud rate value is ignored.\nPlease see the device user manual for supported baud rates.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -673,13 +1069,12 @@ struct MetadataFor using type = commands_3dm::FactoryStreaming; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "action", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -688,17 +1083,59 @@ struct MetadataFor /* .docs = */ "Reserved. Set to 0x00.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "FactoryStreaming", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::FactoryStreaming", /* .title = */ "None", /* .docs = */ "Configures the device for recording data for technical support.\n\nThis command will configure all available data streams to predefined\nformats designed to be used with technical support.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::DatastreamControl::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "desc_set", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "enabled", + /* .docs = */ "", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::DatastreamControl::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -723,17 +1160,21 @@ struct MetadataFor /* .docs = */ "True or false to enable or disable the stream.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "DatastreamControl", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::DatastreamControl", /* .title = */ "None", /* .docs = */ "Enable/disable the selected data stream.\n\nEach data stream (descriptor set) can be enabled or disabled.\nThe default for the device is all streams enabled.\nFor all functions except 0x01 (use new setting),\nthe new enable flag value is ignored and can be omitted.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -839,6 +1280,62 @@ struct MetadataFor }; }; +template<> +struct MetadataFor +{ + using type = commands_3dm::ConstellationSettings::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "max_channels_available", + /* .docs = */ "Maximum channels available", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "max_channels_use", + /* .docs = */ "Maximum channels to use", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "config_count", + /* .docs = */ "Number of constellation configurations", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "settings", + /* .docs = */ "Constellation Settings", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {0, microstrain::Index(2) /* config_count */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ConstellationSettings::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -851,7 +1348,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -860,7 +1357,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -869,17 +1366,21 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {0, microstrain::Index(1) /* config_count */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "ConstellationSettings", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ConstellationSettings", /* .title = */ "None", /* .docs = */ "This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation.\n\nMaximum number of tracking channels to use (total for all constellations):\n0 to max_channels_available (from reply message)\n\nFor each constellation you wish to use, include a ConstellationSettings struct. Note the following:\n\nTotal number of tracking channels (sum of 'reserved_channels' for all constellations) must be <= 32:\n0 -> 32 Number of reserved channels\n0 -> 32 Max number of channels (>= reserved channels)\n\nThe factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3.\n\nWarning: SBAS functionality shall not be used in 'safety of life' applications!\nWarning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK.\nWarning: You cannot enable GLONASS and BeiDou at the same time.\nNote: Enabling SBAS and QZSS augments GPS accuracy.\nNote: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -903,6 +1404,62 @@ struct MetadataFor }; +template<> +struct MetadataFor +{ + using type = commands_3dm::GnssSbasSettings::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable_sbas", + /* .docs = */ "0 - SBAS Disabled, 1 - SBAS enabled", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sbas_options", + /* .docs = */ "SBAS options, see definition", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "num_included_prns", + /* .docs = */ "Number of SBAS PRNs to include in search (0 = include all)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "included_prns", + /* .docs = */ "List of specific SBAS PRNs to search for", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {39, microstrain::Index(2) /* num_included_prns */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GnssSbasSettings::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -915,7 +1472,7 @@ struct MetadataFor /* .docs = */ "0 - SBAS Disabled, 1 - SBAS enabled", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -924,7 +1481,7 @@ struct MetadataFor /* .docs = */ "SBAS options, see definition", /* .type = */ {Type::BITFIELD, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -933,7 +1490,7 @@ struct MetadataFor /* .docs = */ "Number of SBAS PRNs to include in search (0 = include all)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -942,17 +1499,21 @@ struct MetadataFor /* .docs = */ "List of specific SBAS PRNs to search for", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {39, microstrain::Index(2) /* num_included_prns */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GnssSbasSettings", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GnssSbasSettings", /* .title = */ "SBAS Settings", /* .docs = */ "Configure the SBAS subsystem\n\n\n", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -975,6 +1536,44 @@ struct MetadataFor }; +template<> +struct MetadataFor +{ + using type = commands_3dm::GnssAssistedFix::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "option", + /* .docs = */ "Assisted fix options", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "flags", + /* .docs = */ "Assisted fix flags (set to 0xFF)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GnssAssistedFix::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -987,7 +1586,7 @@ struct MetadataFor /* .docs = */ "Assisted fix options", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -996,33 +1595,36 @@ struct MetadataFor /* .docs = */ "Assisted fix flags (set to 0xFF)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GnssAssistedFix", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GnssAssistedFix", /* .title = */ "GNSS Assisted Fix Settings", /* .docs = */ "Set the options for assisted GNSS fix.\n\nDevices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM.\nThese storage mechanisms are used to retain information about the last good GNSS fix. This can greatly reduces the TTFF (Time To First Fix) depending on the age of the stored information.\nThe TTFF can be as low as one second, or up to the equivalent of a cold start. There is a small increase in power used when enabling assisted fix.\n\nThe fastest fix will be obtained by supplying the device with a GNSS Assist Time Update message containing the current GPS time immediately after subsequent power up.\nThis allows the device to determine if the last GNSS information saved is still fresh enough to improve the TTFF.\n\nNOTE: Non-volatile GNSS memory is cleared when going from an enabled state to a disabled state.\nWARNING: The clearing operation results in an erase operation on the GNSS Flash. The flash has a limited durability of 100,000 write/erase cycles", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_3dm::GnssTimeAssistance; + using type = commands_3dm::GnssTimeAssistance::Response; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "tow", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1031,7 +1633,7 @@ struct MetadataFor /* .docs = */ "GPS Weeks since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1040,51 +1642,168 @@ struct MetadataFor /* .docs = */ "Accuracy of time information [seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GnssTimeAssistance", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GnssTimeAssistance::Response", /* .title = */ "None", - /* .docs = */ "Provide the GNSS subsystem with initial time information.\n\nThis message is required immediately after power up if GNSS Assist was enabled when the device was powered off.\nThis will initialize the subsystem clock to help reduce the time to first fix (TTFF).", + /* .docs = */ "", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_3dm::ImuLowpassFilter; + using type = commands_3dm::GnssTimeAssistance; static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { - /* .name = */ "target_descriptor", - /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.\nSupported values are accel (0x04), gyro (0x05), mag (0x06), and\npressure (0x17), provided the data is supported by the device.\nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", - /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .name = */ "tow", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, { - /* .name = */ "enable", - /* .docs = */ "The target data will be filtered if this is true.", - /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .name = */ "week_number", + /* .docs = */ "GPS Weeks since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, { - /* .name = */ "manual", - /* .docs = */ "If false, the cutoff frequency is set to half of the\nstreaming rate as configured by the message format command.\nOtherwise, the cutoff frequency is set according to the\nfollowing 'frequency' parameter.", - /* .type = */ {Type::BOOL, nullptr}, + /* .name = */ "accuracy", + /* .docs = */ "Accuracy of time information [seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GnssTimeAssistance", + /* .title = */ "None", + /* .docs = */ "Provide the GNSS subsystem with initial time information.\n\nThis message is required immediately after power up if GNSS Assist was enabled when the device was powered off.\nThis will initialize the subsystem clock to help reduce the time to first fix (TTFF).", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, false, false, false, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ImuLowpassFilter::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "target_descriptor", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "enable", + /* .docs = */ "True if the filter is currently enabled.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "manual", + /* .docs = */ "True if the filter cutoff was manually configured.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "The cutoff frequency of the filter. If the filter is in\nauto mode, this value is unspecified.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "Reserved and must be ignored.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ImuLowpassFilter::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ImuLowpassFilter; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "target_descriptor", + /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.\nSupported values are accel (0x04), gyro (0x05), mag (0x06), and\npressure (0x17), provided the data is supported by the device.\nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "enable", + /* .docs = */ "The target data will be filtered if this is true.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "manual", + /* .docs = */ "If false, the cutoff frequency is set to half of the\nstreaming rate as configured by the message format command.\nOtherwise, the cutoff frequency is set according to the\nfollowing 'frequency' parameter.", + /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1093,7 +1812,7 @@ struct MetadataFor /* .docs = */ "-3dB cutoff frequency in Hz. Will not affect filtering if 'manual' is false.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1102,17 +1821,21 @@ struct MetadataFor /* .docs = */ "Reserved, set to 0x00.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "ImuLowpassFilter", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ImuLowpassFilter", /* .title = */ "Advanced Low-Pass Filter Settings", /* .docs = */ "Advanced configuration for the IMU data quantity low-pass filters.\n\nDeprecated, use the lowpass filter (0x0C,0x54) command instead.\n\nThe scaled data quantities are by default filtered through a single-pole IIR low-pass filter\nwhich is configured with a -3dB cutoff frequency of half the reporting frequency (set by\ndecimation factor in the IMU Message Format command) to prevent aliasing on a per data\nquantity basis. This advanced configuration command allows for the cutoff frequency to\nbe configured independently of the data reporting frequency as well as allowing for a\ncomplete bypass of the digital low-pass filter.\n\nPossible data descriptors:\n0x04 - Scaled accelerometer data\n0x05 - Scaled gyro data\n0x06 - Scaled magnetometer data (if applicable)\n0x17 - Scaled pressure data (if applicable)", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -1138,6 +1861,35 @@ struct MetadataFor }; +template<> +struct MetadataFor +{ + using type = commands_3dm::PpsSource::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::PpsSource::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -1150,17 +1902,21 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "PpsSource", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::PpsSource", /* .title = */ "None", /* .docs = */ "Controls the Pulse Per Second (PPS) source.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -1239,6 +1995,62 @@ struct MetadataFor }; +template<> +struct MetadataFor +{ + using type = commands_3dm::GpioConfig::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "pin", + /* .docs = */ "GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "feature", + /* .docs = */ "Determines how the pin will be used.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "behavior", + /* .docs = */ "Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.)", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pin_mode", + /* .docs = */ "GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GpioConfig::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -1260,7 +2072,7 @@ struct MetadataFor /* .docs = */ "Determines how the pin will be used.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1269,7 +2081,7 @@ struct MetadataFor /* .docs = */ "Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.)", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1278,17 +2090,59 @@ struct MetadataFor /* .docs = */ "GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual.", /* .type = */ {Type::BITFIELD, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GpioConfig", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GpioConfig", /* .title = */ "GPIO Configuration", /* .docs = */ "Configures the user GPIO pins on the connector for use with several built-in functions or for general input or output.\n\nGPIO pins are device-dependent. Some features are only available on\ncertain pins. Some behaviors require specific configurations.\nConsult the device user manual for restrictions and default settings.\n\nTo avoid glitches on GPIOs configured as an output in a mode other than\nGPIO, always configure the relevant function before setting up the pin\nwith this command. Otherwise, the pin state will be undefined between\nthis command and the one to set up the feature. For input pins, use\nthis command first so the state is well-defined when the feature is\ninitialized.\n\nSome configurations can only be active on one pin at a time. If such\nconfiguration is applied to a second pin, the second one will take\nprecedence and the original pin's configuration will be reset.\n", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GpioState::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "pin", + /* .docs = */ "GPIO pin number counting from 1. Cannot be 0.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "state", + /* .docs = */ "The pin state.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GpioState::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -1313,17 +2167,21 @@ struct MetadataFor /* .docs = */ "The pin state.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GpioState", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GpioState", /* .title = */ "GPIO State", /* .docs = */ "Allows the state of the pin to be read or controlled.\n\nThis command serves two purposes: 1) To allow reading the state of a pin via command,\nrather than polling a data quantity, and 2) to provide a way to set the output state\nwithout also having to specify the operating mode.\n\nThe state read back from the pin is the physical state of the pin, rather than a\nconfiguration value. The state can be read regardless of its configuration as long as\nthe device supports GPIO input on that pin. If the pin is set to an output, the read\nvalue would match the output value.\n\nWhile the state of a pin can always be set, it will only have an observable effect if\nthe pin is set to output mode.\n\nThis command does not support saving, loading, or resetting the state. Instead, use the\nGPIO Configuration command, which allows the initial state to be configured.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, false, false, false, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -1346,6 +2204,53 @@ struct MetadataFor }; +template<> +struct MetadataFor +{ + using type = commands_3dm::Odometer::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "mode", + /* .docs = */ "Mode setting.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "scaling", + /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "Uncertainty in encoder counts to distance translation (1-sigma value) [m/m].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::Odometer::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -1358,7 +2263,7 @@ struct MetadataFor /* .docs = */ "Mode setting.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1367,7 +2272,7 @@ struct MetadataFor /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1376,17 +2281,21 @@ struct MetadataFor /* .docs = */ "Uncertainty in encoder counts to distance translation (1-sigma value) [m/m].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "Odometer", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::Odometer", /* .title = */ "Odometer Settings", /* .docs = */ "Configures the hardware odometer interface.\n", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -1444,28 +2353,87 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_3dm::GetEventSupport; + using type = commands_3dm::GetEventSupport::Response; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "query", - /* .docs = */ "What type of information to retrieve.", + /* .docs = */ "Query type specified in the command.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, + { + /* .name = */ "max_instances", + /* .docs = */ "Number of slots available. The 'instance' number for\nthe configuration or control commands must be between 1 and this value.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "num_entries", + /* .docs = */ "Number of supported types.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "entries", + /* .docs = */ "List of supported types.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {0, microstrain::Index(2) /* num_entries */}, + /* .condition = */ {}, + }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GetEventSupport", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GetEventSupport::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventSupport; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "query", + /* .docs = */ "What type of information to retrieve.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GetEventSupport", /* .title = */ "Get Supported Events", /* .docs = */ "Lists the available trigger or action types.\n\nThere are a limited number of trigger and action slots available\nin the device. Up to M triggers and N actions can be configured at once\nin slots 1..M and 1..N respectively. M and N are identified by the\nmax_instances field in the response with the appropriate query selector.\n\nEach slot can be configured as one of a variety of different types of\ntriggers or actions. The supported types are enumerated in the response\nto this command. Additionally, there is a limit on the number of a given\ntype. In other words, while the device may support M triggers in total,\nonly a few of them maybe usable as a given type. This limit helps optimize\ndevice resources. The limit is identified in the count field.\n\nAll of the information in this command is available in the user manual.\nThis command provides a programmatic method for obtaining the information.\n", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -1490,6 +2458,44 @@ struct MetadataFor }; +template<> +struct MetadataFor +{ + using type = commands_3dm::EventControl::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "instance", + /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "mode", + /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::EventControl::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -1511,17 +2517,21 @@ struct MetadataFor /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "EventControl", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::EventControl", /* .title = */ "Event Control", /* .docs = */ "Enables or disables event triggers.\n\nTriggers can be disabled, enabled, and tested. While disabled, a trigger will\nnot evaluate its logic and effective behave like no trigger is configured.\nA disabled trigger will not activate any actions. Triggers are disabled by default.\n\nUse this command to enable (or disable) a trigger, or to place it into a test mode.\nWhen in test mode, the trigger logic is disabled but the output is forced to\nthe active state, meaning that it will behave as if the trigger logic is satisfied\nand any associated actions will execute.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -1579,19 +2589,56 @@ struct MetadataFor }; }; +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventTriggerStatus::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "count", + /* .docs = */ "Number of entries requested. If requested_count was 0, this is the number of supported trigger slots.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "triggers", + /* .docs = */ "A list of the configured triggers. Entries are in the order requested, or in increasing order if count was 0.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {20, microstrain::Index(0) /* count */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GetEventTriggerStatus::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { using type = commands_3dm::GetEventTriggerStatus; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "requested_count", /* .docs = */ "Number of entries requested. If 0, requests all trigger slots.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1600,17 +2647,21 @@ struct MetadataFor /* .docs = */ "List of trigger instances to query.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {20, microstrain::Index(0) /* requested_count */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GetEventTriggerStatus", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GetEventTriggerStatus", /* .title = */ "Get Trigger Status", /* .docs = */ "", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -1648,19 +2699,56 @@ struct MetadataFor }; }; +template<> +struct MetadataFor +{ + using type = commands_3dm::GetEventActionStatus::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "count", + /* .docs = */ "Number of entries requested. If requested_count was 0, this is the number of supported action slots.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "actions", + /* .docs = */ "A list of the configured actions. Entries are in the order requested, or in increasing order if count was 0.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {20, microstrain::Index(0) /* count */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GetEventActionStatus::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { using type = commands_3dm::GetEventActionStatus; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "requested_count", /* .docs = */ "Number of entries requested. If 0, requests all action slots.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1669,17 +2757,21 @@ struct MetadataFor /* .docs = */ "List of action instances to query.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ {20, microstrain::Index(0) /* requested_count */}, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GetEventActionStatus", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GetEventActionStatus", /* .title = */ "Get Action Status", /* .docs = */ "", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -1866,7 +2958,7 @@ struct MetadataFor /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, + /* .count = */ 4, /* .condition = */ {}, }, }; @@ -1943,6 +3035,53 @@ struct MetadataFor }; }; +template<> +struct MetadataFor +{ + using type = commands_3dm::EventTrigger::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "instance", + /* .docs = */ "Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "type", + /* .docs = */ "Type of trigger to configure.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "parameters", + /* .docs = */ "", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::EventTrigger::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -1964,7 +3103,7 @@ struct MetadataFor /* .docs = */ "Type of trigger to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1973,17 +3112,21 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "EventTrigger", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::EventTrigger", /* .title = */ "Event Trigger Configuration", /* .docs = */ "Configures various types of event triggers.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -2150,6 +3293,62 @@ struct MetadataFor }; }; +template<> +struct MetadataFor +{ + using type = commands_3dm::EventAction::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "instance", + /* .docs = */ "Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "trigger", + /* .docs = */ "Trigger ID number.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "type", + /* .docs = */ "Type of action to configure.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "parameters", + /* .docs = */ "", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::EventAction::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -2171,7 +3370,7 @@ struct MetadataFor /* .docs = */ "Trigger ID number.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2180,7 +3379,7 @@ struct MetadataFor /* .docs = */ "Type of action to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2189,95 +3388,226 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "EventAction", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::EventAction", /* .title = */ "Event Action Configuration", /* .docs = */ "Configures various types of event actions.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_3dm::AccelBias; + using type = commands_3dm::AccelBias::Response; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "bias", /* .docs = */ "accelerometer bias in the sensor frame (x,y,z) [g]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "AccelBias", - /* .title = */ "Configure Accel Bias", - /* .docs = */ "Configures the user specified accelerometer bias\n\nThe user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame.", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::AccelBias::Response", + /* .title = */ "None", + /* .docs = */ "", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_3dm::GyroBias; + using type = commands_3dm::AccelBias; static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { /* .name = */ "bias", - /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", + /* .docs = */ "accelerometer bias in the sensor frame (x,y,z) [g]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "GyroBias", - /* .title = */ "Configure Gyro Bias", - /* .docs = */ "Configures the user specified gyroscope bias\n\nThe user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame.", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::AccelBias", + /* .title = */ "Configure Accel Bias", + /* .docs = */ "Configures the user specified accelerometer bias\n\nThe user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_3dm::CaptureGyroBias; + using type = commands_3dm::GyroBias::Response; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { - /* .name = */ "averaging_time_ms", - /* .docs = */ "Averaging time [milliseconds]", - /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .name = */ "bias", + /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "CaptureGyroBias", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GyroBias::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::GyroBias; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "bias", + /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::GyroBias", + /* .title = */ "Configure Gyro Bias", + /* .docs = */ "Configures the user specified gyroscope bias\n\nThe user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::CaptureGyroBias::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "bias", + /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::CaptureGyroBias::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::CaptureGyroBias; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "averaging_time_ms", + /* .docs = */ "Averaging time [milliseconds]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::CaptureGyroBias", /* .title = */ "Capture Gyro Bias", /* .docs = */ "Samples gyro for a specified time range and writes the averaged result to the Gyro Bias vector in RAM\n\nThe device will average the gyro output for the duration of 'averaging_time_ms.' To store the resulting vector\nin non-volatile memory, use the Set Gyro Bias command.\nIMPORTANT: The device must be stationary and experiencing minimum vibration for the duration of 'averaging_time_ms'\nAveraging Time range: 1000 to 30,000", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::MagHardIronOffset::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "offset", + /* .docs = */ "hard iron offset in the sensor frame (x,y,z) [Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::MagHardIronOffset::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -2293,17 +3623,50 @@ struct MetadataFor /* .docs = */ "hard iron offset in the sensor frame (x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "MagHardIronOffset", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::MagHardIronOffset", /* .title = */ "Magnetometer Hard Iron Offset", /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::MagSoftIronMatrix::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "offset", + /* .docs = */ "soft iron matrix [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::MagSoftIronMatrix::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -2319,17 +3682,50 @@ struct MetadataFor /* .docs = */ "soft iron matrix [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "MagSoftIronMatrix", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::MagSoftIronMatrix", /* .title = */ "Magnetometer Soft Iron Matrix", /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \begin{bmatrix} 0 & 1 & 2 \\ 3 & 4 & 5 \\ 6 & 7 & 8 \end{bmatrix} EQEND\n", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ConingScullingEnable::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "If true, coning and sculling compensation is enabled.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ConingScullingEnable::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -2345,17 +3741,68 @@ struct MetadataFor /* .docs = */ "If true, coning and sculling compensation is enabled.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "ConingScullingEnable", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ConingScullingEnable", /* .title = */ "Coning and Sculling Enable", /* .docs = */ "Controls the Coning and Sculling Compenstation setting.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::Sensor2VehicleTransformEuler::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "roll", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pitch", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "yaw", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::Sensor2VehicleTransformEuler::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -2371,7 +3818,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2380,7 +3827,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2389,17 +3836,50 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "Sensor2VehicleTransformEuler", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::Sensor2VehicleTransformEuler", /* .title = */ "Sensor to Vehicle Frame Transformation Euler", /* .docs = */ "Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, Roll Euler angles.\nThese are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference,\nand describe the transformation of vectors from the sensor body frame to the vehicle frame.
\nNote: This is the transformation, the inverse of the rotation defined in our legacy products.
\nThe transformation may be stored in the device as a matrix or quaternion. When Euler angles are read back from the device, they may not\nbe exactly equal to the Euler angles used to set the transformation, but they are functionally equivalent, such that they result in the same transformation.
\n

\nThis transformation to the vehicle frame will be applied to the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\nComplementary Filter Orientation
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::Sensor2VehicleTransformQuaternion::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "q", + /* .docs = */ "Unit length quaternion representing transform [w, i, j, k]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::Sensor2VehicleTransformQuaternion::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -2415,17 +3895,50 @@ struct MetadataFor /* .docs = */ "Unit length quaternion representing transform [w, i, j, k]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "Sensor2VehicleTransformQuaternion", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::Sensor2VehicleTransformQuaternion", /* .title = */ "Sensor to Vehicle Frame Transformation Quaternion", /* .docs = */ "Set the sensor to vehicle frame transformation using unit length quaternion.\n\nNote: This is the transformation, the inverse of the rotation.\n\nThis quaternion describes the transformation of vectors from the sensor body frame to the vehicle frame of reference, and satisfies the following relationship:
\n\nEQSTART p^{veh} = q^{-1} p^{sen} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the transformation.
\nEQSTART p^{sen} = (0, v^{sen}_x, v^{sen}_y, v^{sen}_z) EQEND and EQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART p^{veh} = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
\n\nThe transformation may be stored in the device as a matrix or a quaternion. When the quaternion is read back from the device, it may not\nbe exactly equal to the quaternion used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::Sensor2VehicleTransformDcm::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "dcm", + /* .docs = */ "3 x 3 direction cosine matrix, stored in row-major order", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::Sensor2VehicleTransformDcm::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -2441,17 +3954,77 @@ struct MetadataFor /* .docs = */ "3 x 3 direction cosine matrix, stored in row-major order", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "Sensor2VehicleTransformDcm", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::Sensor2VehicleTransformDcm", /* .title = */ "Sensor to Vehicle Frame Transformation Direction Cosine Matrix", /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.\n\nThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
\nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
\n\nWhere:
\n\nEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND\nThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not\nbe exactly equal to array used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::ComplementaryFilter::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "pitch_roll_enable", + /* .docs = */ "Enable Pitch/Roll corrections", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading_enable", + /* .docs = */ "Enable Heading corrections (only available on devices with magnetometer)", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pitch_roll_time_constant", + /* .docs = */ "Time constant associated with the pitch/roll corrections [s]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading_time_constant", + /* .docs = */ "Time constant associated with the heading corrections [s]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ComplementaryFilter::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -2467,7 +4040,7 @@ struct MetadataFor /* .docs = */ "Enable Pitch/Roll corrections", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2476,7 +4049,7 @@ struct MetadataFor /* .docs = */ "Enable Heading corrections (only available on devices with magnetometer)", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2485,7 +4058,7 @@ struct MetadataFor /* .docs = */ "Time constant associated with the pitch/roll corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2494,17 +4067,21 @@ struct MetadataFor /* .docs = */ "Time constant associated with the heading corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "ComplementaryFilter", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::ComplementaryFilter", /* .title = */ "Complementary filter settings", /* .docs = */ "Configure the settings for the complementary filter which produces the following (0x80) descriptor set values: attitude matrix (0x80,09), quaternion (0x80,0A), and Euler angle (0x80,0C) outputs.\n\nThe filter can be configured to correct for pitch and roll using the accelerometer (with the assumption that linear acceleration is minimal),\nand to correct for heading using the magnetometer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field).\nPitch/roll and heading corrections each have their own configurable time constants, with a valid range of 1-1000 seconds. The default time constant is 10 seconds.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -2530,6 +4107,44 @@ struct MetadataFor }; +template<> +struct MetadataFor +{ + using type = commands_3dm::SensorRange::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "sensor", + /* .docs = */ "Which type of sensor will get the new range value.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "setting", + /* .docs = */ "Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::SensorRange::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -2551,17 +4166,21 @@ struct MetadataFor /* .docs = */ "Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "SensorRange", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::SensorRange", /* .title = */ "Sensor Range", /* .docs = */ "Changes the IMU sensor gain.\n\nThis allows you to optimize the range to get the best accuracy and performance\nwhile minimizing over-range events.\n\nUse the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine\nthe appropriate setting value for your application. Using values other than\nthose specified may result in a NACK or inaccurate measurement data.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; @@ -2599,13 +4218,59 @@ struct MetadataFor }; }; +template<> +struct MetadataFor +{ + using type = commands_3dm::CalibratedSensorRanges::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "sensor", + /* .docs = */ "The sensor type from the command.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "num_ranges", + /* .docs = */ "Number of supported ranges.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ranges", + /* .docs = */ "List of possible range settings.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {0, microstrain::Index(1) /* num_ranges */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::CalibratedSensorRanges::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { using type = commands_3dm::CalibratedSensorRanges; static constexpr inline ParameterInfo parameters[] = { - FUNCTION_SELECTOR_PARAM, { /* .name = */ "sensor", /* .docs = */ "The sensor to query. Cannot be ALL.", @@ -2617,11 +4282,80 @@ struct MetadataFor }, }; - static constexpr inline StructInfo value = { - /* .name = */ "CalibratedSensorRanges", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::CalibratedSensorRanges", /* .title = */ "Get Calibrated Sensor Ranges", /* .docs = */ "Returns the supported sensor ranges which may be used with the 3DM Sensor Range (0x0C,0x52) command.\n\nThe response includes an array of (u8, float) pairs which map each allowed setting\nto the corresponding maximum range in physical units. See SensorRangeType for units.", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_3dm::LowpassFilter::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "desc_set", + /* .docs = */ "Descriptor set of the quantity to be filtered.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "field_desc", + /* .docs = */ "Field descriptor of the quantity to be filtered.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "enable", + /* .docs = */ "The filter will be enabled if this is true.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "manual", + /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::LowpassFilter::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; @@ -2655,7 +4389,7 @@ struct MetadataFor /* .docs = */ "The filter will be enabled if this is true.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2664,7 +4398,7 @@ struct MetadataFor /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2673,20 +4407,113 @@ struct MetadataFor /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false}, + /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, }, }; - static constexpr inline StructInfo value = { - /* .name = */ "LowpassFilter", + static constexpr inline FieldInfo value = { + /* .name = */ "commands_3dm::LowpassFilter", /* .title = */ "Low-pass anti-aliasing filter", /* .docs = */ "This command controls the low-pass anti-aliasing filter supported data quantities.\n\nSee the device user manual for data quantities which support the anti-aliasing filter.\n\nIf set to automatic mode, the frequency will track half of the transmission rate\nof the target descriptor according to the configured message format (0x0C,0x0F).\nFor example, if scaled accel (0x80,0x04) is set to stream at 100 Hz, the filter would\nbe set to 50 Hz. Changing the message format to 200 Hz would automatically adjust the\nfilter to 100 Hz.\n\nFor WRITE, SAVE, LOAD, and DEFAULT function selectors, the descriptor set and/or field descriptor\nmay be 0x00 to set, save, load, or reset the setting for all supported descriptors. The\nfield descriptor must be 0x00 if the descriptor set is 0x00.\n", /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, }; }; +static constexpr inline std::initializer_list ALL_COMMANDS_3DM = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, +}; + + } // namespace mip::metadata diff --git a/src/cpp/mip/metadata/definitions/commands_aiding.hpp b/src/cpp/mip/metadata/definitions/commands_aiding.hpp new file mode 100644 index 000000000..7c289a55d --- /dev/null +++ b/src/cpp/mip/metadata/definitions/commands_aiding.hpp @@ -0,0 +1,1081 @@ +#pragma once + +#include "common.hpp" + +#include + +#include + +namespace mip::metadata +{ + + +template<> +struct MetadataFor +{ + using type = commands_aiding::FrameConfig::Format; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "EULER", "Translation vector followed by euler angles (roll, pitch, yaw)." }, + { 2, "QUATERNION", "Translation vector followed by quaternion (w, x, y, z)." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Format", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::FrameConfig::Rotation; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "euler", + /* .docs = */ "Rotation represented as euler angles in RPY format [rad]. Range +/- pi.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* format */, static_cast(commands_aiding::FrameConfig::Format::EULER)} /* format == EULER */, + }, + { + /* .name = */ "quaternion", + /* .docs = */ "Rotation represented as a quaternion in WXYZ format.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* format */, static_cast(commands_aiding::FrameConfig::Format::QUATERNION)} /* format == QUATERNION */, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Rotation", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::FrameConfig::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "frame_id", + /* .docs = */ "Reference frame number. Limit 4.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "format", + /* .docs = */ "Format of the transformation.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "tracking_enabled", + /* .docs = */ "If enabled, the Kalman filter will track errors.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "translation", + /* .docs = */ "Translation X, Y, and Z.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "rotation", + /* .docs = */ "Rotation as specified by format.", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::FrameConfig::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::FrameConfig; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "frame_id", + /* .docs = */ "Reference frame number. Limit 4.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "format", + /* .docs = */ "Format of the transformation.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "tracking_enabled", + /* .docs = */ "If enabled, the Kalman filter will track errors.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "translation", + /* .docs = */ "Translation X, Y, and Z.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "rotation", + /* .docs = */ "Rotation as specified by format.", + /* .type = */ {Type::UNION, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::FrameConfig", + /* .title = */ "Frame Configuration", + /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command\nshould mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame)\n\nThis transform satisfies the following relationship:\n\nEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
\n\nWhere:
\nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

\nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
\nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
\n\nRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element\nin the rotation vector is ignored and should be set to 0.\n\nWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.\n\nExample: GNSS antenna lever arm\n\nFrame ID: 1\nFormat: 1 (Euler)\nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)\nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::AidingEchoControl::Mode; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "SUPPRESS_ACK", "Suppresses the usual command ack field for aiding messages." }, + { 1, "STANDARD", "Normal ack/nack behavior." }, + { 2, "RESPONSE", "Echo the data back as a response." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Mode", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::AidingEchoControl::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "mode", + /* .docs = */ "Controls data echoing.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::AidingEchoControl::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::AidingEchoControl; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "mode", + /* .docs = */ "Controls data echoing.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::AidingEchoControl", + /* .title = */ "Aiding Command Echo Control", + /* .docs = */ "Controls command response behavior to external aiding commands", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::Time::Timebase; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "INTERNAL_REFERENCE", "Timestamp provided is with respect to internal clock." }, + { 2, "EXTERNAL_TIME", "Timestamp provided is with respect to external clock, synced by PPS source." }, + { 3, "TIME_OF_ARRIVAL", "Timestamp provided is a fixed latency relative to time of message arrival." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Timebase", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::Time; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "timebase", + /* .docs = */ "Timebase reference, e.g. internal, external, GPS, UTC, etc.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "Reserved, set to 0x01.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "nanoseconds", + /* .docs = */ "Nanoseconds since the timebase epoch.", + /* .type = */ {Type::U64, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Time", + /* .title = */ "Time", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::EcefPos::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "X", "" }, + { 2, "Y", "" }, + { 4, "Z", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::EcefPos; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time", + /* .docs = */ "Timestamp of the measurement.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frame_id", + /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "position", + /* .docs = */ "ECEF position [m].", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "ECEF position uncertainty [m]. Cannot be 0 unless the corresponding valid flags are 0.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::EcefPos", + /* .title = */ "ECEF Position", + /* .docs = */ "Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::LlhPos::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "Latitude", "" }, + { 2, "Longitude", "" }, + { 4, "Height", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::LlhPos; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time", + /* .docs = */ "Timestamp of the measurement.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frame_id", + /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "latitude", + /* .docs = */ "[deg]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "longitude", + /* .docs = */ "[deg]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "height", + /* .docs = */ "[m]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "NED position uncertainty. Cannot be 0 unless the corresponding valid flags are 0.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::LlhPos", + /* .title = */ "LLH Position", + /* .docs = */ "Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid.\nUncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::Height; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time", + /* .docs = */ "Timestamp of the measurement.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frame_id", + /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "height", + /* .docs = */ "[m]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "[m]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::Height", + /* .title = */ "Height", + /* .docs = */ "Estimated value of height.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::EcefVel::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "X", "" }, + { 2, "Y", "" }, + { 4, "Z", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::EcefVel; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time", + /* .docs = */ "Timestamp of the measurement.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frame_id", + /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "velocity", + /* .docs = */ "ECEF velocity [m/s].", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "ECEF velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::EcefVel", + /* .title = */ "ECEF Velocity", + /* .docs = */ "ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::NedVel::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "X", "" }, + { 2, "Y", "" }, + { 4, "Z", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::NedVel; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time", + /* .docs = */ "Timestamp of the measurement.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frame_id", + /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "velocity", + /* .docs = */ "NED velocity [m/s].", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "NED velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::NedVel", + /* .title = */ "NED Velocity", + /* .docs = */ "NED velocity aiding command. Coordinates are given in the local North-East-Down frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::VehicleFixedFrameVelocity::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "X", "" }, + { 2, "Y", "" }, + { 4, "Z", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::VehicleFixedFrameVelocity; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time", + /* .docs = */ "Timestamp of the measurement.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frame_id", + /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "velocity", + /* .docs = */ "[m/s]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "[m/s] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::VehicleFixedFrameVelocity", + /* .title = */ "Vehicle Frame Velocity", + /* .docs = */ "Estimate of velocity of the vehicle in the frame associated\nwith the given sensor ID.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::TrueHeading; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time", + /* .docs = */ "Timestamp of the measurement.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frame_id", + /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading", + /* .docs = */ "Heading [radians]. Range +/- Pi.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "Cannot be 0 unless the valid flags are 0.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::TrueHeading", + /* .title = */ "True Heading", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::MagneticField::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "X", "" }, + { 2, "Y", "" }, + { 4, "Z", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::MagneticField; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time", + /* .docs = */ "Timestamp of the measurement.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frame_id", + /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "magnetic_field", + /* .docs = */ "[G]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "[G] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::MagneticField", + /* .title = */ "Magnetic Field", + /* .docs = */ "Estimate of magnetic field in the frame associated with the given sensor ID.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_aiding::Pressure; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time", + /* .docs = */ "Timestamp of the measurement.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frame_id", + /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pressure", + /* .docs = */ "[mbar]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "[mbar] 1-sigma uncertainty. Cannot be 0 unless the valid flags are 0.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_aiding::Pressure", + /* .title = */ "Pressure", + /* .docs = */ "Estimated value of air pressure.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + + +static constexpr inline std::initializer_list ALL_COMMANDS_AIDING = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, +}; + + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index b18b18b0b..658b31d9e 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -1,4 +1,4 @@ - +#pragma once #include "common.hpp" @@ -15,10 +15,6 @@ struct MetadataFor { using type = commands_base::Ping; - static constexpr inline ParameterInfo parameters[] = { - - }; - static constexpr inline FieldInfo value = { /* .name = */ "commands_base::Ping", /* .title = */ "Ping", @@ -36,10 +32,6 @@ struct MetadataFor { using type = commands_base::SetIdle; - static constexpr inline ParameterInfo parameters[] = { - - }; - static constexpr inline FieldInfo value = { /* .name = */ "commands_base::SetIdle", /* .title = */ "Set to idle", @@ -73,7 +65,7 @@ struct MetadataFor /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, + /* .count = */ 16, /* .condition = */ {}, }, { @@ -82,7 +74,7 @@ struct MetadataFor /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, + /* .count = */ 16, /* .condition = */ {}, }, { @@ -91,7 +83,7 @@ struct MetadataFor /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, + /* .count = */ 16, /* .condition = */ {}, }, { @@ -100,7 +92,7 @@ struct MetadataFor /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, + /* .count = */ 16, /* .condition = */ {}, }, { @@ -109,7 +101,7 @@ struct MetadataFor /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, - /* .count = */ 1, + /* .count = */ 16, /* .condition = */ {}, }, }; @@ -156,10 +148,6 @@ struct MetadataFor { using type = commands_base::GetDeviceInfo; - static constexpr inline ParameterInfo parameters[] = { - - }; - static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetDeviceInfo", /* .title = */ "Get device information", @@ -184,7 +172,7 @@ struct MetadataFor /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, - /* .count = */ 1, + /* .count = */ 0, /* .condition = */ {}, }, }; @@ -206,10 +194,6 @@ struct MetadataFor { using type = commands_base::GetDeviceDescriptors; - static constexpr inline ParameterInfo parameters[] = { - - }; - static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetDeviceDescriptors", /* .title = */ "Get device descriptors", @@ -256,10 +240,6 @@ struct MetadataFor { using type = commands_base::BuiltInTest; - static constexpr inline ParameterInfo parameters[] = { - - }; - static constexpr inline FieldInfo value = { /* .name = */ "commands_base::BuiltInTest", /* .title = */ "Built in test", @@ -277,10 +257,6 @@ struct MetadataFor { using type = commands_base::Resume; - static constexpr inline ParameterInfo parameters[] = { - - }; - static constexpr inline FieldInfo value = { /* .name = */ "commands_base::Resume", /* .title = */ "Resume", @@ -305,7 +281,7 @@ struct MetadataFor /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, - /* .count = */ 1, + /* .count = */ 0, /* .condition = */ {}, }, }; @@ -327,10 +303,6 @@ struct MetadataFor { using type = commands_base::GetExtendedDescriptors; - static constexpr inline ParameterInfo parameters[] = { - - }; - static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetExtendedDescriptors", /* .title = */ "Get device descriptors (extended)", @@ -355,7 +327,7 @@ struct MetadataFor /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, - /* .count = */ 1, + /* .count = */ 16, /* .condition = */ {}, }, }; @@ -377,10 +349,6 @@ struct MetadataFor { using type = commands_base::ContinuousBit; - static constexpr inline ParameterInfo parameters[] = { - - }; - static constexpr inline FieldInfo value = { /* .name = */ "commands_base::ContinuousBit", /* .title = */ "Continuous built-in test", @@ -533,10 +501,6 @@ struct MetadataFor { using type = commands_base::SoftReset; - static constexpr inline ParameterInfo parameters[] = { - - }; - static constexpr inline FieldInfo value = { /* .name = */ "commands_base::SoftReset", /* .title = */ "Reset device", diff --git a/src/cpp/mip/metadata/definitions/commands_filter.hpp b/src/cpp/mip/metadata/definitions/commands_filter.hpp new file mode 100644 index 000000000..00e1db970 --- /dev/null +++ b/src/cpp/mip/metadata/definitions/commands_filter.hpp @@ -0,0 +1,4141 @@ +#pragma once + +#include "common.hpp" + +#include + +#include + +namespace mip::metadata +{ + + +template<> +struct MetadataFor +{ + using type = commands_filter::Reset; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::Reset", + /* .title = */ "Reset Navigation Filter", + /* .docs = */ "Resets the filter to the initialization state.\n\nIf the auto-initialization feature is disabled, the initial attitude or heading must be set in\norder to enter the run state after a reset.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SetInitialAttitude; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "roll", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pitch", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SetInitialAttitude", + /* .title = */ "Set Initial Attitude", + /* .docs = */ "Set the sensor initial attitude.\n\nThis command can only be issued in the 'Init' state and should be used with a good\nestimate of the vehicle attitude. The Euler angles are the sensor body frame with respect\nto the NED frame.\n\nThe valid input ranges are as follows:\n\nRoll: [-pi, pi]\nPitch: [-pi/2, pi/2]\nHeading: [-pi, pi]\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::EstimationControl::EnableFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "gyro_bias", "" }, + { 2, "accel_bias", "" }, + { 4, "gyro_scale_factor", "" }, + { 8, "accel_scale_factor", "" }, + { 16, "antenna_offset", "" }, + { 32, "auto_mag_hard_iron", "" }, + { 64, "auto_mag_soft_iron", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "EnableFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::EstimationControl::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "See above", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::EstimationControl::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::EstimationControl; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "See above", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::EstimationControl", + /* .title = */ "Estimation Control Flags", + /* .docs = */ "Estimation Control Flags\n\nControls which parameters are estimated by the Kalman Filter.\n\nDesired settings should be logically ORed together.\n\nExamples:\n\n0x0001 - Enable Gyro Bias Estimation Only\n0x0063 - Enable Gyro Bias, Accel Bias, and Mag Auto Hard and Soft Iron Cal States Only\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::ExternalGnssUpdate; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "gps_time", + /* .docs = */ "[seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "gps_week", + /* .docs = */ "[GPS week number, not modulus 1024]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "latitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "longitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "height", + /* .docs = */ "Above WGS84 ellipsoid [meters]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "velocity", + /* .docs = */ "NED Frame [meters/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pos_uncertainty", + /* .docs = */ "NED Frame, 1-sigma [meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "vel_uncertainty", + /* .docs = */ "NED Frame, 1-sigma [meters/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::ExternalGnssUpdate", + /* .title = */ "External GNSS Update", + /* .docs = */ "Provide a filter measurement from an external GNSS\n\nThe GNSS source control must be set to 'external' for this command to succeed, otherwise it will be NACK'd.\nPlease refer to your device user manual for information on the maximum rate of this message.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::ExternalHeadingUpdate; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "heading", + /* .docs = */ "Bounded by +-PI [radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading_uncertainty", + /* .docs = */ "1-sigma [radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "type", + /* .docs = */ "1 - True, 2 - Magnetic", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::ExternalHeadingUpdate", + /* .title = */ "External Heading Update", + /* .docs = */ "Provide a filter measurement from an external heading source\n\nThe heading must be the sensor frame with respect to the NED frame.\n\nThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.\nHeading angle uncertainties of <= 0.0 will be NACK'd\n\nPlease refer to your device user manual for information on the maximum rate of this message.\n\nOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.\nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.\n\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::ExternalHeadingUpdateWithTime; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "gps_time", + /* .docs = */ "[seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "gps_week", + /* .docs = */ "[GPS week number, not modulus 1024]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading", + /* .docs = */ "Relative to true north, bounded by +-PI [radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading_uncertainty", + /* .docs = */ "1-sigma [radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "type", + /* .docs = */ "1 - True, 2 - Magnetic", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::ExternalHeadingUpdateWithTime", + /* .title = */ "External Heading Update With Time", + /* .docs = */ "Provide a filter measurement from an external heading source at a specific GPS time\n\nThis is more accurate than the External Heading Update (0x0D, 0x17) and should be used in applications\nwhere the rate of heading change will cause significant measurement error due to the sampling, transmission,\nand processing time required. Accurate time stamping of the heading information is important.\n\nThe heading must be the sensor frame with respect to the NED frame.\n\nThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.\nHeading angle uncertainties of <= 0.0 will be NACK'd\n\nPlease refer to your device user manual for information on the maximum rate of this message.\n\nOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.\nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.\n\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::TareOrientation::MipTareAxes; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "roll", "" }, + { 2, "pitch", "" }, + { 4, "yaw", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "MipTareAxes", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::TareOrientation::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "axes", + /* .docs = */ "Axes to tare", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::TareOrientation::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::TareOrientation; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "axes", + /* .docs = */ "Axes to tare", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::TareOrientation", + /* .title = */ "Tare Sensor Orientation", + /* .docs = */ "Tare the device orientation.\n\nThis function uses the current device orientation relative to the NED frame as the current sensor to vehicle transformation.\nThis command is provided as a convenient way to set the sensor to vehicle frame transformation.\nThe filter must be initialized and have a valid attitude output. If the attitude is not valid, an error will be returned.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::VehicleDynamicsMode::DynamicsMode; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "PORTABLE", "" }, + { 2, "AUTOMOTIVE", "" }, + { 3, "AIRBORNE", "" }, + { 4, "AIRBORNE_HIGH_G", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "DynamicsMode", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::VehicleDynamicsMode::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "mode", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::VehicleDynamicsMode::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::VehicleDynamicsMode; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "mode", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::VehicleDynamicsMode", + /* .title = */ "Vehicle Dynamics Mode", + /* .docs = */ "Controls the vehicle dynamics mode.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SensorToVehicleRotationEuler::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "roll", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pitch", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "yaw", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SensorToVehicleRotationEuler::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SensorToVehicleRotationEuler; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "roll", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pitch", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "yaw", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SensorToVehicleRotationEuler", + /* .title = */ "Sensor to Vehicle Frame Rotation Euler", + /* .docs = */ "Set the sensor to vehicle frame rotation using Yaw, Pitch, Roll Euler angles.\n\nNote: This is the rotation, the inverse of the transformation.\nThese angles define the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe rotation is stored in the device as a quaternion. When Euler angles are read back from the device, they may not\nbe equivalent in value to the Euler angles used to set the rotation, but they are functionally equivalent.
\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SensorToVehicleRotationDcm::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "dcm", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SensorToVehicleRotationDcm::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SensorToVehicleRotationDcm; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "dcm", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SensorToVehicleRotationDcm", + /* .title = */ "Sensor to Vehicle Frame Rotation DCM", + /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \begin{bmatrix} 0 & 1 & 2\\ 3 & 4 & 5\\ 6 & 7 & 8 \end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SensorToVehicleRotationQuaternion::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "quat", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SensorToVehicleRotationQuaternion::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SensorToVehicleRotationQuaternion; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "quat", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SensorToVehicleRotationQuaternion", + /* .title = */ "Sensor to Vehicle Frame Rotation Quaternion", + /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.\n\nNote: This is the rotation, the inverse of the transformation.\nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may not\nbe equivalent in value to the quaternion used to set the rotation, due to normalization.
\n
\nQuaternion element definition:

\n
\nEQSTART Q_{SEN}^{VEH} = \begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \end{bmatrix} EQEND\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SensorToVehicleOffset::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "offset", + /* .docs = */ "[meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SensorToVehicleOffset::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SensorToVehicleOffset; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "offset", + /* .docs = */ "[meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SensorToVehicleOffset", + /* .title = */ "Sensor to Vehicle Frame Offset", + /* .docs = */ "Set the sensor to vehicle frame offset, expressed in the sensor frame.\n\nThis is a simple offset, not a lever arm. It does not compensate for inertial effects experienced from being offset from the center of gravity/rotation of the vehicle.\nIt simply adds the offset to the position output to express it in the origin of the user's vehicle frame.\n\nThis offset affects the following output quantities:\nEstimated LLH Position\n\nThe magnitude of the offset vector is limited to 10 meters", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AntennaOffset::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "offset", + /* .docs = */ "[meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AntennaOffset::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AntennaOffset; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "offset", + /* .docs = */ "[meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AntennaOffset", + /* .title = */ "GNSS Antenna Offset Control", + /* .docs = */ "Set the sensor to GNSS antenna offset.\n\nThis is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.\n\nThe magnitude of the offset vector is limited to 10 meters\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GnssSource::Source; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "ALL_INT", "All internal receivers" }, + { 2, "EXT", "External GNSS messages provided by user" }, + { 3, "INT_1", "Internal GNSS Receiver 1 only" }, + { 4, "INT_2", "Internal GNSS Receiver 2 only" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Source", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GnssSource::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GnssSource::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GnssSource; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "source", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GnssSource", + /* .title = */ "GNSS Aiding Source Control", + /* .docs = */ "Control the source of GNSS information used to update the Kalman Filter.\n\nChanging the GNSS source while the sensor is in the 'running' state may temporarily place\nit back in the 'init' state until the new source of GNSS data is received.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::HeadingSource::Source; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "NONE", "See note 3" }, + { 1, "MAG", "" }, + { 2, "GNSS_VEL", "See notes 1,2" }, + { 3, "EXTERNAL", "" }, + { 4, "GNSS_VEL_AND_MAG", "" }, + { 5, "GNSS_VEL_AND_EXTERNAL", "" }, + { 6, "MAG_AND_EXTERNAL", "" }, + { 7, "GNSS_VEL_AND_MAG_AND_EXTERNAL", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Source", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::HeadingSource::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::HeadingSource::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::HeadingSource; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "source", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::HeadingSource", + /* .title = */ "Heading Aiding Source Control", + /* .docs = */ "Control the source of heading information used to update the Kalman Filter.\n\n1. To use internal GNSS velocity vector for heading updates, the target application\nmust have minimal (preferably no) side-slip. This option is good for wheeled vehicles.\n\n2. On some devices, when using GNSS velocity vector for heading updates, the X-axis of the device\nmust align with the direction of travel. Please reference the user guide for your particular device to\ndetermine if this limitation is applicable.\n\n3. When none is selected, the heading estimate can still converge if GNSS is available and sufficient dynamic motion\n(change in direction of travel and acceleration) is experienced. The heading may drift when: stationary, traveling\nat a constant speed, or during a constant course over ground.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AutoInitControl::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "See above", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AutoInitControl::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AutoInitControl; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "See above", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AutoInitControl", + /* .title = */ "Auto-initialization Control", + /* .docs = */ "Filter Auto-initialization Control\n\nEnable/Disable automatic initialization upon device startup.\n\nPossible enable values:\n\n0x00 - Disable auto-initialization\n0x01 - Enable auto-initialization\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AccelNoise::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "noise", + /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AccelNoise::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AccelNoise; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "noise", + /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AccelNoise", + /* .title = */ "Accelerometer Noise Standard Deviation", + /* .docs = */ "Accelerometer Noise Standard Deviation\n\nEach of the noise values must be greater than 0.0.\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.\nDefault values provide good performance for most laboratory conditions.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GyroNoise::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "noise", + /* .docs = */ "Gyro Noise 1-sigma [rad/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GyroNoise::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GyroNoise; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "noise", + /* .docs = */ "Gyro Noise 1-sigma [rad/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GyroNoise", + /* .title = */ "Gyroscope Noise Standard Deviation", + /* .docs = */ "Gyroscope Noise Standard Deviation\n\nEach of the noise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.\nDefault values provide good performance for most laboratory conditions.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AccelBiasModel::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "beta", + /* .docs = */ "Accel Bias Beta [1/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "noise", + /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AccelBiasModel::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AccelBiasModel; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "beta", + /* .docs = */ "Accel Bias Beta [1/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "noise", + /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AccelBiasModel", + /* .title = */ "Accelerometer Bias Model Parameters", + /* .docs = */ "Accelerometer Bias Model Parameters\n\nNoise values must be greater than 0.0\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GyroBiasModel::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "beta", + /* .docs = */ "Gyro Bias Beta [1/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "noise", + /* .docs = */ "Gyro Noise 1-sigma [rad/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GyroBiasModel::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GyroBiasModel; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "beta", + /* .docs = */ "Gyro Bias Beta [1/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "noise", + /* .docs = */ "Gyro Noise 1-sigma [rad/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GyroBiasModel", + /* .title = */ "Gyroscope Bias Model Parameters", + /* .docs = */ "Gyroscope Bias Model Parameters\n\nNoise values must be greater than 0.0\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AltitudeAiding::AidingSelector; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "NONE", "No altitude aiding" }, + { 1, "PRESURE", "Enable pressure sensor aiding" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "AidingSelector", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AltitudeAiding::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "selector", + /* .docs = */ "See above", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AltitudeAiding::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AltitudeAiding; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "selector", + /* .docs = */ "See above", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AltitudeAiding", + /* .title = */ "Altitude Aiding Control", + /* .docs = */ "Select altitude input for absolute altitude and/or vertical velocity. The primary altitude reading is always GNSS.\nAiding inputs are used to improve GNSS altitude readings when GNSS is available and to backup GNSS during outages.\n\nPressure altitude is based on 'instant sea level pressure' which is dependent on location and weather conditions and can vary by more than 40 meters.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::PitchRollAiding::AidingSource; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "NONE", "No pitch/roll aiding" }, + { 1, "GRAVITY_VEC", "Enable gravity vector aiding" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "AidingSource", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::PitchRollAiding::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "Controls the aiding source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::PitchRollAiding::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::PitchRollAiding; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "source", + /* .docs = */ "Controls the aiding source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::PitchRollAiding", + /* .title = */ "Pitch/Roll Aiding Control", + /* .docs = */ "Select pitch/roll aiding input. Pitch/roll reading is always derived from GNSS corrected inertial solution.\nAiding inputs are used to improve that solution during periods of low dynamics and GNSS outages.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AutoZupt::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "threshold", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AutoZupt::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AutoZupt; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "threshold", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AutoZupt", + /* .title = */ "Zero Velocity Update Control", + /* .docs = */ "The ZUPT is triggered when the scalar magnitude of the GNSS reported velocity vector is equal-to or less than the threshold value.\nThe device will NACK threshold values that are less than zero (i.e.negative.)", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AutoAngularZupt::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "threshold", + /* .docs = */ "[radians/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AutoAngularZupt::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AutoAngularZupt; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "threshold", + /* .docs = */ "[radians/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AutoAngularZupt", + /* .title = */ "Zero Angular Rate Update Control", + /* .docs = */ "Zero Angular Rate Update\nThe ZUPT is triggered when the scalar magnitude of the angular rate vector is equal-to or less than the threshold value.\nThe device will NACK threshold values that are less than zero (i.e.negative.)", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::CommandedZupt; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::CommandedZupt", + /* .title = */ "Commanded Zero Velocity Update", + /* .docs = */ "Please see the device user manual for the maximum rate of this message.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::CommandedAngularZupt; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::CommandedAngularZupt", + /* .title = */ "Commanded Zero Angular Rate Update", + /* .docs = */ "Please see the device user manual for the maximum rate of this message.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagCaptureAutoCal; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagCaptureAutoCal", + /* .title = */ "Magnetometer Capture Auto Calibration", + /* .docs = */ "This command captures the current value of the auto-calibration, applies it to the current fixed hard and soft iron calibration coefficients, and replaces the current fixed hard and soft iron calibration coefficients with the new values.\nThis may be used in place of (or in addition to) a manual hard and soft iron calibration utility. This command also resets the auto-calibration coefficients.\nFunction selector SAVE is the same as issuing the 0x0C, 0x3A and 0x0C, 0x3B commands with the SAVE function selector.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, false, true, false, false, true}, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GravityNoise::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "noise", + /* .docs = */ "Gravity Noise 1-sigma [gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GravityNoise::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GravityNoise; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "noise", + /* .docs = */ "Gravity Noise 1-sigma [gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GravityNoise", + /* .title = */ "Gravity Noise Standard Deviation", + /* .docs = */ "Set the expected gravity noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nNote: Noise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter. Changing this value modifies how the filter responds to dynamic input and can be used to tune filter performance.\nDefault values provide good performance for most laboratory conditions.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::PressureAltitudeNoise::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "noise", + /* .docs = */ "Pressure Altitude Noise 1-sigma [m]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::PressureAltitudeNoise::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::PressureAltitudeNoise; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "noise", + /* .docs = */ "Pressure Altitude Noise 1-sigma [m]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::PressureAltitudeNoise", + /* .title = */ "Pressure Altitude Noise Standard Deviation", + /* .docs = */ "Set the expected pressure altitude noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nThe noise value must be greater than 0.0\n\nThis noise value represents pressure altitude model noise in the Estimation Filter.\nA lower value will increase responsiveness of the sensor to pressure changes, however height estimates will be more susceptible to error from air pressure fluctuations not due to changes in altitude. Default values provide good performance for most laboratory conditions.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::HardIronOffsetNoise::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "noise", + /* .docs = */ "Hard Iron Offset Noise 1-sigma [gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::HardIronOffsetNoise::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::HardIronOffsetNoise; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "noise", + /* .docs = */ "Hard Iron Offset Noise 1-sigma [gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::HardIronOffsetNoise", + /* .title = */ "Hard Iron Offset Process Noise", + /* .docs = */ "Set the expected hard iron offset noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0\n\nThe noise values represent process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SoftIronMatrixNoise::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "noise", + /* .docs = */ "Soft Iron Matrix Noise 1-sigma [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SoftIronMatrixNoise::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SoftIronMatrixNoise; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "noise", + /* .docs = */ "Soft Iron Matrix Noise 1-sigma [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SoftIronMatrixNoise", + /* .title = */ "Soft Iron Offset Process Noise", + /* .docs = */ "Set the expected soft iron matrix noise 1-sigma values.\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagNoise::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "noise", + /* .docs = */ "Mag Noise 1-sigma [gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagNoise::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagNoise; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "noise", + /* .docs = */ "Mag Noise 1-sigma [gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagNoise", + /* .title = */ "Magnetometer Noise Standard Deviation", + /* .docs = */ "Set the expected magnetometer noise 1-sigma values.\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0 (gauss)\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::FilterMagParamSource; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "NONE", "No source. See command documentation for default behavior" }, + { 2, "WMM", "Magnetic field is assumed to conform to the World Magnetic Model, calculated using current location estimate as an input to the model." }, + { 3, "MANUAL", "Magnetic field is assumed to have the parameter specified by the user." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "FilterMagParamSource", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::InclinationSource::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "Inclination Source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "inclination", + /* .docs = */ "Inclination angle [radians] (only required if source = MANUAL)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::InclinationSource::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::InclinationSource; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "source", + /* .docs = */ "Inclination Source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "inclination", + /* .docs = */ "Inclination angle [radians] (only required if source = MANUAL)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::InclinationSource", + /* .title = */ "Inclination Source", + /* .docs = */ "Set/Get the local magnetic field inclination angle source.\n\nThis can be used to correct for the local value of inclination (dip angle) of the earthmagnetic field.\nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagneticDeclinationSource::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "Magnetic field declination angle source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "declination", + /* .docs = */ "Declination angle [radians] (only required if source = MANUAL)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagneticDeclinationSource::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagneticDeclinationSource; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "source", + /* .docs = */ "Magnetic field declination angle source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "declination", + /* .docs = */ "Declination angle [radians] (only required if source = MANUAL)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagneticDeclinationSource", + /* .title = */ "Magnetic Field Declination Source Control", + /* .docs = */ "Set/Get the local magnetic field declination angle source.\n\nThis can be used to correct for the local value of declination of the earthmagnetic field.\nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagFieldMagnitudeSource::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "Magnetic Field Magnitude Source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "magnitude", + /* .docs = */ "Magnitude [gauss] (only required if source = MANUAL)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagFieldMagnitudeSource::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagFieldMagnitudeSource; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "source", + /* .docs = */ "Magnetic Field Magnitude Source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "magnitude", + /* .docs = */ "Magnitude [gauss] (only required if source = MANUAL)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagFieldMagnitudeSource", + /* .title = */ "Magnetic Field Magnitude Source", + /* .docs = */ "Set/Get the local magnetic field magnitude source.\n\nThis is used to specify the local magnitude of the earth's magnetic field.\nHaving a correct value for magnitude is important for best performance of the auto-mag calibration feature and for the magnetometer adaptive magnitude. If you do not have an accurate value for the local magnetic field magnitude, it is recommended that you leave the auto-mag calibration feature off.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::ReferencePosition::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "enable/disable", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "latitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "longitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "altitude", + /* .docs = */ "[meters]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::ReferencePosition::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::ReferencePosition; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "enable/disable", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "latitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "longitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "altitude", + /* .docs = */ "[meters]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::ReferencePosition", + /* .title = */ "Set Reference Position", + /* .docs = */ "Set the Lat/Long/Alt reference position for the sensor.\n\nThis position is used by the sensor to calculate the WGS84 gravity and WMM2015 magnetic field parameters.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::FilterAdaptiveMeasurement; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "DISABLED", "No adaptive measurement" }, + { 1, "FIXED", "Enable fixed adaptive measurement (use specified limits)" }, + { 2, "AUTO", "Enable auto adaptive measurement" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "FilterAdaptiveMeasurement", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AccelMagnitudeErrorAdaptiveMeasurement::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "adaptive_measurement", + /* .docs = */ "Adaptive measurement selector", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "Low-pass filter curoff frequency [hertz]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "low_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "low_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "minimum_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AccelMagnitudeErrorAdaptiveMeasurement::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AccelMagnitudeErrorAdaptiveMeasurement; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "adaptive_measurement", + /* .docs = */ "Adaptive measurement selector", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "Low-pass filter curoff frequency [hertz]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "low_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "low_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "minimum_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AccelMagnitudeErrorAdaptiveMeasurement", + /* .title = */ "Gravity Magnitude Error Adaptive Measurement", + /* .docs = */ "Enable or disable the gravity magnitude error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nAdaptive measurements can be enabled/disabled without the need for providing the additional parameters.\nIn this case, only the function selector and enable value are required; all other parameters will remain at their previous values.\nWhen “auto-adaptive” is selected, the filter and limit parameters are ignored.\nInstead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagMagnitudeErrorAdaptiveMeasurement::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "adaptive_measurement", + /* .docs = */ "Adaptive measurement selector", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "Low-pass filter curoff frequency [hertz]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "low_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "low_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "minimum_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagMagnitudeErrorAdaptiveMeasurement::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagMagnitudeErrorAdaptiveMeasurement; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "adaptive_measurement", + /* .docs = */ "Adaptive measurement selector", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "Low-pass filter curoff frequency [hertz]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "low_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "low_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "minimum_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagMagnitudeErrorAdaptiveMeasurement", + /* .title = */ "Magnetometer Magnitude Error Adaptive Measurement", + /* .docs = */ "Enable or disable the magnetometer magnitude error adaptive measurement.\nThis feature will reject magnetometer readings that are out of range of the thresholds specified (fixed adaptive) or calculated internally (auto-adaptive).\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagDipAngleErrorAdaptiveMeasurement::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "Enable/Disable", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "Low-pass filter curoff frequency [hertz]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "minimum_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagDipAngleErrorAdaptiveMeasurement::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MagDipAngleErrorAdaptiveMeasurement; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "Enable/Disable", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "frequency", + /* .docs = */ "Low-pass filter curoff frequency [hertz]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "high_limit_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "minimum_uncertainty", + /* .docs = */ "1-Sigma [meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MagDipAngleErrorAdaptiveMeasurement", + /* .title = */ "Magnetometer Dig Angle Error Adaptive Measurement", + /* .docs = */ "Enable or disable the magnetometer dip angle error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nThe magnetometer dip angle adaptive measurement is ignored if the auto-adaptive magnetometer magnitude or auto-adaptive accel magnitude options are selected.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AidingMeasurementEnable::AidingSource; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "GNSS_POS_VEL", "GNSS Position and Velocity" }, + { 1, "GNSS_HEADING", "GNSS Heading (dual antenna)" }, + { 2, "ALTIMETER", "Pressure altimeter (built-in sensor)" }, + { 3, "SPEED", "Speed sensor / Odometer" }, + { 4, "MAGNETOMETER", "Magnetometer (built-in sensor)" }, + { 5, "EXTERNAL_HEADING", "External heading input" }, + { 6, "EXTERNAL_ALTIMETER", "External pressure altimeter input" }, + { 7, "EXTERNAL_MAGNETOMETER", "External magnetomer input" }, + { 8, "VEHICLE_FRAME_VEL", "External vehicle frame velocity input" }, + { 65535, "ALL", "Save/load/reset all options" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "AidingSource", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AidingMeasurementEnable::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "aiding_source", + /* .docs = */ "Aiding measurement source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "enable", + /* .docs = */ "Controls the aiding source", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AidingMeasurementEnable::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AidingMeasurementEnable; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "aiding_source", + /* .docs = */ "Aiding measurement source", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "enable", + /* .docs = */ "Controls the aiding source", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AidingMeasurementEnable", + /* .title = */ "Aiding Measurement Control", + /* .docs = */ "Enables / disables the specified aiding measurement source.\n\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::Run; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::Run", + /* .title = */ "Run Navigation Filter", + /* .docs = */ "Manual run command.\n\nIf the initialization configuration has the 'wait_for_run_command' option enabled, the filter will wait until it receives this command before commencing integration and enabling the Kalman filter. Prior to the receipt of this command, the filter will remain in the filter initialization mode.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::KinematicConstraint::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "acceleration_constraint_selection", + /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "velocity_constraint_selection", + /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "angular_constraint_selection", + /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::KinematicConstraint::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::KinematicConstraint; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "acceleration_constraint_selection", + /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "velocity_constraint_selection", + /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "angular_constraint_selection", + /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::KinematicConstraint", + /* .title = */ "Kinematic Constraint Control", + /* .docs = */ "Controls kinematic constraint model selection for the navigation filter.\n\nSee manual for explanation of how the kinematic constraints are applied.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::FilterReferenceFrame; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "ECEF", "WGS84 Earth-fixed, earth centered coordinates" }, + { 2, "LLH", "WGS84 Latitude, longitude, and height above ellipsoid" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "FilterReferenceFrame", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::InitializationConfiguration::AlignmentSelector; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "dual_antenna", "Dual-antenna GNSS alignment" }, + { 2, "kinematic", "GNSS kinematic alignment (GNSS velocity determines initial heading)" }, + { 4, "magnetometer", "Magnetometer heading alignment (Internal magnetometer determines initial heading)" }, + { 8, "external", "External heading alignment (External heading input determines heading)" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "AlignmentSelector", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::InitializationConfiguration::InitialConditionSource; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "AUTO_POS_VEL_ATT", "Automatic position, velocity and attitude" }, + { 1, "AUTO_POS_VEL_PITCH_ROLL", "Automatic position and velocity, automatic pitch and roll, and user-specified heading" }, + { 2, "AUTO_POS_VEL", "Automatic position and velocity, with fully user-specified attitude" }, + { 3, "MANUAL", "User-specified position, velocity, and attitude." }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "InitialConditionSource", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::InitializationConfiguration::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "wait_for_run_command", + /* .docs = */ "Initialize filter only after receiving 'run' command", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_cond_src", + /* .docs = */ "Initial condition source:", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "auto_heading_alignment_selector", + /* .docs = */ "Bitfield specifying the allowed automatic heading alignment methods for automatic initial conditions. Bits are set to 1 to enable, and the correspond to the following:
", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_heading", + /* .docs = */ "User-specified initial platform heading (degrees).", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_pitch", + /* .docs = */ "User-specified initial platform pitch (degrees)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_roll", + /* .docs = */ "User-specified initial platform roll (degrees)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_position", + /* .docs = */ "User-specified initial platform position (units determined by reference frame selector, see note.)", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_velocity", + /* .docs = */ "User-specified initial platform velocity (units determined by reference frame selector, see note.)", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reference_frame_selector", + /* .docs = */ "User-specified initial position/velocity reference frames", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::InitializationConfiguration::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::InitializationConfiguration; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "wait_for_run_command", + /* .docs = */ "Initialize filter only after receiving 'run' command", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_cond_src", + /* .docs = */ "Initial condition source:", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "auto_heading_alignment_selector", + /* .docs = */ "Bitfield specifying the allowed automatic heading alignment methods for automatic initial conditions. Bits are set to 1 to enable, and the correspond to the following:
", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_heading", + /* .docs = */ "User-specified initial platform heading (degrees).", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_pitch", + /* .docs = */ "User-specified initial platform pitch (degrees)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_roll", + /* .docs = */ "User-specified initial platform roll (degrees)", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_position", + /* .docs = */ "User-specified initial platform position (units determined by reference frame selector, see note.)", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "initial_velocity", + /* .docs = */ "User-specified initial platform velocity (units determined by reference frame selector, see note.)", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reference_frame_selector", + /* .docs = */ "User-specified initial position/velocity reference frames", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::InitializationConfiguration", + /* .title = */ "Navigation Filter Initialization", + /* .docs = */ "Controls the source and values used for initial conditions of the navigation solution.\n\nNotes: Initial conditions are the position, velocity, and attitude of the platform used when the filter starts running or is reset.\nFor the user specified position array, the units are meters if the ECEF frame is selected, and degrees latitude, degrees longitude, and meters above ellipsoid if the latitude/longitude/height frame is selected.\nFor the user specified velocity array, the units are meters per second, but the reference frame depends on the reference frame selector (ECEF or NED).", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AdaptiveFilterOptions::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "level", + /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_limit", + /* .docs = */ "Maximum duration of measurement rejection before entering recovery mode (ms)", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AdaptiveFilterOptions::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::AdaptiveFilterOptions; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "level", + /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_limit", + /* .docs = */ "Maximum duration of measurement rejection before entering recovery mode (ms)", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::AdaptiveFilterOptions", + /* .title = */ "Adaptive Filter Control", + /* .docs = */ "Configures the basic setup for auto-adaptive filtering. See product manual for a detailed description of this feature.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MultiAntennaOffset::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "receiver_id", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "antenna_offset", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MultiAntennaOffset::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::MultiAntennaOffset; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "receiver_id", + /* .docs = */ "Receiver: 1, 2, etc...", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "antenna_offset", + /* .docs = */ "Antenna lever arm offset vector in the vehicle frame (m)", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::MultiAntennaOffset", + /* .title = */ "GNSS Multi-Antenna Offset Control", + /* .docs = */ "Set the antenna lever arm.\n\nThis command works with devices that utilize multiple antennas.\n

Offset Limit: 10 m magnitude (default)", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::RelPosConfiguration::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "0 - auto (RTK base station), 1 - manual", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reference_frame_selector", + /* .docs = */ "ECEF or LLH", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reference_coordinates", + /* .docs = */ "reference coordinates, units determined by source selection", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::RelPosConfiguration::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::RelPosConfiguration; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "source", + /* .docs = */ "0 - auto (RTK base station), 1 - manual", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reference_frame_selector", + /* .docs = */ "ECEF or LLH", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reference_coordinates", + /* .docs = */ "reference coordinates, units determined by source selection", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::RelPosConfiguration", + /* .title = */ "Relative Position Configuration", + /* .docs = */ "Configure the reference location for filter relative positioning outputs", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::RefPointLeverArm::ReferencePointSelector; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "VEH", "Defines the origin of the vehicle" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "ReferencePointSelector", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::RefPointLeverArm::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "ref_point_sel", + /* .docs = */ "Reserved, must be 1", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "lever_arm_offset", + /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::RefPointLeverArm::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::RefPointLeverArm; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "ref_point_sel", + /* .docs = */ "Reserved, must be 1", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "lever_arm_offset", + /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::RefPointLeverArm", + /* .title = */ "Reference point lever arm", + /* .docs = */ "Lever arm offset with respect to the sensor for the indicated point of reference.\nThis is used to change the location of the indicated point of reference, and will affect filter position and velocity outputs.\nChanging this setting from default will result in a global position offset that depends on vehicle attitude,\nand a velocity offset that depends on vehicle attitude and angular rate.\n
The lever arm is defined by a 3-element vector that points from the sensor to the desired reference point, with (x,y,z) components given in the vehicle's reference frame.\n

Note, if the reference point selector is set to VEH (1), this setting will affect the following data fields: (0x82, 0x01), (0x82, 0x02), (0x82, 0x40), (0x82, 0x41), and (0x82, 42)\n

Offset Limits\n
Reference Point VEH (1): 10 m magnitude (default)", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SpeedMeasurement; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "Reserved, must be 1.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS time of week when speed was sampled", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "speed", + /* .docs = */ "Estimated speed along vehicle's x-axis (may be positive or negative) [meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "speed_uncertainty", + /* .docs = */ "Estimated uncertainty in the speed measurement (1-sigma value) [meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SpeedMeasurement", + /* .title = */ "Input speed measurement", + /* .docs = */ "Speed aiding measurement, where speed is defined as rate of motion along the vehicle's x-axis direction.\nCan be used by an external odometer/speedometer, for example.\nThis command cannot be used if the internal odometer is configured.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SpeedLeverArm::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "source", + /* .docs = */ "Reserved, must be 1.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "lever_arm_offset", + /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SpeedLeverArm::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SpeedLeverArm; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "source", + /* .docs = */ "Reserved, must be 1.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, true, true, true, true, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "lever_arm_offset", + /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SpeedLeverArm", + /* .title = */ "Measurement speed lever arm", + /* .docs = */ "Lever arm offset for speed measurements.\nThis is used to compensate for an off-center measurement point\nhaving a different speed due to rotation of the vehicle.\nThe typical use case for this would be an odometer attached to a wheel\non a standard 4-wheeled vehicle. If the odometer is on the left wheel,\nit will report higher speed on right turns and lower speed on left turns.\nThis is because the outside edge of the curve is longer than the inside edge.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::WheeledVehicleConstraintControl::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::WheeledVehicleConstraintControl::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::WheeledVehicleConstraintControl; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::WheeledVehicleConstraintControl", + /* .title = */ "Wheeled Vehicle Constraint Control", + /* .docs = */ "Configure the wheeled vehicle kinematic constraint.\n\nWhen enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis.\nBy convention, the primary vehicle axis is the vehicle X-axis (note: the sensor may be physically installed in\nany orientation on the vehicle if the appropriate mounting transformation has been specified).\nThis constraint will typically improve heading estimates for vehicles where the assumption is valid, such\nas an automobile, particularly when GNSS coverage is intermittent.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::VerticalGyroConstraintControl::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::VerticalGyroConstraintControl::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::VerticalGyroConstraintControl; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::VerticalGyroConstraintControl", + /* .title = */ "Vertical Gyro Constraint Control", + /* .docs = */ "Configure the vertical gyro kinematic constraint.\n\nWhen enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track pitch\nand roll under the assumption that the sensor platform is not undergoing linear acceleration.\nThis constraint is useful to maintain accurate pitch and roll during GNSS signal outages.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GnssAntennaCalControl::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "max_offset", + /* .docs = */ "Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GnssAntennaCalControl::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::GnssAntennaCalControl; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "0 - Disable, 1 - Enable", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "max_offset", + /* .docs = */ "Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::GnssAntennaCalControl", + /* .title = */ "GNSS Antenna Offset Calibration Control", + /* .docs = */ "Configure the GNSS antenna lever arm calibration.\n\nWhen enabled, the filter will enable lever arm error tracking, up to the maximum offset specified.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_filter::SetInitialHeading; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "heading", + /* .docs = */ "Initial heading in radians [-pi, pi]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_filter::SetInitialHeading", + /* .title = */ "Set Initial Heading Control", + /* .docs = */ "Set the initial heading angle.\n\nThe estimation filter will reset the heading estimate to provided value. If the product supports magnetometer aiding and this feature has been enabled, the heading\nargument will be ignored and the filter will initialize using the inferred magnetic heading.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + + +static constexpr inline std::initializer_list ALL_COMMANDS_FILTER = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, +}; + + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/commands_gnss.hpp b/src/cpp/mip/metadata/definitions/commands_gnss.hpp new file mode 100644 index 000000000..dbfdecfba --- /dev/null +++ b/src/cpp/mip/metadata/definitions/commands_gnss.hpp @@ -0,0 +1,331 @@ +#pragma once + +#include "common.hpp" + +#include + +#include + +namespace mip::metadata +{ + + +template<> +struct MetadataFor +{ + using type = commands_gnss::ReceiverInfo::Info; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "receiver_id", + /* .docs = */ "Receiver id: e.g. 1, 2, etc.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "mip_data_descriptor_set", + /* .docs = */ "MIP descriptor set associated with this receiver", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "description", + /* .docs = */ "Ascii description of receiver. Contains the following info (comma-delimited):
\nModule name/model
\nFirmware version info", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ NO_FUNCTIONS, + /* .count = */ 32, + /* .condition = */ {}, + }, + }; + + static constexpr inline StructInfo value = { + /* .name = */ "Info", + /* .title = */ "Info", + /* .docs = */ "", + /* .parameters = */ parameters, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_gnss::ReceiverInfo::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "num_receivers", + /* .docs = */ "Number of physical receivers in the device", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "receiver_info", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ {5, microstrain::Index(0) /* num_receivers */}, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_gnss::ReceiverInfo::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_gnss::ReceiverInfo; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_gnss::ReceiverInfo", + /* .title = */ "None", + /* .docs = */ "Return information about the GNSS receivers in the device.\n", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_gnss::SignalConfiguration::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "gps_enable", + /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "glonass_enable", + /* .docs = */ "Bitfield 0: Enable L1OF, 1: Enable L2OF", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "galileo_enable", + /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "beidou_enable", + /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 4, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_gnss::SignalConfiguration::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_gnss::SignalConfiguration; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "gps_enable", + /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "glonass_enable", + /* .docs = */ "Bitfield 0: Enable L1OF, 1: Enable L2OF", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "galileo_enable", + /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "beidou_enable", + /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 4, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_gnss::SignalConfiguration", + /* .title = */ "None", + /* .docs = */ "Configure the GNSS signals used by the device.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_gnss::RtkDongleConfiguration::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "enable", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 3, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_gnss::RtkDongleConfiguration::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_gnss::RtkDongleConfiguration; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "enable", + /* .docs = */ "0 - Disabled, 1- Enabled", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 3, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_gnss::RtkDongleConfiguration", + /* .title = */ "None", + /* .docs = */ "Configure the communications with the RTK Dongle connected to the device.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + + +static constexpr inline std::initializer_list ALL_COMMANDS_GNSS = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, +}; + + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/commands_rtk.hpp b/src/cpp/mip/metadata/definitions/commands_rtk.hpp new file mode 100644 index 000000000..eddf293a5 --- /dev/null +++ b/src/cpp/mip/metadata/definitions/commands_rtk.hpp @@ -0,0 +1,770 @@ +#pragma once + +#include "common.hpp" + +#include + +#include + +namespace mip::metadata +{ + + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetStatusFlags::StatusFlagsLegacy; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 7, "controllerState", "" }, + { 248, "platformState", "" }, + { 1792, "controllerStatusCode", "" }, + { 14336, "platformStatusCode", "" }, + { 49152, "resetCode", "" }, + { 983040, "signalQuality", "" }, + { 4293918720, "reserved", "" }, + { 66060288, "rssi", "" }, + { 201326592, "rsrp", "" }, + { 805306368, "rsrq", "" }, + { 3221225472, "sinr", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "StatusFlagsLegacy", + /* .docs = */ "", + /* .type = */ Type::U32, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetStatusFlags::StatusFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 15, "modem_state", "" }, + { 240, "connection_type", "" }, + { 65280, "rssi", "" }, + { 983040, "signal_quality", "" }, + { 15728640, "tower_change_indicator", "" }, + { 16777216, "nmea_timeout", "" }, + { 33554432, "server_timeout", "" }, + { 67108864, "corrections_timeout", "" }, + { 134217728, "device_out_of_range", "" }, + { 268435456, "corrections_unavailable", "" }, + { 536870912, "reserved", "" }, + { 3221225472, "version", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "StatusFlags", + /* .docs = */ "", + /* .type = */ Type::U32, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetStatusFlags::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "flags", + /* .docs = */ "Model number dependent. See above structures.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetStatusFlags::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetStatusFlags; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetStatusFlags", + /* .title = */ "Get RTK Device Status Flags", + /* .docs = */ "", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetImei::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "IMEI", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 32, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetImei::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetImei; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetImei", + /* .title = */ "Get RTK Device IMEI (International Mobile Equipment Identifier)", + /* .docs = */ "", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetImsi::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "IMSI", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 32, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetImsi::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetImsi; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetImsi", + /* .title = */ "Get RTK Device IMSI (International Mobile Subscriber Identifier)", + /* .docs = */ "", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetIccid::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "ICCID", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 32, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetIccid::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetIccid; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetIccid", + /* .title = */ "Get RTK Device ICCID (Integrated Circuit Card Identification [SIM Number])", + /* .docs = */ "", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::ConnectedDeviceType::Type; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "GENERIC", "" }, + { 1, "GQ7", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "Type", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::ConnectedDeviceType::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "devType", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::ConnectedDeviceType::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::ConnectedDeviceType; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "devType", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::ConnectedDeviceType", + /* .title = */ "Configure or read the type of the connected device", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, true, true, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetActCode::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "ActivationCode", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 32, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetActCode::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetActCode; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetActCode", + /* .title = */ "Get RTK Device Activation Code", + /* .docs = */ "", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetModemFirmwareVersion::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "ModemFirmwareVersion", + /* .docs = */ "", + /* .type = */ {Type::CHAR, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 32, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetModemFirmwareVersion::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetModemFirmwareVersion; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetModemFirmwareVersion", + /* .title = */ "Get RTK Device's Cell Modem Firmware version number", + /* .docs = */ "", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetRssi::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "valid", + /* .docs = */ "", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "rssi", + /* .docs = */ "", + /* .type = */ {Type::S32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "signalQuality", + /* .docs = */ "", + /* .type = */ {Type::S32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetRssi::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::GetRssi; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::GetRssi", + /* .title = */ "None", + /* .docs = */ "Get the RSSI and connected/disconnected status of modem", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::ServiceStatus::ServiceFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "throttle", "" }, + { 2, "corrections_unavailable", "" }, + { 252, "reserved", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ServiceFlags", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::ServiceStatus::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "receivedBytes", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "lastBytes", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "lastBytesTime", + /* .docs = */ "", + /* .type = */ {Type::U64, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::ServiceStatus::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::ServiceStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "reserved1", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved2", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::ServiceStatus", + /* .title = */ "None", + /* .docs = */ "The 3DMRTK will send this message to the server to indicate that the connection should remain open. The Server will respond with information and status.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::MediaSelector; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "MEDIA_ExternalFlash", "" }, + { 1, "MEDIA_SD", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "MediaSelector", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::ProdEraseStorage; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "media", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::ProdEraseStorage", + /* .title = */ "None", + /* .docs = */ "This command will erase the selected media to a raw and uninitialized state. ALL DATA WILL BE LOST.\nThis command is only available in calibration mode.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::LedAction; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "LED_NONE", "" }, + { 1, "LED_FLASH", "" }, + { 2, "LED_PULSATE", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "LedAction", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::LedControl; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "primaryColor", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 3, + /* .condition = */ {}, + }, + { + /* .name = */ "altColor", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 3, + /* .condition = */ {}, + }, + { + /* .name = */ "act", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "period", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::LedControl", + /* .title = */ "None", + /* .docs = */ "This command allows direct control of the LED on the 3DM RTK. This command is only available in calibration mode or Production Test Mode.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_rtk::ModemHardReset; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_rtk::ModemHardReset", + /* .title = */ "None", + /* .docs = */ "This command will clear the modem flash. THIS MUST NOT BE DONE OFTEN AS IT CAN DAMAGE THE FLASH!\nThis command is only available in calibration mode.", + /* .parameters = */ {}, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + + +static constexpr inline std::initializer_list ALL_COMMANDS_RTK = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, +}; + + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/commands_system.hpp b/src/cpp/mip/metadata/definitions/commands_system.hpp new file mode 100644 index 000000000..2a9f7adcf --- /dev/null +++ b/src/cpp/mip/metadata/definitions/commands_system.hpp @@ -0,0 +1,80 @@ +#pragma once + +#include "common.hpp" + +#include + +#include + +namespace mip::metadata +{ + + +template<> +struct MetadataFor +{ + using type = commands_system::CommMode::Response; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "mode", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_system::CommMode::Response", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = commands_system::CommMode; + + static constexpr inline ParameterInfo parameters[] = { + FUNCTION_SELECTOR_PARAM, + { + /* .name = */ "mode", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "commands_system::CommMode", + /* .title = */ "None", + /* .docs = */ "Advanced specialized communication modes.\n\nThis command allows the user to communicate directly with various subsystems which may be present in MIP devices (i.e. IMU, GNSS, etc.)\nPlease see the specific device's user manual for possible modes.\n\nThis command responds with an ACK/NACK just prior to switching to the new protocol.\nFor all functions except 0x01 (use new settings), the new communications mode value is ignored.\n\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ {true, true, false, false, true, true}, + /* .proprietary = */ false, + /* .response = */ &MetadataFor::value, + }; +}; + + +static constexpr inline std::initializer_list ALL_COMMANDS_SYSTEM = { + &MetadataFor::value, + &MetadataFor::value, +}; + + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/data_filter.hpp b/src/cpp/mip/metadata/definitions/data_filter.hpp new file mode 100644 index 000000000..58ba47315 --- /dev/null +++ b/src/cpp/mip/metadata/definitions/data_filter.hpp @@ -0,0 +1,2877 @@ +#pragma once + +#include "common.hpp" + +#include + +#include + +namespace mip::metadata +{ + + +template<> +struct MetadataFor +{ + using type = data_filter::PositionLlh; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "latitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "longitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ellipsoid_height", + /* .docs = */ "[meters]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - Invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::PositionLlh", + /* .title = */ "LLH Position", + /* .docs = */ "Filter reported position in the WGS84 geodetic frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::VelocityNed; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "north", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "east", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "down", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - Invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::VelocityNed", + /* .title = */ "None", + /* .docs = */ "Filter reported velocity in the NED local-level frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AttitudeQuaternion; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "q", + /* .docs = */ "Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AttitudeQuaternion", + /* .title = */ "None", + /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.\nThis quaternion satisfies the following relationship:\n\nEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
\nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AttitudeDcm; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "dcm", + /* .docs = */ "Matrix elements in row-major order.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AttitudeDcm", + /* .title = */ "None", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::EulerAngles; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "roll", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pitch", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "yaw", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::EulerAngles", + /* .title = */ "None", + /* .docs = */ "Filter reported Euler angles describing the orientation of the device with respect to the NED local-level frame.\nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GyroBias; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "bias", + /* .docs = */ "(x, y, z) [radians/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::GyroBias", + /* .title = */ "None", + /* .docs = */ "Filter reported gyro bias expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AccelBias; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "bias", + /* .docs = */ "(x, y, z) [meters/second^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AccelBias", + /* .title = */ "None", + /* .docs = */ "Filter reported accelerometer bias expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::PositionLlhUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "north", + /* .docs = */ "[meters]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "east", + /* .docs = */ "[meters]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "down", + /* .docs = */ "[meters]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::PositionLlhUncertainty", + /* .title = */ "LLH Position Uncertainty", + /* .docs = */ "Filter reported 1-sigma position uncertainty in the NED local-level frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::VelocityNedUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "north", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "east", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "down", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::VelocityNedUncertainty", + /* .title = */ "NED Velocity Uncertainty", + /* .docs = */ "Filter reported 1-sigma velocity uncertainties in the NED local-level frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::EulerAnglesUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "roll", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pitch", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "yaw", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::EulerAnglesUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma Euler angle uncertainties.\nThe uncertainties are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GyroBiasUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "bias_uncert", + /* .docs = */ "(x,y,z) [radians/sec]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::GyroBiasUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma gyro bias uncertainties expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AccelBiasUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "bias_uncert", + /* .docs = */ "(x,y,z) [meters/second^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AccelBiasUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma accelerometer bias uncertainties expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::Timestamp; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "tow", + /* .docs = */ "GPS Time of Week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week Number since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::Timestamp", + /* .title = */ "None", + /* .docs = */ "GPS timestamp of the Filter data\n\nShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.\nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.\nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.\n\nNote: this data field may be deprecated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::FilterMode; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "GX5_STARTUP", "" }, + { 1, "GX5_INIT", "" }, + { 2, "GX5_RUN_SOLUTION_VALID", "" }, + { 3, "GX5_RUN_SOLUTION_ERROR", "" }, + { 1, "INIT", "" }, + { 2, "VERT_GYRO", "" }, + { 3, "AHRS", "" }, + { 4, "FULL_NAV", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "FilterMode", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::FilterDynamicsMode; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "GX5_PORTABLE", "" }, + { 2, "GX5_AUTOMOTIVE", "" }, + { 3, "GX5_AIRBORNE", "" }, + { 1, "GQ7_DEFAULT", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "FilterDynamicsMode", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::FilterStatusFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 4096, "gx5_init_no_attitude", "" }, + { 8192, "gx5_init_no_position_velocity", "" }, + { 1, "gx5_run_imu_unavailable", "" }, + { 2, "gx5_run_gps_unavailable", "" }, + { 8, "gx5_run_matrix_singularity", "" }, + { 16, "gx5_run_position_covariance_warning", "" }, + { 32, "gx5_run_velocity_covariance_warning", "" }, + { 64, "gx5_run_attitude_covariance_warning", "" }, + { 128, "gx5_run_nan_in_solution_warning", "" }, + { 256, "gx5_run_gyro_bias_est_high_warning", "" }, + { 512, "gx5_run_accel_bias_est_high_warning", "" }, + { 1024, "gx5_run_gyro_scale_factor_est_high_warning", "" }, + { 2048, "gx5_run_accel_scale_factor_est_high_warning", "" }, + { 4096, "gx5_run_mag_bias_est_high_warning", "" }, + { 8192, "gx5_run_ant_offset_correction_est_high_warning", "" }, + { 16384, "gx5_run_mag_hard_iron_est_high_warning", "" }, + { 32768, "gx5_run_mag_soft_iron_est_high_warning", "" }, + { 3, "gq7_filter_condition", "" }, + { 4, "gq7_roll_pitch_warning", "" }, + { 8, "gq7_heading_warning", "" }, + { 16, "gq7_position_warning", "" }, + { 32, "gq7_velocity_warning", "" }, + { 64, "gq7_imu_bias_warning", "" }, + { 128, "gq7_gnss_clk_warning", "" }, + { 256, "gq7_antenna_lever_arm_warning", "" }, + { 512, "gq7_mounting_transform_warning", "" }, + { 1024, "gq7_time_sync_warning", "No time synchronization pulse detected" }, + { 61440, "gq7_solution_error", "Filter computation warning flags. If any bits 12-15 are set, and all filter outputs will be invalid." }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "FilterStatusFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::Status; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "filter_state", + /* .docs = */ "Device-specific filter state. Please consult the user manual for definition.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "dynamics_mode", + /* .docs = */ "Device-specific dynamics mode. Please consult the user manual for definition.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "status_flags", + /* .docs = */ "Device-specific status flags. Please consult the user manual for definition.", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::Status", + /* .title = */ "None", + /* .docs = */ "Device-specific filter status indicators.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::LinearAccel; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "accel", + /* .docs = */ "(x,y,z) [meters/second^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::LinearAccel", + /* .title = */ "None", + /* .docs = */ "Filter-compensated linear acceleration expressed in the vehicle frame.\nNote: The estimated gravity has been removed from this data leaving only linear acceleration.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GravityVector; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "gravity", + /* .docs = */ "(x, y, z) [meters/second^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::GravityVector", + /* .title = */ "None", + /* .docs = */ "Filter reported gravity vector expressed in the vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::CompAccel; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "accel", + /* .docs = */ "(x,y,z) [meters/second^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::CompAccel", + /* .title = */ "Compensated Acceleration", + /* .docs = */ "Filter-compensated acceleration expressed in the vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::CompAngularRate; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "gyro", + /* .docs = */ "(x, y, z) [radians/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::CompAngularRate", + /* .title = */ "None", + /* .docs = */ "Filter-compensated angular rate expressed in the vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::QuaternionAttitudeUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "q", + /* .docs = */ "[dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::QuaternionAttitudeUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported quaternion uncertainties.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::Wgs84GravityMag; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "magnitude", + /* .docs = */ "[meters/second^2]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::Wgs84GravityMag", + /* .title = */ "None", + /* .docs = */ "Filter reported WGS84 gravity magnitude.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::HeadingUpdateState::HeadingSource; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "NONE", "" }, + { 1, "MAGNETOMETER", "" }, + { 2, "GNSS_VELOCITY_VECTOR", "" }, + { 4, "EXTERNAL", "" }, + { 8, "DUAL_ANTENNA", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "HeadingSource", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::HeadingUpdateState; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "heading", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading_1sigma", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "source", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "1 if a valid heading update was received in 2 seconds, 0 otherwise.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::HeadingUpdateState", + /* .title = */ "None", + /* .docs = */ "Filter reported heading update state.\n\nHeading updates can be applied from the sources listed below. Note, some of these sources may be combined.\nThe heading value is always relative to true north.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MagneticModel; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "intensity_north", + /* .docs = */ "[Gauss]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "intensity_east", + /* .docs = */ "[Gauss]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "intensity_down", + /* .docs = */ "[Gauss]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "inclination", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "declination", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MagneticModel", + /* .title = */ "None", + /* .docs = */ "The World Magnetic Model is used for this data. Please refer to the device user manual for the current version of the model.\nA valid GNSS location is required for the model to be valid.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AccelScaleFactor; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scale_factor", + /* .docs = */ "(x,y,z) [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AccelScaleFactor", + /* .title = */ "None", + /* .docs = */ "Filter reported accelerometer scale factor expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AccelScaleFactorUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scale_factor_uncert", + /* .docs = */ "(x,y,z) [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AccelScaleFactorUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma accelerometer scale factor uncertainty expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GyroScaleFactor; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scale_factor", + /* .docs = */ "(x,y,z) [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::GyroScaleFactor", + /* .title = */ "None", + /* .docs = */ "Filter reported gyro scale factor expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GyroScaleFactorUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scale_factor_uncert", + /* .docs = */ "(x,y,z) [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::GyroScaleFactorUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma gyro scale factor uncertainty expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MagBias; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "bias", + /* .docs = */ "(x,y,z) [Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MagBias", + /* .title = */ "None", + /* .docs = */ "Filter reported magnetometer bias expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MagBiasUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "bias_uncert", + /* .docs = */ "(x,y,z) [Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MagBiasUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma magnetometer bias uncertainty expressed in the sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::StandardAtmosphere; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "geometric_altitude", + /* .docs = */ "Input into calculation [meters]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "geopotential_altitude", + /* .docs = */ "[meters]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "standard_temperature", + /* .docs = */ "[degC]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "standard_pressure", + /* .docs = */ "[milliBar]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "standard_density", + /* .docs = */ "[kilogram/meter^3]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::StandardAtmosphere", + /* .title = */ "None", + /* .docs = */ "Filter reported standard atmosphere parameters.\n\nThe US 1976 Standard Atmosphere Model is used. A valid GNSS location is required for the model to be valid.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::PressureAltitude; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "pressure_altitude", + /* .docs = */ "[meters]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::PressureAltitude", + /* .title = */ "None", + /* .docs = */ "Filter reported pressure altitude.\n\nThe US 1976 Standard Atmosphere Model is used to calculate the pressure altitude in meters.\nA valid pressure sensor reading is required for the pressure altitude to be valid.\nThe minimum pressure reading supported by the model is 0.0037 mBar, corresponding to an altitude of 84,852 meters.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::DensityAltitude; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "density_altitude", + /* .docs = */ "m", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::DensityAltitude", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AntennaOffsetCorrection; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "offset", + /* .docs = */ "(x,y,z) [meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AntennaOffsetCorrection", + /* .title = */ "None", + /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.\n\nThis offset added to any previously stored offset vector to compensate for errors in definition.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AntennaOffsetCorrectionUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "offset_uncert", + /* .docs = */ "(x,y,z) [meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AntennaOffsetCorrectionUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma GNSS antenna offset uncertainties in vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MultiAntennaOffsetCorrection; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "receiver_id", + /* .docs = */ "Receiver ID for the receiver to which the antenna is attached", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "offset", + /* .docs = */ "(x,y,z) [meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MultiAntennaOffsetCorrection", + /* .title = */ "None", + /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.\n\nThis offset added to any previously stored offset vector to compensate for errors in definition.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MultiAntennaOffsetCorrectionUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "receiver_id", + /* .docs = */ "Receiver ID for the receiver to which the antenna is attached", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "offset_uncert", + /* .docs = */ "(x,y,z) [meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MultiAntennaOffsetCorrectionUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma GNSS antenna offset uncertainties in vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MagnetometerOffset; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "hard_iron", + /* .docs = */ "(x,y,z) [Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MagnetometerOffset", + /* .title = */ "None", + /* .docs = */ "Filter reported magnetometer hard iron offset in sensor frame.\n\nThis offset added to any previously stored hard iron offset vector to compensate for magnetometer in-run bias errors.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MagnetometerMatrix; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "soft_iron", + /* .docs = */ "Row-major [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MagnetometerMatrix", + /* .title = */ "None", + /* .docs = */ "Filter reported magnetometer soft iron matrix in sensor frame.\n\nThis matrix is post multiplied to any previously stored soft iron matrix to compensate for magnetometer in-run errors.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MagnetometerOffsetUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "hard_iron_uncertainty", + /* .docs = */ "(x,y,z) [Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MagnetometerOffsetUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma magnetometer hard iron offset uncertainties in sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MagnetometerMatrixUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "soft_iron_uncertainty", + /* .docs = */ "Row-major [dimensionless]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MagnetometerMatrixUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma magnetometer soft iron matrix uncertainties in sensor frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MagnetometerCovarianceMatrix; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "covariance", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MagnetometerCovarianceMatrix", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::MagnetometerResidualVector; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "residual", + /* .docs = */ "(x,y,z) [Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::MagnetometerResidualVector", + /* .title = */ "None", + /* .docs = */ "Filter reported magnetometer measurement residuals in vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::ClockCorrection; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "receiver_id", + /* .docs = */ "1, 2, etc.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "bias", + /* .docs = */ "[seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "bias_drift", + /* .docs = */ "[seconds/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::ClockCorrection", + /* .title = */ "None", + /* .docs = */ "Filter reported GNSS receiver clock error parameters.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::ClockCorrectionUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "receiver_id", + /* .docs = */ "1, 2, etc.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "bias_uncertainty", + /* .docs = */ "[seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "bias_drift_uncertainty", + /* .docs = */ "[seconds/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::ClockCorrectionUncertainty", + /* .title = */ "None", + /* .docs = */ "Filter reported 1-sigma GNSS receiver clock error parameters.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GnssAidStatusFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tight_coupling", "If 1, the Kalman filter is processing raw range information from this GNSS module" }, + { 2, "differential", "If 1, the Kalman filter is processing RTK corrections from this GNSS module" }, + { 4, "integer_fix", "If 1, the Kalman filter has an RTK integer fix from this GNSS module, indicating the best position performance possible" }, + { 8, "GPS_L1", "If 1, the Kalman filter is using GPS L1 measurements" }, + { 16, "GPS_L2", "If 1, the Kalman filter is using GPS L2 measurements" }, + { 32, "GPS_L5", "If 1, the Kalman filter is using GPS L5 measurements (not available on the GQ7)" }, + { 64, "GLO_L1", "If 1, the Kalman filter is using GLONASS L1 measurements" }, + { 128, "GLO_L2", "If 1, the Kalman filter is using GLONASS L2 measurements" }, + { 256, "GAL_E1", "If 1, the Kalman filter is using Galileo E1 measurements" }, + { 512, "GAL_E5", "If 1, the Kalman filter is using Galileo E5 measurements" }, + { 1024, "GAL_E6", "If 1, the Kalman filter is using Galileo E6 measurements" }, + { 2048, "BEI_B1", "If 1, the Kalman filter is using Beidou B1 measurements (not enabled on GQ7 currently)" }, + { 4096, "BEI_B2", "If 1, the Kalman filter is using Beidou B2 measurements (not enabled on GQ7 currently)" }, + { 8192, "BEI_B3", "If 1, the Kalman filter is using Beidou B3 measurements (not available on the GQ7)" }, + { 16384, "no_fix", "If 1, this GNSS module is reporting no position fix" }, + { 32768, "config_error", "If 1, there is likely an issue with the antenna offset for this GNSS module" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "GnssAidStatusFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GnssPosAidStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "receiver_id", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_of_week", + /* .docs = */ "Last GNSS aiding measurement time of week [seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "status", + /* .docs = */ "Aiding measurement status bitfield", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 8, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::GnssPosAidStatus", + /* .title = */ "GNSS Position Aiding Status", + /* .docs = */ "Filter reported GNSS position aiding status", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GnssAttAidStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_of_week", + /* .docs = */ "Last valid aiding measurement time of week [seconds] [processed instead of measured?]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "status", + /* .docs = */ "Last valid aiding measurement status bitfield", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 8, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::GnssAttAidStatus", + /* .title = */ "GNSS Attitude Aiding Status", + /* .docs = */ "Filter reported dual antenna GNSS attitude aiding status", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::HeadAidStatus::HeadingAidType; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "DUAL_ANTENNA", "" }, + { 2, "EXTERNAL_MESSAGE", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "HeadingAidType", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::HeadAidStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_of_week", + /* .docs = */ "Last valid aiding measurement time of week [seconds] [processed instead of measured?]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "type", + /* .docs = */ "1 - Dual antenna, 2 - External heading message (user supplied)", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 2, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::HeadAidStatus", + /* .title = */ "None", + /* .docs = */ "Filter reported GNSS heading aiding status", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::RelPosNed; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "relative_position", + /* .docs = */ "[meters, NED]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::RelPosNed", + /* .title = */ "NED Relative Position", + /* .docs = */ "Filter reported relative position, with respect to configured reference position", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::EcefPos; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "position_ecef", + /* .docs = */ "[meters, ECEF]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::EcefPos", + /* .title = */ "ECEF Position", + /* .docs = */ "Filter reported ECEF position", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::EcefVel; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "velocity_ecef", + /* .docs = */ "[meters/second, ECEF]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::EcefVel", + /* .title = */ "ECEF Velocity", + /* .docs = */ "Filter reported ECEF velocity", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::EcefPosUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "pos_uncertainty", + /* .docs = */ "[meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::EcefPosUncertainty", + /* .title = */ "ECEF Position Uncertainty", + /* .docs = */ "Filter reported 1-sigma position uncertainty in the ECEF frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::EcefVelUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "vel_uncertainty", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::EcefVelUncertainty", + /* .title = */ "ECEF Velocity Uncertainty", + /* .docs = */ "Filter reported 1-sigma velocity uncertainties in the ECEF frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::FilterAidingMeasurementType; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "GNSS", "" }, + { 2, "DUAL_ANTENNA", "" }, + { 3, "HEADING", "" }, + { 4, "PRESSURE", "" }, + { 5, "MAGNETOMETER", "" }, + { 6, "SPEED", "" }, + { 33, "POS_ECEF", "" }, + { 34, "POS_LLH", "" }, + { 40, "VEL_ECEF", "" }, + { 41, "VEL_NED", "" }, + { 42, "VEL_VEHICLE_FRAME", "" }, + { 49, "HEADING_TRUE", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "FilterAidingMeasurementType", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::FilterMeasurementIndicator; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "enabled", "" }, + { 2, "used", "" }, + { 4, "residual_high_warning", "" }, + { 8, "sample_time_warning", "" }, + { 16, "configuration_error", "" }, + { 32, "max_num_meas_exceeded", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "FilterMeasurementIndicator", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AidingMeasurementSummary; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_of_week", + /* .docs = */ "[seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "source", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "type", + /* .docs = */ "(see product manual for supported types) Note: values 0x20 and above correspond to commanded aiding measurements in the 0x13 Aiding command set.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "indicator", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AidingMeasurementSummary", + /* .title = */ "None", + /* .docs = */ "Filter reported aiding measurement summary. This message contains a summary of the specified aiding measurement over the previous measurement interval ending at the specified time.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::OdometerScaleFactorError; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scale_factor_error", + /* .docs = */ "[dimensionless]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::OdometerScaleFactorError", + /* .title = */ "Odometer Scale Factor Error", + /* .docs = */ "Filter reported odometer scale factor error. The total scale factor estimate is the user indicated scale factor, plus the user indicated scale factor times the scale factor error.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::OdometerScaleFactorErrorUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scale_factor_error_uncertainty", + /* .docs = */ "[dimensionless]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::OdometerScaleFactorErrorUncertainty", + /* .title = */ "Odometer Scale Factor Error Uncertainty", + /* .docs = */ "Filter reported odometer scale factor error uncertainty.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GnssDualAntennaStatus::FixType; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "FIX_NONE", "" }, + { 1, "FIX_DA_FLOAT", "" }, + { 2, "FIX_DA_FIXED", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "FixType", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GnssDualAntennaStatus::DualAntennaStatusFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "rcv_1_data_valid", "" }, + { 2, "rcv_2_data_valid", "" }, + { 4, "antenna_offsets_valid", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "DualAntennaStatusFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_filter::GnssDualAntennaStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_of_week", + /* .docs = */ "Last dual-antenna GNSS aiding measurement time of week [seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading_unc", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "fix_type", + /* .docs = */ "Fix type indicator", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "status_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "0 - invalid, 1 - valid", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::GnssDualAntennaStatus", + /* .title = */ "GNSS Dual Antenna Status", + /* .docs = */ "Summary information for status of GNSS dual antenna heading estimate.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AidingFrameConfigError; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "frame_id", + /* .docs = */ "Frame ID for the receiver to which the antenna is attached", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "translation", + /* .docs = */ "Translation config X, Y, and Z (m).", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "attitude", + /* .docs = */ "Attitude quaternion", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AidingFrameConfigError", + /* .title = */ "Aiding Frame Configuration Error", + /* .docs = */ "Filter reported aiding source frame configuration error\n\nThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_filter::AidingFrameConfigErrorUncertainty; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "frame_id", + /* .docs = */ "Frame ID for the receiver to which the antenna is attached", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "translation_unc", + /* .docs = */ "Translation uncertaint X, Y, and Z (m).", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "attitude_unc", + /* .docs = */ "Attitude uncertainty, X, Y, and Z (radians).", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_filter::AidingFrameConfigErrorUncertainty", + /* .title = */ "Aiding Frame Configuration Error Uncertainty", + /* .docs = */ "Filter reported aiding source frame configuration error uncertainty\n\nThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + + +static constexpr inline std::initializer_list ALL_DATA_FILTER = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, +}; + + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/data_gnss.hpp b/src/cpp/mip/metadata/definitions/data_gnss.hpp new file mode 100644 index 000000000..5b9d66848 --- /dev/null +++ b/src/cpp/mip/metadata/definitions/data_gnss.hpp @@ -0,0 +1,3812 @@ +#pragma once + +#include "common.hpp" + +#include + +#include + +namespace mip::metadata +{ + + +template<> +struct MetadataFor +{ + using type = data_gnss::PosLlh::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "lat_lon", "" }, + { 2, "ellipsoid_height", "" }, + { 4, "msl_height", "" }, + { 8, "horizontal_accuracy", "" }, + { 16, "vertical_accuracy", "" }, + { 31, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::PosLlh; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "latitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "longitude", + /* .docs = */ "[degrees]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ellipsoid_height", + /* .docs = */ "[meters]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "msl_height", + /* .docs = */ "[meters]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "horizontal_accuracy", + /* .docs = */ "[meters]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "vertical_accuracy", + /* .docs = */ "[meters]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::PosLlh", + /* .title = */ "GNSS LLH Position", + /* .docs = */ "GNSS reported position in the WGS84 geodetic frame", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::PosEcef::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "position", "" }, + { 2, "position_accuracy", "" }, + { 3, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::PosEcef; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "x", + /* .docs = */ "[meters]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "x_accuracy", + /* .docs = */ "[meters]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::PosEcef", + /* .title = */ "GNSS ECEF Position", + /* .docs = */ "GNSS reported position in the Earth-centered, Earth-Fixed (ECEF) frame", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::VelNed::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "velocity", "" }, + { 2, "speed_3d", "" }, + { 4, "ground_speed", "" }, + { 8, "heading", "" }, + { 16, "speed_accuracy", "" }, + { 32, "heading_accuracy", "" }, + { 63, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::VelNed; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "v", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "speed", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ground_speed", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading", + /* .docs = */ "[degrees]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "speed_accuracy", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "heading_accuracy", + /* .docs = */ "[degrees]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::VelNed", + /* .title = */ "NED Velocity", + /* .docs = */ "GNSS reported velocity in the NED frame", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::VelEcef::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "velocity", "" }, + { 2, "velocity_accuracy", "" }, + { 3, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::VelEcef; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "v", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "v_accuracy", + /* .docs = */ "[meters/second]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::VelEcef", + /* .title = */ "GNSS ECEF Velocity", + /* .docs = */ "GNSS reported velocity in the Earth-centered, Earth-Fixed (ECEF) frame", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::Dop::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "gdop", "" }, + { 2, "pdop", "" }, + { 4, "hdop", "" }, + { 8, "vdop", "" }, + { 16, "tdop", "" }, + { 32, "ndop", "" }, + { 64, "edop", "" }, + { 127, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::Dop; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "gdop", + /* .docs = */ "Geometric DOP", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pdop", + /* .docs = */ "Position DOP", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "hdop", + /* .docs = */ "Horizontal DOP", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "vdop", + /* .docs = */ "Vertical DOP", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "tdop", + /* .docs = */ "Time DOP", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ndop", + /* .docs = */ "Northing DOP", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "edop", + /* .docs = */ "Easting DOP", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::Dop", + /* .title = */ "None", + /* .docs = */ "GNSS reported dilution of precision information.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::UtcTime::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "gnss_date_time", "" }, + { 2, "leap_seconds_known", "" }, + { 3, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::UtcTime; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "year", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "month", + /* .docs = */ "Month (1-12)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "day", + /* .docs = */ "Day (1-31)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "hour", + /* .docs = */ "Hour (0-23)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "min", + /* .docs = */ "Minute (0-59)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sec", + /* .docs = */ "Second (0-59)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "msec", + /* .docs = */ "Millisecond(0-999)", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::UtcTime", + /* .title = */ "None", + /* .docs = */ "GNSS reported Coordinated Universal Time", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GpsTime::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tow", "" }, + { 2, "week_number", "" }, + { 3, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GpsTime; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "tow", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::GpsTime", + /* .title = */ "None", + /* .docs = */ "GNSS reported GPS Time", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::ClockInfo::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "bias", "" }, + { 2, "drift", "" }, + { 4, "accuracy_estimate", "" }, + { 7, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::ClockInfo; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "bias", + /* .docs = */ "[seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "drift", + /* .docs = */ "[seconds/second]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "accuracy_estimate", + /* .docs = */ "[seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::ClockInfo", + /* .title = */ "None", + /* .docs = */ "GNSS reported receiver clock parameters", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::FixInfo::FixType; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "FIX_3D", "" }, + { 1, "FIX_2D", "" }, + { 2, "FIX_TIME_ONLY", "" }, + { 3, "FIX_NONE", "" }, + { 4, "FIX_INVALID", "" }, + { 5, "FIX_RTK_FLOAT", "" }, + { 6, "FIX_RTK_FIXED", "" }, + { 7, "FIX_DIFFERENTIAL", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "FixType", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::FixInfo::FixFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "sbas_used", "" }, + { 2, "dgnss_used", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "FixFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::FixInfo::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "fix_type", "" }, + { 2, "num_sv", "" }, + { 4, "fix_flags", "" }, + { 7, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::FixInfo; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "fix_type", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "num_sv", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "fix_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::FixInfo", + /* .title = */ "None", + /* .docs = */ "GNSS reported position fix type", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SvInfo::SVFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "used_for_navigation", "" }, + { 2, "healthy", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "SVFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SvInfo::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "channel", "" }, + { 2, "sv_id", "" }, + { 4, "carrier_noise_ratio", "" }, + { 8, "azimuth", "" }, + { 16, "elevation", "" }, + { 32, "sv_flags", "" }, + { 63, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SvInfo; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "channel", + /* .docs = */ "Receiver channel number", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sv_id", + /* .docs = */ "GNSS Satellite ID", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "carrier_noise_ratio", + /* .docs = */ "[dBHz]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "azimuth", + /* .docs = */ "[deg]", + /* .type = */ {Type::S16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "elevation", + /* .docs = */ "[deg]", + /* .type = */ {Type::S16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sv_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::SvInfo", + /* .title = */ "None", + /* .docs = */ "GNSS reported space vehicle information\n\nWhen enabled, these fields will arrive in separate MIP packets", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::HwStatus::ReceiverState; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "OFF", "" }, + { 1, "ON", "" }, + { 2, "UNKNOWN", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "ReceiverState", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::HwStatus::AntennaState; + + static constexpr inline EnumInfo::Entry entries[] = { + { 1, "INIT", "" }, + { 2, "SHORT", "" }, + { 3, "OPEN", "" }, + { 4, "GOOD", "" }, + { 5, "UNKNOWN", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "AntennaState", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::HwStatus::AntennaPower; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "OFF", "" }, + { 1, "ON", "" }, + { 2, "UNKNOWN", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "AntennaPower", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::HwStatus::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "sensor_state", "" }, + { 2, "antenna_state", "" }, + { 4, "antenna_power", "" }, + { 7, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::HwStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "receiver_state", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "antenna_state", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "antenna_power", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::HwStatus", + /* .title = */ "GNSS Hardware Status", + /* .docs = */ "GNSS reported hardware status", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::DgpsInfo::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "age", "" }, + { 2, "base_station_id", "" }, + { 4, "base_station_status", "" }, + { 8, "num_channels", "" }, + { 15, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::DgpsInfo; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "sv_id", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "age", + /* .docs = */ "", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "range_correction", + /* .docs = */ "", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "range_rate_correction", + /* .docs = */ "", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::DgpsInfo", + /* .title = */ "None", + /* .docs = */ "GNSS reported DGNSS status\n\n
Possible Base Station Status Values:
\n
  0 - UDRE Scale Factor = 1.0
\n
  1 - UDRE Scale Factor = 0.75
\n
  2 - UDRE Scale Factor = 0.5
\n
  3 - UDRE Scale Factor = 0.3
\n
  4 - UDRE Scale Factor = 0.2
\n
  5 - UDRE Scale Factor = 0.1
\n
  6 - Reference Station Transmission Not Monitored
\n
  7 - Reference Station Not Working
\n\n(UDRE = User Differential Range Error)", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::DgpsChannel::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "id", "" }, + { 2, "age", "" }, + { 4, "range_correction", "" }, + { 8, "range_rate_correction", "" }, + { 15, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::DgpsChannel; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "sv_id", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "age", + /* .docs = */ "[s]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "range_correction", + /* .docs = */ "[m]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "range_rate_correction", + /* .docs = */ "[m/s]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::DgpsChannel", + /* .title = */ "None", + /* .docs = */ "GNSS reported DGPS Channel Status status\n\nWhen enabled, a separate field for each active space vehicle will be sent in the packet.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::ClockInfo2::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "bias", "" }, + { 2, "drift", "" }, + { 4, "bias_accuracy", "" }, + { 8, "drift_accuracy", "" }, + { 15, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::ClockInfo2; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "bias", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "drift", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "bias_accuracy_estimate", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "drift_accuracy_estimate", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::ClockInfo2", + /* .title = */ "None", + /* .docs = */ "GNSS reported receiver clock parameters\n\nThis supersedes MIP_DATA_DESC_GNSS_CLOCK_INFO with additional information.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GpsLeapSeconds::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 2, "leap_seconds", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GpsLeapSeconds; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "leap_seconds", + /* .docs = */ "[s]", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::GpsLeapSeconds", + /* .title = */ "None", + /* .docs = */ "GNSS reported leap seconds (difference between GPS and UTC Time)", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SbasSystem; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "UNKNOWN", "" }, + { 1, "WAAS", "" }, + { 2, "EGNOS", "" }, + { 3, "MSAS", "" }, + { 4, "GAGAN", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "SbasSystem", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SbasInfo::SbasStatus; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "range_available", "" }, + { 2, "corrections_available", "" }, + { 4, "integrity_available", "" }, + { 8, "test_mode", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "SbasStatus", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SbasInfo::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tow", "" }, + { 2, "week_number", "" }, + { 4, "sbas_system", "" }, + { 8, "sbas_id", "" }, + { 16, "count", "" }, + { 32, "sbas_status", "" }, + { 63, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SbasInfo; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sbas_system", + /* .docs = */ "SBAS system id", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sbas_id", + /* .docs = */ "SBAS satellite id.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "count", + /* .docs = */ "Number of SBAS corrections", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sbas_status", + /* .docs = */ "Status of the SBAS service", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::SbasInfo", + /* .title = */ "None", + /* .docs = */ "GNSS SBAS status", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GnssConstellationId; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "UNKNOWN", "" }, + { 1, "GPS", "" }, + { 2, "GLONASS", "" }, + { 3, "GALILEO", "" }, + { 4, "BEIDOU", "" }, + { 5, "SBAS", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "GnssConstellationId", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SbasCorrection::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "udrei", "" }, + { 2, "pseudorange_correction", "" }, + { 4, "iono_correction", "" }, + { 7, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SbasCorrection; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "index", + /* .docs = */ "Index of this field in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "count", + /* .docs = */ "Total number of fields in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week the message was received [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "gnss_id", + /* .docs = */ "GNSS constellation id", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sv_id", + /* .docs = */ "GNSS satellite id within the constellation.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "udrei", + /* .docs = */ "[See above 0-13 usable, 14 not monitored, 15 - do not use]", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pseudorange_correction", + /* .docs = */ "Pseudo-range correction [meters].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "iono_correction", + /* .docs = */ "Ionospheric correction [meters].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::SbasCorrection", + /* .title = */ "None", + /* .docs = */ "GNSS calculated SBAS Correction\n\nUDREI - the variance of a normal distribution associated with the user differential range errors for a\nsatellite after application of fast and long-term corrections, excluding atmospheric effects\n\n
UDREI  Variance
\n
-----------------------
\n
0      0.0520 m^2
\n
1      0.0924 m^2
\n
2      0.1444 m^2
\n
3      0.2830 m^2
\n
4      0.4678 m^2
\n
5      0.8315 m^2
\n
6      1.2992 m^2
\n
7      1.8709 m^2
\n
8      2.5465 m^2
\n
9      3.3260 m^2
\n
10     5.1968 m^2
\n
11     20.7870 m^2
\n
12     230.9661 m^2
\n
13     2078.695 m^2
\n
14     'Not Monitored'
\n
15     'Do Not Use'
", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::RfErrorDetection::RFBand; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "UNKNOWN", "" }, + { 1, "L1", "" }, + { 2, "L2", "" }, + { 5, "L5", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "RFBand", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::RfErrorDetection::JammingState; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "UNKNOWN", "" }, + { 1, "NONE", "" }, + { 2, "PARTIAL", "" }, + { 3, "SIGNIFICANT", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "JammingState", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::RfErrorDetection::SpoofingState; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "UNKNOWN", "" }, + { 1, "NONE", "" }, + { 2, "PARTIAL", "" }, + { 3, "SIGNIFICANT", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "SpoofingState", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::RfErrorDetection::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "rf_band", "" }, + { 2, "jamming_state", "" }, + { 4, "spoofing_state", "" }, + { 7, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::RfErrorDetection; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "rf_band", + /* .docs = */ "RF Band of the reported information", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "jamming_state", + /* .docs = */ "GNSS Jamming State (as reported by the GNSS module)", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "spoofing_state", + /* .docs = */ "GNSS Spoofing State (as reported by the GNSS module)", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "Reserved for future use", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 4, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::RfErrorDetection", + /* .title = */ "None", + /* .docs = */ "GNSS Error Detection subsystem status", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::BaseStationInfo::IndicatorFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "gps", "" }, + { 2, "glonass", "" }, + { 4, "galileo", "" }, + { 8, "beidou", "" }, + { 16, "ref_station", "" }, + { 32, "single_receiver", "" }, + { 64, "quarter_cycle_bit1", "" }, + { 128, "quarter_cycle_bit2", "" }, + { 192, "quarter_cycle_bits", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "IndicatorFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::BaseStationInfo::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tow", "" }, + { 2, "week_number", "" }, + { 4, "ecef_position", "" }, + { 8, "height", "" }, + { 16, "station_id", "" }, + { 32, "indicators", "" }, + { 63, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::BaseStationInfo; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week the message was received [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ecef_pos", + /* .docs = */ "Earth-centered, Earth-fixed [m]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "height", + /* .docs = */ "Antenna Height above the marker used in the survey [m]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "station_id", + /* .docs = */ "Range: 0-4095", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "indicators", + /* .docs = */ "Bitfield", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::BaseStationInfo", + /* .title = */ "None", + /* .docs = */ "RTCM reported base station information (sourced from RTCM Message 1005 or 1006)\n\nValid Flag Mapping:", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::RtkCorrectionsStatus::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tow", "" }, + { 2, "week_number", "" }, + { 4, "epoch_status", "" }, + { 8, "dongle_status", "" }, + { 16, "gps_latency", "" }, + { 32, "glonass_latency", "" }, + { 64, "galileo_latency", "" }, + { 128, "beidou_latency", "" }, + { 255, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::RtkCorrectionsStatus::EpochStatus; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "antenna_location_received", "" }, + { 2, "antenna_description_received", "" }, + { 4, "gps_received", "" }, + { 8, "glonass_received", "" }, + { 16, "galileo_received", "" }, + { 32, "beidou_received", "" }, + { 64, "using_gps_msm_messages", "Using MSM messages for GPS corrections instead of RTCM messages 1001-1004" }, + { 128, "using_glonass_msm_messages", "Using MSM messages for GLONASS corrections instead of RTCM messages 1009-1012" }, + { 256, "dongle_status_read_failed", "A read of the dongle status was attempted, but failed" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "EpochStatus", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::RtkCorrectionsStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "epoch_status", + /* .docs = */ "Status of the corrections received during this epoch", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "dongle_status", + /* .docs = */ "RTK Dongle Status Flags (valid only when using RTK dongle, see Get RTK Device Status Flags (0x0F,0x01) for details)", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "gps_correction_latency", + /* .docs = */ "Latency of last GPS correction [seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "glonass_correction_latency", + /* .docs = */ "Latency of last GLONASS correction [seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "galileo_correction_latency", + /* .docs = */ "Latency of last Galileo correction [seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "beidou_correction_latency", + /* .docs = */ "Latency of last Beidou correction [seconds]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "reserved", + /* .docs = */ "Reserved for future use", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 4, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::RtkCorrectionsStatus", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SatelliteStatus::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tow", "" }, + { 2, "week_number", "" }, + { 4, "gnss_id", "" }, + { 8, "satellite_id", "" }, + { 16, "elevation", "" }, + { 32, "azimuth", "" }, + { 64, "health", "" }, + { 127, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::SatelliteStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "index", + /* .docs = */ "Index of this field in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "count", + /* .docs = */ "Total number of fields in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "gnss_id", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "satellite_id", + /* .docs = */ "GNSS satellite id within the constellation", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "elevation", + /* .docs = */ "Elevation of the satellite relative to the rover [degrees]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "azimuth", + /* .docs = */ "Azimuth of the satellite relative to the rover [degrees]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "health", + /* .docs = */ "True if the satellite is healthy.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::SatelliteStatus", + /* .title = */ "None", + /* .docs = */ "Status information for a GNSS satellite.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GnssSignalId; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "UNKNOWN", "" }, + { 1, "GPS_L1CA", "" }, + { 2, "GPS_L1P", "" }, + { 3, "GPS_L1Z", "" }, + { 4, "GPS_L2CA", "" }, + { 5, "GPS_L2P", "" }, + { 6, "GPS_L2Z", "" }, + { 7, "GPS_L2CL", "" }, + { 8, "GPS_L2CM", "" }, + { 9, "GPS_L2CML", "" }, + { 10, "GPS_L5I", "" }, + { 11, "GPS_L5Q", "" }, + { 12, "GPS_L5IQ", "" }, + { 13, "GPS_L1CD", "" }, + { 14, "GPS_L1CP", "" }, + { 15, "GPS_L1CDP", "" }, + { 32, "GLONASS_G1CA", "" }, + { 33, "GLONASS_G1P", "" }, + { 34, "GLONASS_G2C", "" }, + { 35, "GLONASS_G2P", "" }, + { 64, "GALILEO_E1C", "" }, + { 65, "GALILEO_E1A", "" }, + { 66, "GALILEO_E1B", "" }, + { 67, "GALILEO_E1BC", "" }, + { 68, "GALILEO_E1ABC", "" }, + { 69, "GALILEO_E6C", "" }, + { 70, "GALILEO_E6A", "" }, + { 71, "GALILEO_E6B", "" }, + { 72, "GALILEO_E6BC", "" }, + { 73, "GALILEO_E6ABC", "" }, + { 74, "GALILEO_E5BI", "" }, + { 75, "GALILEO_E5BQ", "" }, + { 76, "GALILEO_E5BIQ", "" }, + { 77, "GALILEO_E5ABI", "" }, + { 78, "GALILEO_E5ABQ", "" }, + { 79, "GALILEO_E5ABIQ", "" }, + { 80, "GALILEO_E5AI", "" }, + { 81, "GALILEO_E5AQ", "" }, + { 82, "GALILEO_E5AIQ", "" }, + { 96, "SBAS_L1CA", "" }, + { 97, "SBAS_L5I", "" }, + { 98, "SBAS_L5Q", "" }, + { 99, "SBAS_L5IQ", "" }, + { 128, "QZSS_L1CA", "" }, + { 129, "QZSS_LEXS", "" }, + { 130, "QZSS_LEXL", "" }, + { 131, "QZSS_LEXSL", "" }, + { 132, "QZSS_L2CM", "" }, + { 133, "QZSS_L2CL", "" }, + { 134, "QZSS_L2CML", "" }, + { 135, "QZSS_L5I", "" }, + { 136, "QZSS_L5Q", "" }, + { 137, "QZSS_L5IQ", "" }, + { 138, "QZSS_L1CD", "" }, + { 139, "QZSS_L1CP", "" }, + { 140, "QZSS_L1CDP", "" }, + { 160, "BEIDOU_B1I", "" }, + { 161, "BEIDOU_B1Q", "" }, + { 162, "BEIDOU_B1IQ", "" }, + { 163, "BEIDOU_B3I", "" }, + { 164, "BEIDOU_B3Q", "" }, + { 165, "BEIDOU_B3IQ", "" }, + { 166, "BEIDOU_B2I", "" }, + { 167, "BEIDOU_B2Q", "" }, + { 168, "BEIDOU_B2IQ", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "GnssSignalId", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::Raw::GnssSignalQuality; + + static constexpr inline EnumInfo::Entry entries[] = { + { 0, "NONE", "" }, + { 1, "SEARCHING", "" }, + { 2, "ACQUIRED", "" }, + { 3, "UNUSABLE", "" }, + { 4, "TIME_LOCKED", "" }, + { 5, "FULLY_LOCKED", "" }, + }; + + static constexpr inline EnumInfo value = { + /* .name = */ "GnssSignalQuality", + /* .docs = */ "", + /* .type = */ Type::U8, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::Raw::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tow", "" }, + { 2, "week_number", "" }, + { 4, "receiver_id", "" }, + { 8, "tracking_channel", "" }, + { 16, "gnss_id", "" }, + { 32, "satellite_id", "" }, + { 64, "signal_id", "" }, + { 128, "signal_strength", "" }, + { 256, "quality", "" }, + { 512, "pseudorange", "" }, + { 1024, "carrier_phase", "" }, + { 2048, "doppler", "" }, + { 4096, "range_uncertainty", "" }, + { 8192, "carrier_phase_uncertainty", "" }, + { 16384, "doppler_uncertainty", "" }, + { 32768, "lock_time", "" }, + { 65535, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::Raw; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "index", + /* .docs = */ "Index of this field in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "count", + /* .docs = */ "Total number of fields in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "receiver_id", + /* .docs = */ "When the measurement comes from RTCM, this will be the reference station ID; otherwise, it's the receiver number (1,2,...)", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "tracking_channel", + /* .docs = */ "Channel the receiver is using to track this satellite.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "gnss_id", + /* .docs = */ "", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "satellite_id", + /* .docs = */ "GNSS satellite id within the constellation.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "signal_id", + /* .docs = */ "Signal identifier for the satellite.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "signal_strength", + /* .docs = */ "Carrier to noise ratio [dBHz].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "quality", + /* .docs = */ "Indicator of signal quality.", + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pseudorange", + /* .docs = */ "Pseudo-range measurement [meters].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "carrier_phase", + /* .docs = */ "Carrier phase measurement [Carrier periods].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "doppler", + /* .docs = */ "Measured doppler shift [Hz].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "range_uncert", + /* .docs = */ "Uncertainty of the pseudo-range measurement [m].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "phase_uncert", + /* .docs = */ "Uncertainty of the phase measurement [Carrier periods].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "doppler_uncert", + /* .docs = */ "Uncertainty of the measured doppler shift [Hz].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "lock_time", + /* .docs = */ "DOC\nMinimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::Raw", + /* .title = */ "None", + /* .docs = */ "GNSS Raw observation.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GpsEphemeris::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "ephemeris", "" }, + { 2, "modern_data", "" }, + { 3, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GpsEphemeris; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "index", + /* .docs = */ "Index of this field in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "count", + /* .docs = */ "Total number of fields in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "satellite_id", + /* .docs = */ "GNSS satellite id within the constellation.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "health", + /* .docs = */ "Satellite and signal health", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "iodc", + /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "iode", + /* .docs = */ "Issue of Data Ephemeris.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "t_oc", + /* .docs = */ "Reference time for clock data.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "af0", + /* .docs = */ "Clock bias in [s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "af1", + /* .docs = */ "Clock drift in [s/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "af2", + /* .docs = */ "Clock drift rate in [s/s^2].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "t_gd", + /* .docs = */ "T Group Delay [s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ISC_L1CA", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ISC_L2C", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "t_oe", + /* .docs = */ "Reference time for ephemeris in [s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "a", + /* .docs = */ "Semi-major axis [m].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "a_dot", + /* .docs = */ "Semi-major axis rate [m/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "mean_anomaly", + /* .docs = */ "[rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "delta_mean_motion", + /* .docs = */ "[rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "delta_mean_motion_dot", + /* .docs = */ "[rad/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "eccentricity", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "argument_of_perigee", + /* .docs = */ "[rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "omega", + /* .docs = */ "Longitude of Ascending Node [rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "omega_dot", + /* .docs = */ "Rate of Right Ascension [rad/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "inclination", + /* .docs = */ "Inclination angle [rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "inclination_dot", + /* .docs = */ "Inclination angle rate of change [rad/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_ic", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_is", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_uc", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_us", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_rc", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_rs", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::GpsEphemeris", + /* .title = */ "None", + /* .docs = */ "GPS Ephemeris Data", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GalileoEphemeris::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "ephemeris", "" }, + { 2, "modern_data", "" }, + { 3, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GalileoEphemeris; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "index", + /* .docs = */ "Index of this field in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "count", + /* .docs = */ "Total number of fields in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "satellite_id", + /* .docs = */ "GNSS satellite id within the constellation.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "health", + /* .docs = */ "Satellite and signal health", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "iodc", + /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "iode", + /* .docs = */ "Issue of Data Ephemeris.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "t_oc", + /* .docs = */ "Reference time for clock data.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "af0", + /* .docs = */ "Clock bias in [s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "af1", + /* .docs = */ "Clock drift in [s/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "af2", + /* .docs = */ "Clock drift rate in [s/s^2].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "t_gd", + /* .docs = */ "T Group Delay [s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ISC_L1CA", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "ISC_L2C", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "t_oe", + /* .docs = */ "Reference time for ephemeris in [s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "a", + /* .docs = */ "Semi-major axis [m].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "a_dot", + /* .docs = */ "Semi-major axis rate [m/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "mean_anomaly", + /* .docs = */ "[rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "delta_mean_motion", + /* .docs = */ "[rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "delta_mean_motion_dot", + /* .docs = */ "[rad/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "eccentricity", + /* .docs = */ "", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "argument_of_perigee", + /* .docs = */ "[rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "omega", + /* .docs = */ "Longitude of Ascending Node [rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "omega_dot", + /* .docs = */ "Rate of Right Ascension [rad/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "inclination", + /* .docs = */ "Inclination angle [rad].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "inclination_dot", + /* .docs = */ "Inclination angle rate of change [rad/s].", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_ic", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_is", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_uc", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_us", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_rc", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "c_rs", + /* .docs = */ "Harmonic Correction Term.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::GalileoEphemeris", + /* .title = */ "None", + /* .docs = */ "Galileo Ephemeris Data", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GloEphemeris::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "ephemeris", "" }, + { 1, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GloEphemeris; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "index", + /* .docs = */ "Index of this field in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "count", + /* .docs = */ "Total number of fields in this epoch.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "satellite_id", + /* .docs = */ "GNSS satellite id within the constellation.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "freq_number", + /* .docs = */ "GLONASS frequency number (-7 to 24)", + /* .type = */ {Type::S8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "tk", + /* .docs = */ "Frame start time within current day [seconds]", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "tb", + /* .docs = */ "Ephemeris reference time [seconds]", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "sat_type", + /* .docs = */ "Type of satellite (M) GLONASS = 0, GLONASS-M = 1", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "gamma", + /* .docs = */ "Relative deviation of carrier frequency from nominal [dimensionless]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "tau_n", + /* .docs = */ "Time correction relative to GLONASS Time [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "x", + /* .docs = */ "Satellite PE-90 position [m]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "v", + /* .docs = */ "Satellite PE-90 velocity [m/s]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "a", + /* .docs = */ "Satellite PE-90 acceleration due to perturbations [m/s^2]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "health", + /* .docs = */ "Satellite Health (Bn), Non-zero indicates satellite malfunction", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "P", + /* .docs = */ "Satellite operation mode (See GLONASS ICD)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "NT", + /* .docs = */ "Day number within a 4 year period.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "delta_tau_n", + /* .docs = */ "Time difference between L1 and L2[m/s]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "Ft", + /* .docs = */ "User Range Accuracy (See GLONASS ICD)", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "En", + /* .docs = */ "Age of current information [days]", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "P1", + /* .docs = */ "Time interval between adjacent values of tb [minutes]", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "P2", + /* .docs = */ "Oddness '1' or evenness '0' of the value of tb.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "P3", + /* .docs = */ "Number of satellites in almanac for this frame", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "P4", + /* .docs = */ "Flag indicating ephemeris parameters are present", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::GloEphemeris", + /* .title = */ "Glonass Ephemeris", + /* .docs = */ "Glonass Ephemeris Data", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GpsIonoCorr::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tow", "" }, + { 2, "week_number", "" }, + { 4, "alpha", "" }, + { 8, "beta", "" }, + { 15, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GpsIonoCorr; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "alpha", + /* .docs = */ "Ionospheric Correction Terms.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 4, + /* .condition = */ {}, + }, + { + /* .name = */ "beta", + /* .docs = */ "Ionospheric Correction Terms.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 4, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::GpsIonoCorr", + /* .title = */ "GPS Ionospheric Correction", + /* .docs = */ "Ionospheric Correction Terms for GNSS", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GalileoIonoCorr::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tow", "" }, + { 2, "week_number", "" }, + { 4, "alpha", "" }, + { 8, "disturbance_flags", "" }, + { 15, "flags", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_gnss::GalileoIonoCorr; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_of_week", + /* .docs = */ "GPS Time of week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "alpha", + /* .docs = */ "Coefficients for the model.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "disturbance_flags", + /* .docs = */ "Region disturbance flags (bits 1-5).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_gnss::GalileoIonoCorr", + /* .title = */ "Galileo Ionospheric Correction", + /* .docs = */ "Ionospheric Correction Terms for Galileo", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + + +static constexpr inline std::initializer_list ALL_DATA_GNSS = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, +}; + + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index 855dfc207..cf7d8052c 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -1,74 +1,839 @@ #pragma once -#include #include "common.hpp" +#include + #include -#include namespace mip::metadata { + +template<> +struct MetadataFor +{ + using type = data_sensor::RawAccel; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "raw_accel", + /* .docs = */ "Native sensor counts", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::RawAccel", + /* .title = */ "None", + /* .docs = */ "Three element vector representing the sensed acceleration.\nThis quantity is temperature compensated and expressed in the sensor body frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::RawGyro; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "raw_gyro", + /* .docs = */ "Native sensor counts", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::RawGyro", + /* .title = */ "None", + /* .docs = */ "Three element vector representing the sensed angular rate.\nThis quantity is temperature compensated and expressed in the sensor body frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::RawMag; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "raw_mag", + /* .docs = */ "Native sensor counts", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::RawMag", + /* .title = */ "None", + /* .docs = */ "Three element vector representing the sensed magnetic field.\nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::RawPressure; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "raw_pressure", + /* .docs = */ "Native sensor counts", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::RawPressure", + /* .title = */ "None", + /* .docs = */ "Scalar value representing the sensed ambient pressure.\nThis quantity is temperature compensated.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { - using Field = data_sensor::ScaledAccel; + using type = data_sensor::ScaledAccel; static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "scaled_accel", - /* .docs = */ "Scaled acceleration in [g]", + /* .docs = */ "(x, y, z)[g]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - ///* .byte_offset = */ 0, - ///* .functions = */ {false, false, false, false, false}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, }, }; static constexpr inline FieldInfo value = { - /* .name = */ "ScaledAccel", - /* .title = */ "Scaled Accel", - /* .docs = */ "Acceleration", + /* .name = */ "data_sensor::ScaledAccel", + /* .title = */ "None", + /* .docs = */ "3-element vector representing the sensed acceleration.\nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, - /* .descriptor = */ Field::DESCRIPTOR, - ///* .functions = */ {false,false,false,false,false}, - ///* .proprietary = */ false, - ///* .response = */ nullptr, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; template<> struct MetadataFor { - using Field = data_sensor::ScaledGyro; + using type = data_sensor::ScaledGyro; static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "scaled_gyro", - /* .docs = */ "Scaled angular rate in [rad/s]", + /* .docs = */ "(x, y, z) [radians/second]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::ScaledGyro", + /* .title = */ "None", + /* .docs = */ "3-element vector representing the sensed angular rate.\nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::ScaledMag; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scaled_mag", + /* .docs = */ "(x, y, z) [Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::ScaledMag", + /* .title = */ "None", + /* .docs = */ "3-element vector representing the sensed magnetic field.\nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::ScaledPressure; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "scaled_pressure", + /* .docs = */ "[mBar]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::ScaledPressure", + /* .title = */ "None", + /* .docs = */ "Scalar value representing the sensed ambient pressure.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::DeltaTheta; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "delta_theta", + /* .docs = */ "(x, y, z) [radians]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, - ///* .byte_offset = */ 0, - ///* .functions = */ {false, false, false, false, false}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, }, }; static constexpr inline FieldInfo value = { - /* .name = */ "ScaledGyro", - /* .title = */ "Scaled Gyro", - /* .docs = */ "Angular rate of rotation.", + /* .name = */ "data_sensor::DeltaTheta", + /* .title = */ "None", + /* .docs = */ "3-element vector representing the time integral of angular rate.\nThis quantity is the integral of sensed angular rate over the period set by the IMU message format. It is expressed in the vehicle frame.", /* .parameters = */ parameters, - /* .descriptor = */ Field::DESCRIPTOR, - ///* .functions = */ {false,false,false,false,false}, - ///* .proprietary = */ false, - ///* .response = */ nullptr, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, }; }; +template<> +struct MetadataFor +{ + using type = data_sensor::DeltaVelocity; -static constexpr inline std::initializer_list ALL_SENSOR_DATA = { + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "delta_velocity", + /* .docs = */ "(x, y, z) [g*sec]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::DeltaVelocity", + /* .title = */ "None", + /* .docs = */ "3-element vector representing the time integral of acceleration.\nThis quantity is the integral of sensed acceleration over the period set by the IMU message format. It is expressed in the vehicle frame.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::CompOrientationMatrix; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "m", + /* .docs = */ "Matrix elements in row-major order.", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::CompOrientationMatrix", + /* .title = */ "Complementary Filter Orientation Matrix", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::CompQuaternion; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "q", + /* .docs = */ "Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::CompQuaternion", + /* .title = */ "Complementary Filter Quaternion", + /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.\nThis quaternion satisfies the following relationship:\n\nEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
\nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::CompEulerAngles; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "roll", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "pitch", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "yaw", + /* .docs = */ "[radians]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::CompEulerAngles", + /* .title = */ "Complementary Filter Euler Angles", + /* .docs = */ "Euler angles describing the orientation of the device with respect to the NED local-level frame.\nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::CompOrientationUpdateMatrix; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "m", + /* .docs = */ "", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::CompOrientationUpdateMatrix", + /* .title = */ "Complementary Filter Orientation Update Matrix", + /* .docs = */ "DEPRECATED!", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::OrientationRawTemp; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "raw_temp", + /* .docs = */ "", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 4, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::OrientationRawTemp", + /* .title = */ "None", + /* .docs = */ "DEPRECATED!", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::InternalTimestamp; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "counts", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::InternalTimestamp", + /* .title = */ "None", + /* .docs = */ "DEPRECATED!", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::PpsTimestamp; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "seconds", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "useconds", + /* .docs = */ "", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::PpsTimestamp", + /* .title = */ "PPS Timestamp", + /* .docs = */ "DEPRECATED!", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::GpsTimestamp::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "pps_valid", "True when the PPS signal is present." }, + { 2, "time_refresh", "Toggles each time the time is updated via internal GPS or the GPS Time Update command (0x01, 0x72)." }, + { 4, "time_initialized", "True if the time has ever been set." }, + { 8, "tow_valid", "True if the time of week is valid." }, + { 16, "week_number_valid", "True if the week number is valid." }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::GpsTimestamp; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "tow", + /* .docs = */ "GPS Time of Week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week Number since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::GpsTimestamp", + /* .title = */ "None", + /* .docs = */ "GPS timestamp of the SENSOR data\n\nShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.\nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.\nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.\n\nNote: this data field may be deprecated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::TemperatureAbs; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "min_temp", + /* .docs = */ "[degC]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "max_temp", + /* .docs = */ "[degC]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "mean_temp", + /* .docs = */ "[degC]", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::TemperatureAbs", + /* .title = */ "Temperature Statistics", + /* .docs = */ "SENSOR reported temperature statistics\n\nTemperature may originate from the MEMS sensors, or be calculated in combination with board temperature sensors.\nAll quantities are calculated with respect to the last power on or reset, whichever is later.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::UpVector; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "up", + /* .docs = */ "[Gs]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::UpVector", + /* .title = */ "None", + /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimated vertical direction.\nThis quantity is expressed in the vehicle frame.\n\nThis quantity is sensitive to non-gravitational accelerations, which may cause notable deviations from the true vertical direction.\n\nFor legacy reasons, this vector is the inverse of the gravity vector.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::NorthVector; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "north", + /* .docs = */ "[Gauss]", + /* .type = */ {Type::STRUCT, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::NorthVector", + /* .title = */ "None", + /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimate of magnetic north.\nThis quantity is expressed in the vehicle frame.\n\nThis quantity is sensitive to local magnetic field perturbations, which may cause notable deviations from true magnetic north.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::OverrangeStatus::Status; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "accel_x", "" }, + { 2, "accel_y", "" }, + { 4, "accel_z", "" }, + { 16, "gyro_x", "" }, + { 32, "gyro_y", "" }, + { 64, "gyro_z", "" }, + { 256, "mag_x", "" }, + { 512, "mag_y", "" }, + { 1024, "mag_z", "" }, + { 4096, "press", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "Status", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::OverrangeStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "status", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::OverrangeStatus", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_sensor::OdometerData; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "speed", + /* .docs = */ "Average speed over the time interval [m/s]. Can be negative for quadrature encoders.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "uncertainty", + /* .docs = */ "Uncertainty of velocity [m/s].", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "If odometer is configured, bit 0 will be set to 1.", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_sensor::OdometerData", + /* .title = */ "None", + /* .docs = */ "", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + + +static constexpr inline std::initializer_list ALL_DATA_SENSOR = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, }; -} // namespace mip + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/data_shared.hpp b/src/cpp/mip/metadata/definitions/data_shared.hpp new file mode 100644 index 000000000..24409e893 --- /dev/null +++ b/src/cpp/mip/metadata/definitions/data_shared.hpp @@ -0,0 +1,381 @@ +#pragma once + +#include "common.hpp" + +#include + +#include + +namespace mip::metadata +{ + + +template<> +struct MetadataFor +{ + using type = data_shared::EventSource; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "trigger_id", + /* .docs = */ "Trigger ID number. If 0, this message was emitted due to being\nscheduled in the 3DM Message Format Command (0x0C,0x0F).", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_shared::EventSource", + /* .title = */ "None", + /* .docs = */ "Identifies which event trigger caused this packet to be emitted.\n\nGenerally this is used to determine whether a packet was emitted\ndue to scheduled streaming or due to an event.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_shared::Ticks; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "ticks", + /* .docs = */ "Ticks since powerup.", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_shared::Ticks", + /* .title = */ "None", + /* .docs = */ "Time since powerup in multiples of the base rate.\n\nThe counter will wrap around to 0 after approximately 50 days.\nOne tick is equivalent to one base period (reciprocal of the base rate).", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_shared::DeltaTicks; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "ticks", + /* .docs = */ "Ticks since last output.", + /* .type = */ {Type::U32, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_shared::DeltaTicks", + /* .title = */ "None", + /* .docs = */ "Ticks since the last output of this field.\n\nThis field can be used to track the amount of time passed between\nevent occurrences.\nOne tick is equivalent to one base period (reciprocal of the base rate).", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_shared::GpsTimestamp::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "tow", "Whole number seconds TOW has been set" }, + { 2, "week_number", "Week number has been set" }, + { 3, "time_valid", "Both TOW and Week Number have been set" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_shared::GpsTimestamp; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "tow", + /* .docs = */ "GPS Time of Week [seconds]", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "week_number", + /* .docs = */ "GPS Week Number since 1980 [weeks]", + /* .type = */ {Type::U16, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_shared::GpsTimestamp", + /* .title = */ "None", + /* .docs = */ "Outputs the current GPS system time in time-of-week and week number format.\n\nFor events, this is the time of the event trigger.\nIn order to be valid, a PPS signal needs to be present, and both a valid GPS time-of-week and week number command (0x0C, 0x72) need to be received after PPS sync has been achieved.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_shared::DeltaTime; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "seconds", + /* .docs = */ "Seconds since last output.", + /* .type = */ {Type::DOUBLE, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_shared::DeltaTime", + /* .title = */ "None", + /* .docs = */ "Time in the synchronized clock domain since the last output of this field within the same descriptor set and event instance.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.\n\nThis field contains the same value as the delta external time field, 0xD8,\nbut is expressed in seconds. Transmission of either of these fields\nrestarts a shared counter, so only one should be streamed at a time to\navoid confusion. The counter is not shared across descriptors sets or\nbetween event instances.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_shared::ReferenceTimestamp; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "nanoseconds", + /* .docs = */ "Nanoseconds since initialization.", + /* .type = */ {Type::U64, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_shared::ReferenceTimestamp", + /* .title = */ "None", + /* .docs = */ "Internal reference timestamp.\n\nThis timestamp represents the time at which the corresponding\ndata was sampled, according to the internal reference clock.\n\nThis is a monotonic clock which never jumps. The value is always valid.\n\nFor events, this is the time of the event trigger.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_shared::ReferenceTimeDelta; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "dt_nanos", + /* .docs = */ "Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source.", + /* .type = */ {Type::U64, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_shared::ReferenceTimeDelta", + /* .title = */ "None", + /* .docs = */ "Delta time since the last packet.\n\nDifference between the time as reported by the shared reference time field, 0xD5,\nand the previous output of this delta quantity within the same descriptor set and event instance.\n\nThe delta is based on the reference time which never jumps. The value\nis always valid.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_shared::ExternalTimestamp::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "nanoseconds", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_shared::ExternalTimestamp; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "nanoseconds", + /* .docs = */ "", + /* .type = */ {Type::U64, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_shared::ExternalTimestamp", + /* .title = */ "None", + /* .docs = */ "External timestamp in nanoseconds.\n\nThis timestamp represents the time at which the corresponding\ndata was sampled in the external clock domain.\nEquivalent to the GPS Timestamp but in nanoseconds.\n\nFor events, this is the time of the event trigger.\n\nTo be valid, external clock sync must be achieved using the PPS input.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_shared::ExternalTimeDelta::ValidFlags; + + static constexpr inline BitfieldInfo::Entry entries[] = { + { 1, "dt_nanos", "" }, + }; + + static constexpr inline BitfieldInfo value = { + /* .name = */ "ValidFlags", + /* .docs = */ "", + /* .type = */ Type::U16, + /* .entries = */ entries, + }; + +}; + +template<> +struct MetadataFor +{ + using type = data_shared::ExternalTimeDelta; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "dt_nanos", + /* .docs = */ "Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source.", + /* .type = */ {Type::U64, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "valid_flags", + /* .docs = */ "", + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_shared::ExternalTimeDelta", + /* .title = */ "None", + /* .docs = */ "Delta time since the last packet containing delta external (0xFF,0xD4) or delta gps time (0xFF,0xD8).\n\nDifference between the time as reported by the shared external time field, 0xD7,\nand the previous output of this delta quantity within the same descriptor set and event instance.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.\n\nThis field contains the same value as the delta gps time field, 0xD4,\nbut is expressed in nanoseconds. Transmission of either of these fields\nrestarts a shared counter, so only one should be streamed at a time to\navoid confusion. The counter is not shared across descriptors sets or\nbetween event instances.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + + +static constexpr inline std::initializer_list ALL_DATA_SHARED = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, +}; + + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/definitions/data_system.hpp b/src/cpp/mip/metadata/definitions/data_system.hpp new file mode 100644 index 000000000..de699bd71 --- /dev/null +++ b/src/cpp/mip/metadata/definitions/data_system.hpp @@ -0,0 +1,157 @@ +#pragma once + +#include "common.hpp" + +#include + +#include + +namespace mip::metadata +{ + + +template<> +struct MetadataFor +{ + using type = data_system::BuiltInTest; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "result", + /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 16, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_system::BuiltInTest", + /* .title = */ "None", + /* .docs = */ "Contains the continuous built-in-test (BIT) results.\n\nDue to the large size of this field, it is recommended to stream it at\na low rate or poll it on demand.\n\nThese bits are 'sticky' until the next output message. If a fault occurs\nin between scheduled messages or while the device is idle, the next\npacket with this field will have the corresponding flags set. The flag\nis then cleared unless the fault persists.\n\nUnlike the commanded BIT, some bits may be 1 in certain\nnon-fault situations, so simply checking if the result is all 0s is\nnot very useful. For example, on devices with a built-in GNSS receiver,\na 'solution fault' bit may be set before the receiver has obtained\na position fix. Consult the device manual to determine which bits are\nof interest for your application.\n\nAll unspecified bits are reserved for future use and must be ignored.\n", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_system::TimeSyncStatus; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "time_sync", + /* .docs = */ "True if sync with the PPS signal is currently valid. False if PPS\nfeature is disabled or a PPS signal is not detected.", + /* .type = */ {Type::BOOL, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "last_pps_rcvd", + /* .docs = */ "Elapsed time in seconds since last PPS was received, with a maximum\nvalue of 255.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_system::TimeSyncStatus", + /* .title = */ "None", + /* .docs = */ "Indicates whether a sync has been achieved using the PPS signal.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_system::GpioState; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "states", + /* .docs = */ "Bitfield containing the states for each GPIO pin.
\nBit 0 (0x01): pin 1
\nBit 1 (0x02): pin 2
\nBit 2 (0x04): pin 3
\nBit 3 (0x08): pin 4
\nBits for pins that don't exist will read as 0.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_system::GpioState", + /* .title = */ "None", + /* .docs = */ "Indicates the state of all of the user GPIO pins.\n\nThis message can be used to correlate external signals\nwith the device time or other data quantities. It should\ngenerally be used with slow GPIO signals as brief pulses\nshorter than the scheduled data rate will be missed.\n\nTo synchronize with faster signals and pulses, or for more accurate timestamping,\nutilize the event system and set the GPIO feature to TIMESTAMP in the 3DM GPIO\nConfiguration command (0x0C,0x41).\n\nThese GPIO states are sampled within one base period\nof the system data descriptor set.\n\nTo obtain valid readings, the desired pin(s) must be configured to the GPIO feature\n(either input or output behavior) using the 3DM GPIO Configuration command\n(0x0C,0x41). Other gpio features may work on some devices but this is not guaranteed.\nConsult the factory before producing a design relying on reading pins configured\nto other feature types.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + +template<> +struct MetadataFor +{ + using type = data_system::GpioAnalogValue; + + static constexpr inline ParameterInfo parameters[] = { + { + /* .name = */ "gpio_id", + /* .docs = */ "GPIO pin number starting with 1.", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + { + /* .name = */ "value", + /* .docs = */ "Value of the GPIO line in scaled volts.", + /* .type = */ {Type::FLOAT, nullptr}, + /* .accessor = */ utils::access, + /* .functions = */ {true, false, false, false, false, true}, + /* .count = */ 1, + /* .condition = */ {}, + }, + }; + + static constexpr inline FieldInfo value = { + /* .name = */ "data_system::GpioAnalogValue", + /* .title = */ "None", + /* .docs = */ "Indicates the analog value of the given user GPIO.\nThe pin must be configured for analog input.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + + +static constexpr inline std::initializer_list ALL_DATA_SYSTEM = { + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, +}; + + +} // namespace mip::metadata + diff --git a/src/cpp/mip/metadata/mip_all_definitions.hpp b/src/cpp/mip/metadata/mip_all_definitions.hpp index f26d80ab3..3979191b1 100644 --- a/src/cpp/mip/metadata/mip_all_definitions.hpp +++ b/src/cpp/mip/metadata/mip_all_definitions.hpp @@ -1,27 +1,55 @@ -#include #include +#include +#include +#include +#include +#include +#include + +#include +#include #include +#include +#include namespace mip::metadata { static constexpr inline std::initializer_list< const std::initializer_list* > ALL_COMMANDS = { + &ALL_COMMANDS_3DM, + &ALL_COMMANDS_AIDING, &ALL_COMMANDS_BASE, - // &ALL_3DM_COMMANDS, + &ALL_COMMANDS_FILTER, + &ALL_COMMANDS_GNSS, + &ALL_COMMANDS_RTK, + &ALL_COMMANDS_SYSTEM, }; static constexpr inline std::initializer_list< const std::initializer_list* > ALL_DATA = { - &ALL_SENSOR_DATA, + &ALL_DATA_FILTER, + &ALL_DATA_GNSS, + &ALL_DATA_SENSOR, + &ALL_DATA_SHARED, + &ALL_DATA_SYSTEM, }; static constexpr inline std::initializer_list< const std::initializer_list< const FieldInfo* >* > ALL_FIELDS = { // Commands + &ALL_COMMANDS_3DM, + &ALL_COMMANDS_AIDING, &ALL_COMMANDS_BASE, - // &ALL_3DM_COMMANDS, + &ALL_COMMANDS_FILTER, + &ALL_COMMANDS_GNSS, + &ALL_COMMANDS_RTK, + &ALL_COMMANDS_SYSTEM, // Data - &ALL_SENSOR_DATA, + &ALL_DATA_FILTER, + &ALL_DATA_GNSS, + &ALL_DATA_SENSOR, + &ALL_DATA_SHARED, + &ALL_DATA_SYSTEM, }; } // namespace mip diff --git a/src/cpp/mip/metadata/mip_definitions.cpp b/src/cpp/mip/metadata/mip_definitions.cpp index ba57be9db..7a2a83cbb 100644 --- a/src/cpp/mip/metadata/mip_definitions.cpp +++ b/src/cpp/mip/metadata/mip_definitions.cpp @@ -1,6 +1,9 @@ #include "mip_definitions.hpp" +#include + + namespace mip::metadata { @@ -37,10 +40,19 @@ const FieldInfo* Definitions::findField(mip::CompositeDescriptor descriptor) con //auto it = findFieldIter(descriptor); auto it = mFields.find(descriptor); - if(it == mFields.end()) - return nullptr; + if(it != mFields.end()) + return *it; + + // Check for shared data fields. + if(isDataDescriptorSet(descriptor.descriptorSet) && isSharedDataFieldDescriptor(descriptor.fieldDescriptor)) + { + it = mFields.find(CompositeDescriptor{data_shared::DESCRIPTOR_SET, descriptor.fieldDescriptor}); + + if(it != mFields.end()) + return *it; + } - return *it; + return nullptr; } } // namespace mip::metadata From 09a94ac3c433f9180ac9867ff4876b14f9f30035 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 16 Jul 2024 14:11:54 -0400 Subject: [PATCH 048/147] Updates to serialization code (rudimentary endianness support) [WIP]. --- examples/CSV/stringify.cpp | 22 +- src/c/microstrain/common/serialization.c | 2 +- src/c/mip/definitions/commands_3dm.c | 2507 +++-------- src/c/mip/definitions/commands_3dm.h | 1138 +++-- src/c/mip/definitions/commands_aiding.c | 514 +-- src/c/mip/definitions/commands_aiding.h | 233 +- src/c/mip/definitions/commands_base.c | 150 +- src/c/mip/definitions/commands_base.h | 113 +- src/c/mip/definitions/commands_filter.c | 2630 ++++-------- src/c/mip/definitions/commands_filter.h | 971 +++-- src/c/mip/definitions/commands_gnss.c | 163 +- src/c/mip/definitions/commands_gnss.h | 48 +- src/c/mip/definitions/commands_rtk.c | 210 +- src/c/mip/definitions/commands_rtk.h | 173 +- src/c/mip/definitions/commands_system.c | 38 +- src/c/mip/definitions/commands_system.h | 18 +- src/c/mip/definitions/data_filter.c | 768 ++-- src/c/mip/definitions/data_filter.h | 469 +- src/c/mip/definitions/data_gnss.c | 1257 ++---- src/c/mip/definitions/data_gnss.h | 998 +++-- src/c/mip/definitions/data_sensor.c | 186 +- src/c/mip/definitions/data_sensor.h | 128 +- src/c/mip/definitions/data_shared.c | 63 +- src/c/mip/definitions/data_shared.h | 86 +- src/c/mip/definitions/data_system.c | 24 +- src/c/mip/definitions/data_system.h | 24 +- src/c/mip/mip_interface.h | 6 +- src/cpp/microstrain/common/platform.hpp | 6 + src/cpp/microstrain/common/serialization.hpp | 379 +- .../common/serialization/readwrite.hpp | 181 + .../common/serialization/serializer.hpp | 462 ++ src/cpp/mip/definitions/commands_3dm.cpp | 3551 ++++++--------- src/cpp/mip/definitions/commands_3dm.hpp | 2034 +++++---- src/cpp/mip/definitions/commands_aiding.cpp | 665 ++- src/cpp/mip/definitions/commands_aiding.hpp | 314 +- src/cpp/mip/definitions/commands_base.cpp | 326 +- src/cpp/mip/definitions/commands_base.hpp | 432 +- src/cpp/mip/definitions/commands_filter.cpp | 3812 +++++++---------- src/cpp/mip/definitions/commands_filter.hpp | 2151 +++++----- src/cpp/mip/definitions/commands_gnss.cpp | 274 +- src/cpp/mip/definitions/commands_gnss.hpp | 156 +- src/cpp/mip/definitions/commands_rtk.cpp | 414 +- src/cpp/mip/definitions/commands_rtk.hpp | 491 ++- src/cpp/mip/definitions/commands_system.cpp | 68 +- src/cpp/mip/definitions/commands_system.hpp | 52 +- src/cpp/mip/definitions/common.hpp | 22 +- src/cpp/mip/definitions/data_filter.cpp | 937 ++-- src/cpp/mip/definitions/data_filter.hpp | 1038 +++-- src/cpp/mip/definitions/data_gnss.cpp | 1121 +++-- src/cpp/mip/definitions/data_gnss.hpp | 872 ++-- src/cpp/mip/definitions/data_sensor.cpp | 259 +- src/cpp/mip/definitions/data_sensor.hpp | 412 +- src/cpp/mip/definitions/data_shared.cpp | 101 +- src/cpp/mip/definitions/data_shared.hpp | 171 +- src/cpp/mip/definitions/data_system.cpp | 53 +- src/cpp/mip/definitions/data_system.hpp | 72 +- src/cpp/mip/mip_descriptors.hpp | 7 +- src/cpp/mip/mip_packet.hpp | 6 +- src/cpp/mip/mip_serialization.hpp | 65 +- 59 files changed, 14592 insertions(+), 19251 deletions(-) create mode 100644 src/cpp/microstrain/common/serialization/readwrite.hpp create mode 100644 src/cpp/microstrain/common/serialization/serializer.hpp diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp index ccd904a98..cc46a008f 100644 --- a/examples/CSV/stringify.cpp +++ b/examples/CSV/stringify.cpp @@ -26,7 +26,7 @@ struct Formatter { static constexpr size_t MAX_PARAMETERS = 20; - microstrain::Serializer serializer; + mip::Serializer serializer; std::ostream& ss; std::array offsets; @@ -77,18 +77,18 @@ std::ostream& Formatter::formatBasicType() ///@returns A uint64_t containing the value. All smaller integers are converted to this type. ///@returns std::nullopt (no value) if the offset/size is beyond the end of the buffer. /// -static std::optional readIntegralValue(Type type, microstrain::Serializer& serializer) +static std::optional readIntegralValue(Type type, mip::Serializer& serializer) { switch(type) { - case Type::U8: return microstrain::extract(serializer); - case Type::S8: return microstrain::extract< int8_t >(serializer); - case Type::U16: return microstrain::extract(serializer); - case Type::S16: return microstrain::extract< int32_t>(serializer); - case Type::U32: return microstrain::extract(serializer); - case Type::S32: return microstrain::extract< int64_t>(serializer); - case Type::U64: return microstrain::extract(serializer); - case Type::S64: return microstrain::extract< int64_t>(serializer); + case Type::U8: return microstrain::extract(serializer); + case Type::S8: return microstrain::extract(serializer); + case Type::U16: return microstrain::extract(serializer); + case Type::S16: return microstrain::extract(serializer); + case Type::U32: return microstrain::extract(serializer); + case Type::S32: return microstrain::extract(serializer); + case Type::U64: return microstrain::extract(serializer); + case Type::S64: return microstrain::extract(serializer); default: return std::nullopt; } } @@ -376,7 +376,7 @@ std::ostream& formatField(std::ostream& ss, const mip::FieldView& field) ss << info->name; Formatter formatter = { - microstrain::Serializer(field.payload(), field.payloadLength()), + mip::Serializer(field.payload(), field.payloadLength()), ss, }; diff --git a/src/c/microstrain/common/serialization.c b/src/c/microstrain/common/serialization.c index dde2ed5a2..d55a5b3e7 100644 --- a/src/c/microstrain/common/serialization.c +++ b/src/c/microstrain/common/serialization.c @@ -183,7 +183,7 @@ EXTRACT_MACRO(double, double ) /// The counter value read from the buffer. ///@param max_count /// The maximum value of the counter. If the count exceeds this, it is -/// set to 0 and the serializer is put into an error state. +/// set to 0 and the serializer is insert into an error state. /// void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* count_out, uint8_t max_count) { diff --git a/src/c/mip/definitions/commands_3dm.c b/src/c/mip/definitions/commands_3dm.c index 0035e5175..8704e3243 100644 --- a/src/c/mip/definitions/commands_3dm.c +++ b/src/c/mip/definitions/commands_3dm.c @@ -13,13 +13,10 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions +// Mip Fields //////////////////////////////////////////////////////////////////////////////// void insert_mip_nmea_message(microstrain_serializer* serializer, const mip_nmea_message* self) @@ -27,9 +24,9 @@ void insert_mip_nmea_message(microstrain_serializer* serializer, const mip_nmea_ insert_mip_nmea_message_message_id(serializer, self->message_id); insert_mip_nmea_message_talker_id(serializer, self->talker_id); - + microstrain_insert_u8(serializer, self->source_desc_set); - + microstrain_insert_u16(serializer, self->decimation); } @@ -38,55 +35,17 @@ void extract_mip_nmea_message(microstrain_serializer* serializer, mip_nmea_messa extract_mip_nmea_message_message_id(serializer, &self->message_id); extract_mip_nmea_message_talker_id(serializer, &self->talker_id); - + microstrain_extract_u8(serializer, &self->source_desc_set); - + microstrain_extract_u16(serializer, &self->decimation); } -void insert_mip_nmea_message_message_id(microstrain_serializer* serializer, const mip_nmea_message_message_id self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_nmea_message_message_id(microstrain_serializer* serializer, mip_nmea_message_message_id* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_nmea_message_talker_id(microstrain_serializer* serializer, const mip_nmea_message_talker_id self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_nmea_message_talker_id(microstrain_serializer* serializer, mip_nmea_message_talker_id* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_sensor_range_type(microstrain_serializer* serializer, const mip_sensor_range_type self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_sensor_range_type(microstrain_serializer* serializer, mip_sensor_range_type* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - - -//////////////////////////////////////////////////////////////////////////////// -// Mip Fields -//////////////////////////////////////////////////////////////////////////////// - void insert_mip_3dm_poll_imu_message_command(microstrain_serializer* serializer, const mip_3dm_poll_imu_message_command* self) { microstrain_insert_bool(serializer, self->suppress_ack); - + microstrain_insert_u8(serializer, self->num_descriptors); @@ -99,22 +58,21 @@ void extract_mip_3dm_poll_imu_message_command(microstrain_serializer* serializer microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); } -mip_cmd_result mip_3dm_poll_imu_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) +mip_cmd_result mip_3dm_poll_imu_message(mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_bool(&serializer, suppress_ack); - + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); @@ -123,13 +81,12 @@ mip_cmd_result mip_3dm_poll_imu_message(struct mip_interface* device, bool suppr assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_IMU_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_IMU_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_poll_gnss_message_command(microstrain_serializer* serializer, const mip_3dm_poll_gnss_message_command* self) { microstrain_insert_bool(serializer, self->suppress_ack); - + microstrain_insert_u8(serializer, self->num_descriptors); @@ -142,22 +99,21 @@ void extract_mip_3dm_poll_gnss_message_command(microstrain_serializer* serialize microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); } -mip_cmd_result mip_3dm_poll_gnss_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) +mip_cmd_result mip_3dm_poll_gnss_message(mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_bool(&serializer, suppress_ack); - + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); @@ -166,13 +122,12 @@ mip_cmd_result mip_3dm_poll_gnss_message(struct mip_interface* device, bool supp assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_GNSS_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_GNSS_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_poll_filter_message_command(microstrain_serializer* serializer, const mip_3dm_poll_filter_message_command* self) { microstrain_insert_bool(serializer, self->suppress_ack); - + microstrain_insert_u8(serializer, self->num_descriptors); @@ -185,22 +140,21 @@ void extract_mip_3dm_poll_filter_message_command(microstrain_serializer* seriali microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); } -mip_cmd_result mip_3dm_poll_filter_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) +mip_cmd_result mip_3dm_poll_filter_message(mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_bool(&serializer, suppress_ack); - + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); @@ -209,8 +163,7 @@ mip_cmd_result mip_3dm_poll_filter_message(struct mip_interface* device, bool su assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_FILTER_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_FILTER_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_imu_message_format_command(microstrain_serializer* serializer, const mip_3dm_imu_message_format_command* self) { @@ -233,8 +186,7 @@ void extract_mip_3dm_imu_message_format_command(microstrain_serializer* serializ if( self->function == MIP_FUNCTION_WRITE ) { assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -242,34 +194,14 @@ void extract_mip_3dm_imu_message_format_command(microstrain_serializer* serializ } } -void insert_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, const mip_3dm_imu_message_format_response* self) -{ - microstrain_insert_u8(serializer, self->num_descriptors); - - - for(unsigned int i=0; i < self->num_descriptors; i++) - insert_mip_descriptor_rate(serializer, &self->descriptors[i]); - -} -void extract_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, mip_3dm_imu_message_format_response* self) -{ - assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); - - for(unsigned int i=0; i < self->num_descriptors; i++) - extract_mip_descriptor_rate(serializer, &self->descriptors[i]); - -} - -mip_cmd_result mip_3dm_write_imu_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) +mip_cmd_result mip_3dm_write_imu_message_format(mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); @@ -278,10 +210,9 @@ mip_cmd_result mip_3dm_write_imu_message_format(struct mip_interface* device, ui assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) +mip_cmd_result mip_3dm_read_imu_message_format(mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -292,8 +223,7 @@ mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uin assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -307,12 +237,12 @@ mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uin for(unsigned int i=0; i < *num_descriptors_out; i++) extract_mip_descriptor_rate(&deserializer, &descriptors_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_imu_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_save_imu_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -322,10 +252,9 @@ mip_cmd_result mip_3dm_save_imu_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_imu_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_load_imu_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -335,10 +264,9 @@ mip_cmd_result mip_3dm_load_imu_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_imu_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_default_imu_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -348,8 +276,7 @@ mip_cmd_result mip_3dm_default_imu_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_gps_message_format_command(microstrain_serializer* serializer, const mip_3dm_gps_message_format_command* self) { @@ -372,8 +299,7 @@ void extract_mip_3dm_gps_message_format_command(microstrain_serializer* serializ if( self->function == MIP_FUNCTION_WRITE ) { assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -381,34 +307,14 @@ void extract_mip_3dm_gps_message_format_command(microstrain_serializer* serializ } } -void insert_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, const mip_3dm_gps_message_format_response* self) -{ - microstrain_insert_u8(serializer, self->num_descriptors); - - - for(unsigned int i=0; i < self->num_descriptors; i++) - insert_mip_descriptor_rate(serializer, &self->descriptors[i]); - -} -void extract_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, mip_3dm_gps_message_format_response* self) -{ - assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); - - for(unsigned int i=0; i < self->num_descriptors; i++) - extract_mip_descriptor_rate(serializer, &self->descriptors[i]); - -} - -mip_cmd_result mip_3dm_write_gps_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) +mip_cmd_result mip_3dm_write_gps_message_format(mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); @@ -417,10 +323,9 @@ mip_cmd_result mip_3dm_write_gps_message_format(struct mip_interface* device, ui assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) +mip_cmd_result mip_3dm_read_gps_message_format(mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -431,8 +336,7 @@ mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uin assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -446,12 +350,12 @@ mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uin for(unsigned int i=0; i < *num_descriptors_out; i++) extract_mip_descriptor_rate(&deserializer, &descriptors_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_gps_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_save_gps_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -461,10 +365,9 @@ mip_cmd_result mip_3dm_save_gps_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_gps_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_load_gps_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -474,10 +377,9 @@ mip_cmd_result mip_3dm_load_gps_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_gps_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_default_gps_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -487,8 +389,7 @@ mip_cmd_result mip_3dm_default_gps_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_filter_message_format_command(microstrain_serializer* serializer, const mip_3dm_filter_message_format_command* self) { @@ -511,8 +412,7 @@ void extract_mip_3dm_filter_message_format_command(microstrain_serializer* seria if( self->function == MIP_FUNCTION_WRITE ) { assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -520,34 +420,14 @@ void extract_mip_3dm_filter_message_format_command(microstrain_serializer* seria } } -void insert_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, const mip_3dm_filter_message_format_response* self) -{ - microstrain_insert_u8(serializer, self->num_descriptors); - - - for(unsigned int i=0; i < self->num_descriptors; i++) - insert_mip_descriptor_rate(serializer, &self->descriptors[i]); - -} -void extract_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, mip_3dm_filter_message_format_response* self) -{ - assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); - - for(unsigned int i=0; i < self->num_descriptors; i++) - extract_mip_descriptor_rate(serializer, &self->descriptors[i]); - -} - -mip_cmd_result mip_3dm_write_filter_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) +mip_cmd_result mip_3dm_write_filter_message_format(mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); @@ -556,10 +436,9 @@ mip_cmd_result mip_3dm_write_filter_message_format(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) +mip_cmd_result mip_3dm_read_filter_message_format(mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -570,8 +449,7 @@ mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -585,12 +463,12 @@ mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, for(unsigned int i=0; i < *num_descriptors_out; i++) extract_mip_descriptor_rate(&deserializer, &descriptors_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_filter_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_save_filter_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -600,10 +478,9 @@ mip_cmd_result mip_3dm_save_filter_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_filter_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_load_filter_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -613,10 +490,9 @@ mip_cmd_result mip_3dm_load_filter_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_filter_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_default_filter_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -626,10 +502,9 @@ mip_cmd_result mip_3dm_default_filter_message_format(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_imu_get_base_rate(struct mip_interface* device, uint16_t* rate_out) +mip_cmd_result mip_3dm_imu_get_base_rate(mip_interface* device, uint16_t* rate_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -644,12 +519,12 @@ mip_cmd_result mip_3dm_imu_get_base_rate(struct mip_interface* device, uint16_t* assert(rate_out); microstrain_extract_u16(&deserializer, rate_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_gps_get_base_rate(struct mip_interface* device, uint16_t* rate_out) +mip_cmd_result mip_3dm_gps_get_base_rate(mip_interface* device, uint16_t* rate_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -664,12 +539,12 @@ mip_cmd_result mip_3dm_gps_get_base_rate(struct mip_interface* device, uint16_t* assert(rate_out); microstrain_extract_u16(&deserializer, rate_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_filter_get_base_rate(struct mip_interface* device, uint16_t* rate_out) +mip_cmd_result mip_3dm_filter_get_base_rate(mip_interface* device, uint16_t* rate_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -684,7 +559,7 @@ mip_cmd_result mip_3dm_filter_get_base_rate(struct mip_interface* device, uint16 assert(rate_out); microstrain_extract_u16(&deserializer, rate_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -692,9 +567,9 @@ mip_cmd_result mip_3dm_filter_get_base_rate(struct mip_interface* device, uint16 void insert_mip_3dm_poll_data_command(microstrain_serializer* serializer, const mip_3dm_poll_data_command* self) { microstrain_insert_u8(serializer, self->desc_set); - + microstrain_insert_bool(serializer, self->suppress_ack); - + microstrain_insert_u8(serializer, self->num_descriptors); @@ -705,28 +580,27 @@ void insert_mip_3dm_poll_data_command(microstrain_serializer* serializer, const void extract_mip_3dm_poll_data_command(microstrain_serializer* serializer, mip_3dm_poll_data_command* self) { microstrain_extract_u8(serializer, &self->desc_set); - + microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) microstrain_extract_u8(serializer, &self->descriptors[i]); } -mip_cmd_result mip_3dm_poll_data(struct mip_interface* device, uint8_t desc_set, bool suppress_ack, uint8_t num_descriptors, const uint8_t* descriptors) +mip_cmd_result mip_3dm_poll_data(mip_interface* device, uint8_t desc_set, bool suppress_ack, uint8_t num_descriptors, const uint8_t* descriptors) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_u8(&serializer, desc_set); - + microstrain_insert_bool(&serializer, suppress_ack); - + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); @@ -735,8 +609,7 @@ mip_cmd_result mip_3dm_poll_data(struct mip_interface* device, uint8_t desc_set, assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_DATA, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_DATA, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_get_base_rate_command(microstrain_serializer* serializer, const mip_3dm_get_base_rate_command* self) { @@ -749,46 +622,30 @@ void extract_mip_3dm_get_base_rate_command(microstrain_serializer* serializer, m } -void insert_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_get_base_rate_response* self) -{ - microstrain_insert_u8(serializer, self->desc_set); - - microstrain_insert_u16(serializer, self->rate); - -} -void extract_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_get_base_rate_response* self) -{ - microstrain_extract_u8(serializer, &self->desc_set); - - microstrain_extract_u16(serializer, &self->rate); - -} - -mip_cmd_result mip_3dm_get_base_rate(struct mip_interface* device, uint8_t desc_set, uint16_t* rate_out) +mip_cmd_result mip_3dm_get_base_rate(mip_interface* device, uint8_t desc_set, uint16_t* rate_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_u8(&serializer, desc_set); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GET_BASE_RATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_BASE_RATE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GET_BASE_RATE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_BASE_RATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &desc_set); assert(rate_out); microstrain_extract_u16(&deserializer, rate_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -796,7 +653,7 @@ mip_cmd_result mip_3dm_get_base_rate(struct mip_interface* device, uint8_t desc_ void insert_mip_3dm_message_format_command(microstrain_serializer* serializer, const mip_3dm_message_format_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->desc_set); if( self->function == MIP_FUNCTION_WRITE ) @@ -812,14 +669,13 @@ void insert_mip_3dm_message_format_command(microstrain_serializer* serializer, c void extract_mip_3dm_message_format_command(microstrain_serializer* serializer, mip_3dm_message_format_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->desc_set); if( self->function == MIP_FUNCTION_WRITE ) { assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); for(unsigned int i=0; i < self->num_descriptors; i++) extract_mip_descriptor_rate(serializer, &self->descriptors[i]); @@ -827,40 +683,16 @@ void extract_mip_3dm_message_format_command(microstrain_serializer* serializer, } } -void insert_mip_3dm_message_format_response(microstrain_serializer* serializer, const mip_3dm_message_format_response* self) -{ - microstrain_insert_u8(serializer, self->desc_set); - - microstrain_insert_u8(serializer, self->num_descriptors); - - - for(unsigned int i=0; i < self->num_descriptors; i++) - insert_mip_descriptor_rate(serializer, &self->descriptors[i]); - -} -void extract_mip_3dm_message_format_response(microstrain_serializer* serializer, mip_3dm_message_format_response* self) -{ - microstrain_extract_u8(serializer, &self->desc_set); - - assert(self->num_descriptors); - microstrain_extract_count(serializer, &self->num_descriptors, - sizeof(self->descriptors) / sizeof(self->descriptors[0])); - - for(unsigned int i=0; i < self->num_descriptors; i++) - extract_mip_descriptor_rate(serializer, &self->descriptors[i]); - -} - -mip_cmd_result mip_3dm_write_message_format(struct mip_interface* device, uint8_t desc_set, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) +mip_cmd_result mip_3dm_write_message_format(mip_interface* device, uint8_t desc_set, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, desc_set); - + microstrain_insert_u8(&serializer, num_descriptors); assert(descriptors || (num_descriptors == 0)); @@ -869,30 +701,28 @@ mip_cmd_result mip_3dm_write_message_format(struct mip_interface* device, uint8_ assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_message_format(struct mip_interface* device, uint8_t desc_set, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) +mip_cmd_result mip_3dm_read_message_format(mip_interface* device, uint8_t desc_set, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, desc_set); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &desc_set); assert(num_descriptors_out); @@ -902,60 +732,57 @@ mip_cmd_result mip_3dm_read_message_format(struct mip_interface* device, uint8_t for(unsigned int i=0; i < *num_descriptors_out; i++) extract_mip_descriptor_rate(&deserializer, &descriptors_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_message_format(struct mip_interface* device, uint8_t desc_set) +mip_cmd_result mip_3dm_save_message_format(mip_interface* device, uint8_t desc_set) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, desc_set); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_message_format(struct mip_interface* device, uint8_t desc_set) +mip_cmd_result mip_3dm_load_message_format(mip_interface* device, uint8_t desc_set) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, desc_set); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_message_format(struct mip_interface* device, uint8_t desc_set) +mip_cmd_result mip_3dm_default_message_format(mip_interface* device, uint8_t desc_set) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, desc_set); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_nmea_poll_data_command(microstrain_serializer* serializer, const mip_3dm_nmea_poll_data_command* self) { microstrain_insert_bool(serializer, self->suppress_ack); - + microstrain_insert_u8(serializer, self->count); @@ -968,21 +795,21 @@ void extract_mip_3dm_nmea_poll_data_command(microstrain_serializer* serializer, microstrain_extract_bool(serializer, &self->suppress_ack); assert(self->count); - microstrain_extract_count(serializer, &self->count, sizeof(self->format_entries) / sizeof(self->format_entries[0])); + microstrain_extract_count(serializer, &self->count, sizeof(self->format_entries)/sizeof(self->format_entries[0])); for(unsigned int i=0; i < self->count; i++) extract_mip_nmea_message(serializer, &self->format_entries[i]); } -mip_cmd_result mip_3dm_nmea_poll_data(struct mip_interface* device, bool suppress_ack, uint8_t count, const mip_nmea_message* format_entries) +mip_cmd_result mip_3dm_nmea_poll_data(mip_interface* device, bool suppress_ack, uint8_t count, const mip_nmea_message* format_entries) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_bool(&serializer, suppress_ack); - + microstrain_insert_u8(&serializer, count); assert(format_entries || (count == 0)); @@ -991,8 +818,7 @@ mip_cmd_result mip_3dm_nmea_poll_data(struct mip_interface* device, bool suppres assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_NMEA_MESSAGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_POLL_NMEA_MESSAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_nmea_message_format_command(microstrain_serializer* serializer, const mip_3dm_nmea_message_format_command* self) { @@ -1015,8 +841,7 @@ void extract_mip_3dm_nmea_message_format_command(microstrain_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { assert(self->count); - microstrain_extract_count(serializer, &self->count, - sizeof(self->format_entries) / sizeof(self->format_entries[0])); + microstrain_extract_count(serializer, &self->count, sizeof(self->format_entries)/sizeof(self->format_entries[0])); for(unsigned int i=0; i < self->count; i++) extract_mip_nmea_message(serializer, &self->format_entries[i]); @@ -1024,33 +849,14 @@ void extract_mip_3dm_nmea_message_format_command(microstrain_serializer* seriali } } -void insert_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, const mip_3dm_nmea_message_format_response* self) -{ - microstrain_insert_u8(serializer, self->count); - - - for(unsigned int i=0; i < self->count; i++) - insert_mip_nmea_message(serializer, &self->format_entries[i]); - -} -void extract_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, mip_3dm_nmea_message_format_response* self) -{ - assert(self->count); - microstrain_extract_count(serializer, &self->count, sizeof(self->format_entries) / sizeof(self->format_entries[0])); - - for(unsigned int i=0; i < self->count; i++) - extract_mip_nmea_message(serializer, &self->format_entries[i]); - -} - -mip_cmd_result mip_3dm_write_nmea_message_format(struct mip_interface* device, uint8_t count, const mip_nmea_message* format_entries) +mip_cmd_result mip_3dm_write_nmea_message_format(mip_interface* device, uint8_t count, const mip_nmea_message* format_entries) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, count); assert(format_entries || (count == 0)); @@ -1059,10 +865,9 @@ mip_cmd_result mip_3dm_write_nmea_message_format(struct mip_interface* device, u assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, uint8_t* count_out, uint8_t count_out_max, mip_nmea_message* format_entries_out) +mip_cmd_result mip_3dm_read_nmea_message_format(mip_interface* device, uint8_t* count_out, uint8_t count_out_max, mip_nmea_message* format_entries_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1073,8 +878,7 @@ mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, ui assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1088,12 +892,12 @@ mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, ui for(unsigned int i=0; i < *count_out; i++) extract_mip_nmea_message(&deserializer, &format_entries_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_nmea_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_save_nmea_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1103,10 +907,9 @@ mip_cmd_result mip_3dm_save_nmea_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_nmea_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_load_nmea_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1116,10 +919,9 @@ mip_cmd_result mip_3dm_load_nmea_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_nmea_message_format(struct mip_interface* device) +mip_cmd_result mip_3dm_default_nmea_message_format(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1129,8 +931,7 @@ mip_cmd_result mip_3dm_default_nmea_message_format(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_device_settings_command(microstrain_serializer* serializer, const mip_3dm_device_settings_command* self) { @@ -1143,7 +944,7 @@ void extract_mip_3dm_device_settings_command(microstrain_serializer* serializer, } -mip_cmd_result mip_3dm_save_device_settings(struct mip_interface* device) +mip_cmd_result mip_3dm_save_device_settings(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1153,10 +954,9 @@ mip_cmd_result mip_3dm_save_device_settings(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_device_settings(struct mip_interface* device) +mip_cmd_result mip_3dm_load_device_settings(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1166,10 +966,9 @@ mip_cmd_result mip_3dm_load_device_settings(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_device_settings(struct mip_interface* device) +mip_cmd_result mip_3dm_default_device_settings(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1179,8 +978,7 @@ mip_cmd_result mip_3dm_default_device_settings(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_uart_baudrate_command(microstrain_serializer* serializer, const mip_3dm_uart_baudrate_command* self) { @@ -1203,33 +1001,21 @@ void extract_mip_3dm_uart_baudrate_command(microstrain_serializer* serializer, m } } -void insert_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, const mip_3dm_uart_baudrate_response* self) -{ - microstrain_insert_u32(serializer, self->baud); - -} -void extract_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, mip_3dm_uart_baudrate_response* self) -{ - microstrain_extract_u32(serializer, &self->baud); - -} - -mip_cmd_result mip_3dm_write_uart_baudrate(struct mip_interface* device, uint32_t baud) +mip_cmd_result mip_3dm_write_uart_baudrate(mip_interface* device, uint32_t baud) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u32(&serializer, baud); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t* baud_out) +mip_cmd_result mip_3dm_read_uart_baudrate(mip_interface* device, uint32_t* baud_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1240,8 +1026,7 @@ mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_UART_BAUDRATE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_UART_BAUDRATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1251,12 +1036,12 @@ mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t assert(baud_out); microstrain_extract_u32(&deserializer, baud_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_uart_baudrate(struct mip_interface* device) +mip_cmd_result mip_3dm_save_uart_baudrate(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1266,10 +1051,9 @@ mip_cmd_result mip_3dm_save_uart_baudrate(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_uart_baudrate(struct mip_interface* device) +mip_cmd_result mip_3dm_load_uart_baudrate(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1279,10 +1063,9 @@ mip_cmd_result mip_3dm_load_uart_baudrate(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_uart_baudrate(struct mip_interface* device) +mip_cmd_result mip_3dm_default_uart_baudrate(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1292,54 +1075,41 @@ mip_cmd_result mip_3dm_default_uart_baudrate(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_UART_BAUDRATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_factory_streaming_command(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command* self) { insert_mip_3dm_factory_streaming_command_action(serializer, self->action); - + microstrain_insert_u8(serializer, self->reserved); } void extract_mip_3dm_factory_streaming_command(microstrain_serializer* serializer, mip_3dm_factory_streaming_command* self) { extract_mip_3dm_factory_streaming_command_action(serializer, &self->action); - + microstrain_extract_u8(serializer, &self->reserved); } -void insert_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command_action self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, mip_3dm_factory_streaming_command_action* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_3dm_factory_streaming(struct mip_interface* device, mip_3dm_factory_streaming_command_action action, uint8_t reserved) +mip_cmd_result mip_3dm_factory_streaming(mip_interface* device, mip_3dm_factory_streaming_command_action action, uint8_t reserved) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_3dm_factory_streaming_command_action(&serializer, action); - + microstrain_insert_u8(&serializer, reserved); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_datastream_control_command(microstrain_serializer* serializer, const mip_3dm_datastream_control_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->desc_set); if( self->function == MIP_FUNCTION_WRITE ) @@ -1351,7 +1121,7 @@ void insert_mip_3dm_datastream_control_command(microstrain_serializer* serialize void extract_mip_3dm_datastream_control_command(microstrain_serializer* serializer, mip_3dm_datastream_control_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->desc_set); if( self->function == MIP_FUNCTION_WRITE ) @@ -1361,113 +1131,93 @@ void extract_mip_3dm_datastream_control_command(microstrain_serializer* serializ } } -void insert_mip_3dm_datastream_control_response(microstrain_serializer* serializer, const mip_3dm_datastream_control_response* self) -{ - microstrain_insert_u8(serializer, self->desc_set); - - microstrain_insert_bool(serializer, self->enabled); - -} -void extract_mip_3dm_datastream_control_response(microstrain_serializer* serializer, mip_3dm_datastream_control_response* self) -{ - microstrain_extract_u8(serializer, &self->desc_set); - - microstrain_extract_bool(serializer, &self->enabled); - -} - -mip_cmd_result mip_3dm_write_datastream_control(struct mip_interface* device, uint8_t desc_set, bool enable) +mip_cmd_result mip_3dm_write_datastream_control(mip_interface* device, uint8_t desc_set, bool enable) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, desc_set); - + microstrain_insert_bool(&serializer, enable); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_datastream_control(struct mip_interface* device, uint8_t desc_set, bool* enabled_out) +mip_cmd_result mip_3dm_read_datastream_control(mip_interface* device, uint8_t desc_set, bool* enabled_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, desc_set); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_DATASTREAM_ENABLE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_DATASTREAM_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &desc_set); assert(enabled_out); microstrain_extract_bool(&deserializer, enabled_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_datastream_control(struct mip_interface* device, uint8_t desc_set) +mip_cmd_result mip_3dm_save_datastream_control(mip_interface* device, uint8_t desc_set) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, desc_set); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_datastream_control(struct mip_interface* device, uint8_t desc_set) +mip_cmd_result mip_3dm_load_datastream_control(mip_interface* device, uint8_t desc_set) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, desc_set); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_datastream_control(struct mip_interface* device, uint8_t desc_set) +mip_cmd_result mip_3dm_default_datastream_control(mip_interface* device, uint8_t desc_set) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, desc_set); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_constellation_settings_command(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command* self) { @@ -1476,7 +1226,7 @@ void insert_mip_3dm_constellation_settings_command(microstrain_serializer* seria if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_u16(serializer, self->max_channels); - + microstrain_insert_u8(serializer, self->config_count); @@ -1494,7 +1244,7 @@ void extract_mip_3dm_constellation_settings_command(microstrain_serializer* seri microstrain_extract_u16(serializer, &self->max_channels); assert(self->config_count); - microstrain_extract_count(serializer, &self->config_count, sizeof(self->settings) / sizeof(self->settings[0])); + microstrain_extract_count(serializer, &self->config_count, sizeof(self->settings)/sizeof(self->settings[0])); for(unsigned int i=0; i < self->config_count; i++) extract_mip_3dm_constellation_settings_command_settings(serializer, &self->settings[i]); @@ -1502,104 +1252,27 @@ void extract_mip_3dm_constellation_settings_command(microstrain_serializer* seri } } -void insert_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, const mip_3dm_constellation_settings_response* self) +mip_cmd_result mip_3dm_write_constellation_settings(mip_interface* device, uint16_t max_channels, uint8_t config_count, const mip_3dm_constellation_settings_command_settings* settings) { - microstrain_insert_u16(serializer, self->max_channels_available); - - microstrain_insert_u16(serializer, self->max_channels_use); - - microstrain_insert_u8(serializer, self->config_count); + microstrain_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - for(unsigned int i=0; i < self->config_count; i++) - insert_mip_3dm_constellation_settings_command_settings(serializer, &self->settings[i]); + microstrain_insert_u16(&serializer, max_channels); -} -void extract_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, mip_3dm_constellation_settings_response* self) -{ - microstrain_extract_u16(serializer, &self->max_channels_available); - - microstrain_extract_u16(serializer, &self->max_channels_use); + microstrain_insert_u8(&serializer, config_count); - assert(self->config_count); - microstrain_extract_count(serializer, &self->config_count, sizeof(self->settings) / sizeof(self->settings[0])); + assert(settings || (config_count == 0)); + for(unsigned int i=0; i < config_count; i++) + insert_mip_3dm_constellation_settings_command_settings(&serializer, &settings[i]); - for(unsigned int i=0; i < self->config_count; i++) - extract_mip_3dm_constellation_settings_command_settings(serializer, &self->settings[i]); + assert(microstrain_serializer_is_ok(&serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } - -void insert_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -void insert_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_settings* self) -{ - insert_mip_3dm_constellation_settings_command_constellation_id(serializer, self->constellation_id); - - microstrain_insert_u8(serializer, self->enable); - - microstrain_insert_u8(serializer, self->reserved_channels); - - microstrain_insert_u8(serializer, self->max_channels); - - insert_mip_3dm_constellation_settings_command_option_flags(serializer, self->option_flags); - -} -void extract_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_settings* self) -{ - extract_mip_3dm_constellation_settings_command_constellation_id(serializer, &self->constellation_id); - - microstrain_extract_u8(serializer, &self->enable); - - microstrain_extract_u8(serializer, &self->reserved_channels); - - microstrain_extract_u8(serializer, &self->max_channels); - - extract_mip_3dm_constellation_settings_command_option_flags(serializer, &self->option_flags); - -} - -mip_cmd_result mip_3dm_write_constellation_settings(struct mip_interface* device, uint16_t max_channels, uint8_t config_count, const mip_3dm_constellation_settings_command_settings* settings) -{ - microstrain_serializer serializer; - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - microstrain_insert_u16(&serializer, max_channels); - - microstrain_insert_u8(&serializer, config_count); - - assert(settings || (config_count == 0)); - for(unsigned int i=0; i < config_count; i++) - insert_mip_3dm_constellation_settings_command_settings(&serializer, &settings[i]); - - assert(microstrain_serializer_is_ok(&serializer)); - - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); -} -mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, uint16_t* max_channels_available_out, uint16_t* max_channels_use_out, uint8_t* config_count_out, uint8_t config_count_out_max, mip_3dm_constellation_settings_command_settings* settings_out) +mip_cmd_result mip_3dm_read_constellation_settings(mip_interface* device, uint16_t* max_channels_available_out, uint16_t* max_channels_use_out, uint8_t* config_count_out, uint8_t config_count_out_max, mip_3dm_constellation_settings_command_settings* settings_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1610,8 +1283,7 @@ mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1631,12 +1303,12 @@ mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, for(unsigned int i=0; i < *config_count_out; i++) extract_mip_3dm_constellation_settings_command_settings(&deserializer, &settings_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_constellation_settings(struct mip_interface* device) +mip_cmd_result mip_3dm_save_constellation_settings(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1646,10 +1318,9 @@ mip_cmd_result mip_3dm_save_constellation_settings(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_constellation_settings(struct mip_interface* device) +mip_cmd_result mip_3dm_load_constellation_settings(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1659,10 +1330,9 @@ mip_cmd_result mip_3dm_load_constellation_settings(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_constellation_settings(struct mip_interface* device) +mip_cmd_result mip_3dm_default_constellation_settings(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1672,8 +1342,7 @@ mip_cmd_result mip_3dm_default_constellation_settings(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command* self) { @@ -1684,7 +1353,7 @@ void insert_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serialize microstrain_insert_u8(serializer, self->enable_sbas); insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, self->sbas_options); - + microstrain_insert_u8(serializer, self->num_included_prns); @@ -1704,8 +1373,7 @@ void extract_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializ extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, &self->sbas_options); assert(self->num_included_prns); - microstrain_extract_count(serializer, &self->num_included_prns, - sizeof(self->included_prns) / sizeof(self->included_prns[0])); + microstrain_extract_count(serializer, &self->num_included_prns, sizeof(self->included_prns)/sizeof(self->included_prns[0])); for(unsigned int i=0; i < self->num_included_prns; i++) microstrain_extract_u16(serializer, &self->included_prns[i]); @@ -1713,57 +1381,18 @@ void extract_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializ } } -void insert_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_response* self) -{ - microstrain_insert_u8(serializer, self->enable_sbas); - - insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, self->sbas_options); - - microstrain_insert_u8(serializer, self->num_included_prns); - - - for(unsigned int i=0; i < self->num_included_prns; i++) - microstrain_insert_u16(serializer, self->included_prns[i]); - -} -void extract_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_response* self) -{ - microstrain_extract_u8(serializer, &self->enable_sbas); - - extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, &self->sbas_options); - - assert(self->num_included_prns); - microstrain_extract_count(serializer, &self->num_included_prns, - sizeof(self->included_prns) / sizeof(self->included_prns[0])); - - for(unsigned int i=0; i < self->num_included_prns; i++) - microstrain_extract_u16(serializer, &self->included_prns[i]); - -} - -void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_3dm_write_gnss_sbas_settings(struct mip_interface* device, uint8_t enable_sbas, mip_3dm_gnss_sbas_settings_command_sbasoptions sbas_options, uint8_t num_included_prns, const uint16_t* included_prns) +mip_cmd_result mip_3dm_write_gnss_sbas_settings(mip_interface* device, uint8_t enable_sbas, mip_3dm_gnss_sbas_settings_command_sbasoptions sbas_options, uint8_t num_included_prns, const uint16_t* included_prns) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, enable_sbas); insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(&serializer, sbas_options); - + microstrain_insert_u8(&serializer, num_included_prns); assert(included_prns || (num_included_prns == 0)); @@ -1772,10 +1401,9 @@ mip_cmd_result mip_3dm_write_gnss_sbas_settings(struct mip_interface* device, ui assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uint8_t* enable_sbas_out, mip_3dm_gnss_sbas_settings_command_sbasoptions* sbas_options_out, uint8_t* num_included_prns_out, uint8_t num_included_prns_out_max, uint16_t* included_prns_out) +mip_cmd_result mip_3dm_read_gnss_sbas_settings(mip_interface* device, uint8_t* enable_sbas_out, mip_3dm_gnss_sbas_settings_command_sbasoptions* sbas_options_out, uint8_t* num_included_prns_out, uint8_t num_included_prns_out_max, uint16_t* included_prns_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1786,8 +1414,7 @@ mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uin assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1807,12 +1434,12 @@ mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uin for(unsigned int i=0; i < *num_included_prns_out; i++) microstrain_extract_u16(&deserializer, &included_prns_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_gnss_sbas_settings(struct mip_interface* device) +mip_cmd_result mip_3dm_save_gnss_sbas_settings(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1822,10 +1449,9 @@ mip_cmd_result mip_3dm_save_gnss_sbas_settings(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_gnss_sbas_settings(struct mip_interface* device) +mip_cmd_result mip_3dm_load_gnss_sbas_settings(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1835,10 +1461,9 @@ mip_cmd_result mip_3dm_load_gnss_sbas_settings(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_gnss_sbas_settings(struct mip_interface* device) +mip_cmd_result mip_3dm_default_gnss_sbas_settings(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1848,8 +1473,7 @@ mip_cmd_result mip_3dm_default_gnss_sbas_settings(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_SBAS_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command* self) { @@ -1858,7 +1482,7 @@ void insert_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serializer if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, self->option); - + microstrain_insert_u8(serializer, self->flags); } @@ -1870,39 +1494,13 @@ void extract_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serialize if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, &self->option); - + microstrain_extract_u8(serializer, &self->flags); } } -void insert_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_response* self) -{ - insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, self->option); - - microstrain_insert_u8(serializer, self->flags); - -} -void extract_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_response* self) -{ - extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, &self->option); - - microstrain_extract_u8(serializer, &self->flags); - -} - -void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_3dm_write_gnss_assisted_fix(struct mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option option, uint8_t flags) +mip_cmd_result mip_3dm_write_gnss_assisted_fix(mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option option, uint8_t flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1911,15 +1509,14 @@ mip_cmd_result mip_3dm_write_gnss_assisted_fix(struct mip_interface* device, mip insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(&serializer, option); - + microstrain_insert_u8(&serializer, flags); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* option_out, uint8_t* flags_out) +mip_cmd_result mip_3dm_read_gnss_assisted_fix(mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* option_out, uint8_t* flags_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1930,8 +1527,7 @@ mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_ assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1944,12 +1540,12 @@ mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_ assert(flags_out); microstrain_extract_u8(&deserializer, flags_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_gnss_assisted_fix(struct mip_interface* device) +mip_cmd_result mip_3dm_save_gnss_assisted_fix(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1959,10 +1555,9 @@ mip_cmd_result mip_3dm_save_gnss_assisted_fix(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_gnss_assisted_fix(struct mip_interface* device) +mip_cmd_result mip_3dm_load_gnss_assisted_fix(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1972,10 +1567,9 @@ mip_cmd_result mip_3dm_load_gnss_assisted_fix(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_gnss_assisted_fix(struct mip_interface* device) +mip_cmd_result mip_3dm_default_gnss_assisted_fix(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1985,8 +1579,7 @@ mip_cmd_result mip_3dm_default_gnss_assisted_fix(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_gnss_time_assistance_command(microstrain_serializer* serializer, const mip_3dm_gnss_time_assistance_command* self) { @@ -1995,9 +1588,9 @@ void insert_mip_3dm_gnss_time_assistance_command(microstrain_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_double(serializer, self->tow); - + microstrain_insert_u16(serializer, self->week_number); - + microstrain_insert_float(serializer, self->accuracy); } @@ -2009,53 +1602,33 @@ void extract_mip_3dm_gnss_time_assistance_command(microstrain_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_double(serializer, &self->tow); - + microstrain_extract_u16(serializer, &self->week_number); - + microstrain_extract_float(serializer, &self->accuracy); } } -void insert_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, const mip_3dm_gnss_time_assistance_response* self) -{ - microstrain_insert_double(serializer, self->tow); - - microstrain_insert_u16(serializer, self->week_number); - - microstrain_insert_float(serializer, self->accuracy); - -} -void extract_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, mip_3dm_gnss_time_assistance_response* self) -{ - microstrain_extract_double(serializer, &self->tow); - - microstrain_extract_u16(serializer, &self->week_number); - - microstrain_extract_float(serializer, &self->accuracy); - -} - -mip_cmd_result mip_3dm_write_gnss_time_assistance(struct mip_interface* device, double tow, uint16_t week_number, float accuracy) +mip_cmd_result mip_3dm_write_gnss_time_assistance(mip_interface* device, double tow, uint16_t week_number, float accuracy) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_double(&serializer, tow); - + microstrain_insert_u16(&serializer, week_number); - + microstrain_insert_float(&serializer, accuracy); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, double* tow_out, uint16_t* week_number_out, float* accuracy_out) +mip_cmd_result mip_3dm_read_gnss_time_assistance(mip_interface* device, double* tow_out, uint16_t* week_number_out, float* accuracy_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2066,8 +1639,7 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GNSS_TIME_ASSISTANCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2083,7 +1655,7 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d assert(accuracy_out); microstrain_extract_float(&deserializer, accuracy_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2091,17 +1663,17 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, d void insert_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serializer, const mip_3dm_imu_lowpass_filter_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->target_descriptor); if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_bool(serializer, self->enable); - + microstrain_insert_bool(serializer, self->manual); - + microstrain_insert_u16(serializer, self->frequency); - + microstrain_insert_u8(serializer, self->reserved); } @@ -2109,93 +1681,64 @@ void insert_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serialize void extract_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serializer, mip_3dm_imu_lowpass_filter_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->target_descriptor); if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_bool(serializer, &self->enable); - + microstrain_extract_bool(serializer, &self->manual); - + microstrain_extract_u16(serializer, &self->frequency); - + microstrain_extract_u8(serializer, &self->reserved); } } -void insert_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_imu_lowpass_filter_response* self) -{ - microstrain_insert_u8(serializer, self->target_descriptor); - - microstrain_insert_bool(serializer, self->enable); - - microstrain_insert_bool(serializer, self->manual); - - microstrain_insert_u16(serializer, self->frequency); - - microstrain_insert_u8(serializer, self->reserved); - -} -void extract_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_imu_lowpass_filter_response* self) -{ - microstrain_extract_u8(serializer, &self->target_descriptor); - - microstrain_extract_bool(serializer, &self->enable); - - microstrain_extract_bool(serializer, &self->manual); - - microstrain_extract_u16(serializer, &self->frequency); - - microstrain_extract_u8(serializer, &self->reserved); - -} - -mip_cmd_result mip_3dm_write_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) +mip_cmd_result mip_3dm_write_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, target_descriptor); - + microstrain_insert_bool(&serializer, enable); - + microstrain_insert_bool(&serializer, manual); - + microstrain_insert_u16(&serializer, frequency); - + microstrain_insert_u8(&serializer, reserved); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor, bool* enable_out, bool* manual_out, uint16_t* frequency_out, uint8_t* reserved_out) +mip_cmd_result mip_3dm_read_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor, bool* enable_out, bool* manual_out, uint16_t* frequency_out, uint8_t* reserved_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, target_descriptor); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_ADVANCED_DATA_FILTER, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_ADVANCED_DATA_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &target_descriptor); assert(enable_out); @@ -2210,55 +1753,52 @@ mip_cmd_result mip_3dm_read_imu_lowpass_filter(struct mip_interface* device, uin assert(reserved_out); microstrain_extract_u8(&deserializer, reserved_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) +mip_cmd_result mip_3dm_save_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, target_descriptor); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) +mip_cmd_result mip_3dm_load_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, target_descriptor); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor) +mip_cmd_result mip_3dm_default_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, target_descriptor); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_IMU_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_pps_source_command(microstrain_serializer* serializer, const mip_3dm_pps_source_command* self) { @@ -2281,29 +1821,7 @@ void extract_mip_3dm_pps_source_command(microstrain_serializer* serializer, mip_ } } -void insert_mip_3dm_pps_source_response(microstrain_serializer* serializer, const mip_3dm_pps_source_response* self) -{ - insert_mip_3dm_pps_source_command_source(serializer, self->source); - -} -void extract_mip_3dm_pps_source_response(microstrain_serializer* serializer, mip_3dm_pps_source_response* self) -{ - extract_mip_3dm_pps_source_command_source(serializer, &self->source); - -} - -void insert_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, const mip_3dm_pps_source_command_source self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, mip_3dm_pps_source_command_source* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_3dm_write_pps_source(struct mip_interface* device, mip_3dm_pps_source_command_source source) +mip_cmd_result mip_3dm_write_pps_source(mip_interface* device, mip_3dm_pps_source_command_source source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2315,10 +1833,9 @@ mip_cmd_result mip_3dm_write_pps_source(struct mip_interface* device, mip_3dm_pp assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps_source_command_source* source_out) +mip_cmd_result mip_3dm_read_pps_source(mip_interface* device, mip_3dm_pps_source_command_source* source_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2329,8 +1846,7 @@ mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_PPS_SOURCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_PPS_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2340,12 +1856,12 @@ mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps assert(source_out); extract_mip_3dm_pps_source_command_source(&deserializer, source_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_pps_source(struct mip_interface* device) +mip_cmd_result mip_3dm_save_pps_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2355,10 +1871,9 @@ mip_cmd_result mip_3dm_save_pps_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_pps_source(struct mip_interface* device) +mip_cmd_result mip_3dm_load_pps_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2368,10 +1883,9 @@ mip_cmd_result mip_3dm_load_pps_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_pps_source(struct mip_interface* device) +mip_cmd_result mip_3dm_default_pps_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2381,13 +1895,12 @@ mip_cmd_result mip_3dm_default_pps_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_PPS_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_gpio_config_command(microstrain_serializer* serializer, const mip_3dm_gpio_config_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->pin); if( self->function == MIP_FUNCTION_WRITE ) @@ -2403,7 +1916,7 @@ void insert_mip_3dm_gpio_config_command(microstrain_serializer* serializer, cons void extract_mip_3dm_gpio_config_command(microstrain_serializer* serializer, mip_3dm_gpio_config_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->pin); if( self->function == MIP_FUNCTION_WRITE ) @@ -2417,70 +1930,14 @@ void extract_mip_3dm_gpio_config_command(microstrain_serializer* serializer, mip } } -void insert_mip_3dm_gpio_config_response(microstrain_serializer* serializer, const mip_3dm_gpio_config_response* self) -{ - microstrain_insert_u8(serializer, self->pin); - - insert_mip_3dm_gpio_config_command_feature(serializer, self->feature); - - insert_mip_3dm_gpio_config_command_behavior(serializer, self->behavior); - - insert_mip_3dm_gpio_config_command_pin_mode(serializer, self->pin_mode); - -} -void extract_mip_3dm_gpio_config_response(microstrain_serializer* serializer, mip_3dm_gpio_config_response* self) -{ - microstrain_extract_u8(serializer, &self->pin); - - extract_mip_3dm_gpio_config_command_feature(serializer, &self->feature); - - extract_mip_3dm_gpio_config_command_behavior(serializer, &self->behavior); - - extract_mip_3dm_gpio_config_command_pin_mode(serializer, &self->pin_mode); - -} - -void insert_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_feature self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, mip_3dm_gpio_config_command_feature* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_behavior self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, mip_3dm_gpio_config_command_behavior* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_3dm_write_gpio_config(struct mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature feature, mip_3dm_gpio_config_command_behavior behavior, mip_3dm_gpio_config_command_pin_mode pin_mode) +mip_cmd_result mip_3dm_write_gpio_config(mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature feature, mip_3dm_gpio_config_command_behavior behavior, mip_3dm_gpio_config_command_pin_mode pin_mode) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, pin); insert_mip_3dm_gpio_config_command_feature(&serializer, feature); @@ -2491,30 +1948,28 @@ mip_cmd_result mip_3dm_write_gpio_config(struct mip_interface* device, uint8_t p assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature* feature_out, mip_3dm_gpio_config_command_behavior* behavior_out, mip_3dm_gpio_config_command_pin_mode* pin_mode_out) +mip_cmd_result mip_3dm_read_gpio_config(mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature* feature_out, mip_3dm_gpio_config_command_behavior* behavior_out, mip_3dm_gpio_config_command_pin_mode* pin_mode_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, pin); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_GPIO_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GPIO_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &pin); assert(feature_out); @@ -2526,55 +1981,52 @@ mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pi assert(pin_mode_out); extract_mip_3dm_gpio_config_command_pin_mode(&deserializer, pin_mode_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_gpio_config(struct mip_interface* device, uint8_t pin) +mip_cmd_result mip_3dm_save_gpio_config(mip_interface* device, uint8_t pin) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, pin); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_gpio_config(struct mip_interface* device, uint8_t pin) +mip_cmd_result mip_3dm_load_gpio_config(mip_interface* device, uint8_t pin) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, pin); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_gpio_config(struct mip_interface* device, uint8_t pin) +mip_cmd_result mip_3dm_default_gpio_config(mip_interface* device, uint8_t pin) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, pin); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_gpio_state_command(microstrain_serializer* serializer, const mip_3dm_gpio_state_command* self) { @@ -2607,65 +2059,48 @@ void extract_mip_3dm_gpio_state_command(microstrain_serializer* serializer, mip_ } } -void insert_mip_3dm_gpio_state_response(microstrain_serializer* serializer, const mip_3dm_gpio_state_response* self) -{ - microstrain_insert_u8(serializer, self->pin); - - microstrain_insert_bool(serializer, self->state); - -} -void extract_mip_3dm_gpio_state_response(microstrain_serializer* serializer, mip_3dm_gpio_state_response* self) -{ - microstrain_extract_u8(serializer, &self->pin); - - microstrain_extract_bool(serializer, &self->state); - -} - -mip_cmd_result mip_3dm_write_gpio_state(struct mip_interface* device, uint8_t pin, bool state) +mip_cmd_result mip_3dm_write_gpio_state(mip_interface* device, uint8_t pin, bool state) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, pin); - + microstrain_insert_bool(&serializer, state); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_STATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_STATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_gpio_state(struct mip_interface* device, uint8_t pin, bool* state_out) +mip_cmd_result mip_3dm_read_gpio_state(mip_interface* device, uint8_t pin, bool* state_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, pin); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_STATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_GPIO_STATE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GPIO_STATE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GPIO_STATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &pin); assert(state_out); microstrain_extract_bool(&deserializer, state_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2677,9 +2112,9 @@ void insert_mip_3dm_odometer_command(microstrain_serializer* serializer, const m if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_3dm_odometer_command_mode(serializer, self->mode); - + microstrain_insert_float(serializer, self->scaling); - + microstrain_insert_float(serializer, self->uncertainty); } @@ -2691,45 +2126,15 @@ void extract_mip_3dm_odometer_command(microstrain_serializer* serializer, mip_3d if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_3dm_odometer_command_mode(serializer, &self->mode); - + microstrain_extract_float(serializer, &self->scaling); - + microstrain_extract_float(serializer, &self->uncertainty); } } -void insert_mip_3dm_odometer_response(microstrain_serializer* serializer, const mip_3dm_odometer_response* self) -{ - insert_mip_3dm_odometer_command_mode(serializer, self->mode); - - microstrain_insert_float(serializer, self->scaling); - - microstrain_insert_float(serializer, self->uncertainty); - -} -void extract_mip_3dm_odometer_response(microstrain_serializer* serializer, mip_3dm_odometer_response* self) -{ - extract_mip_3dm_odometer_command_mode(serializer, &self->mode); - - microstrain_extract_float(serializer, &self->scaling); - - microstrain_extract_float(serializer, &self->uncertainty); - -} - -void insert_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, const mip_3dm_odometer_command_mode self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, mip_3dm_odometer_command_mode* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_3dm_write_odometer(struct mip_interface* device, mip_3dm_odometer_command_mode mode, float scaling, float uncertainty) +mip_cmd_result mip_3dm_write_odometer(mip_interface* device, mip_3dm_odometer_command_mode mode, float scaling, float uncertainty) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2738,17 +2143,16 @@ mip_cmd_result mip_3dm_write_odometer(struct mip_interface* device, mip_3dm_odom insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_3dm_odometer_command_mode(&serializer, mode); - + microstrain_insert_float(&serializer, scaling); - + microstrain_insert_float(&serializer, uncertainty); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odometer_command_mode* mode_out, float* scaling_out, float* uncertainty_out) +mip_cmd_result mip_3dm_read_odometer(mip_interface* device, mip_3dm_odometer_command_mode* mode_out, float* scaling_out, float* uncertainty_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2759,8 +2163,7 @@ mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odome assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_ODOMETER_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_ODOMETER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2776,12 +2179,12 @@ mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odome assert(uncertainty_out); microstrain_extract_float(&deserializer, uncertainty_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_odometer(struct mip_interface* device) +mip_cmd_result mip_3dm_save_odometer(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2791,10 +2194,9 @@ mip_cmd_result mip_3dm_save_odometer(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_odometer(struct mip_interface* device) +mip_cmd_result mip_3dm_load_odometer(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2804,10 +2206,9 @@ mip_cmd_result mip_3dm_load_odometer(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_odometer(struct mip_interface* device) +mip_cmd_result mip_3dm_default_odometer(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2817,8 +2218,7 @@ mip_cmd_result mip_3dm_default_odometer(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_get_event_support_command(microstrain_serializer* serializer, const mip_3dm_get_event_support_command* self) { @@ -2831,60 +2231,7 @@ void extract_mip_3dm_get_event_support_command(microstrain_serializer* serialize } -void insert_mip_3dm_get_event_support_response(microstrain_serializer* serializer, const mip_3dm_get_event_support_response* self) -{ - insert_mip_3dm_get_event_support_command_query(serializer, self->query); - - microstrain_insert_u8(serializer, self->max_instances); - - microstrain_insert_u8(serializer, self->num_entries); - - - for(unsigned int i=0; i < self->num_entries; i++) - insert_mip_3dm_get_event_support_command_info(serializer, &self->entries[i]); - -} -void extract_mip_3dm_get_event_support_response(microstrain_serializer* serializer, mip_3dm_get_event_support_response* self) -{ - extract_mip_3dm_get_event_support_command_query(serializer, &self->query); - - microstrain_extract_u8(serializer, &self->max_instances); - - assert(self->num_entries); - microstrain_extract_count(serializer, &self->num_entries, sizeof(self->entries) / sizeof(self->entries[0])); - - for(unsigned int i=0; i < self->num_entries; i++) - extract_mip_3dm_get_event_support_command_info(serializer, &self->entries[i]); - -} - -void insert_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_query self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, mip_3dm_get_event_support_command_query* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_info* self) -{ - microstrain_insert_u8(serializer, self->type); - - microstrain_insert_u8(serializer, self->count); - -} -void extract_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, mip_3dm_get_event_support_command_info* self) -{ - microstrain_extract_u8(serializer, &self->type); - - microstrain_extract_u8(serializer, &self->count); - -} - -mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_get_event_support_command_query query, uint8_t* max_instances_out, uint8_t* num_entries_out, uint8_t num_entries_out_max, mip_3dm_get_event_support_command_info* entries_out) +mip_cmd_result mip_3dm_get_event_support(mip_interface* device, mip_3dm_get_event_support_command_query query, uint8_t* max_instances_out, uint8_t* num_entries_out, uint8_t num_entries_out_max, mip_3dm_get_event_support_command_info* entries_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2895,8 +2242,7 @@ mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_g assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_SUPPORT, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_EVENT_SUPPORT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_SUPPORT, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_SUPPORT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2915,7 +2261,7 @@ mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_g for(unsigned int i=0; i < *num_entries_out; i++) extract_mip_3dm_get_event_support_command_info(&deserializer, &entries_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -2923,7 +2269,7 @@ mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_g void insert_mip_3dm_event_control_command(microstrain_serializer* serializer, const mip_3dm_event_control_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->instance); if( self->function == MIP_FUNCTION_WRITE ) @@ -2935,7 +2281,7 @@ void insert_mip_3dm_event_control_command(microstrain_serializer* serializer, co void extract_mip_3dm_event_control_command(microstrain_serializer* serializer, mip_3dm_event_control_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->instance); if( self->function == MIP_FUNCTION_WRITE ) @@ -2945,124 +2291,93 @@ void extract_mip_3dm_event_control_command(microstrain_serializer* serializer, m } } -void insert_mip_3dm_event_control_response(microstrain_serializer* serializer, const mip_3dm_event_control_response* self) -{ - microstrain_insert_u8(serializer, self->instance); - - insert_mip_3dm_event_control_command_mode(serializer, self->mode); - -} -void extract_mip_3dm_event_control_response(microstrain_serializer* serializer, mip_3dm_event_control_response* self) -{ - microstrain_extract_u8(serializer, &self->instance); - - extract_mip_3dm_event_control_command_mode(serializer, &self->mode); - -} - -void insert_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, const mip_3dm_event_control_command_mode self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, mip_3dm_event_control_command_mode* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_3dm_write_event_control(struct mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode mode) +mip_cmd_result mip_3dm_write_event_control(mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode mode) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, instance); insert_mip_3dm_event_control_command_mode(&serializer, mode); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_event_control(struct mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode* mode_out) +mip_cmd_result mip_3dm_read_event_control(mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode* mode_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_EVENT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &instance); assert(mode_out); extract_mip_3dm_event_control_command_mode(&deserializer, mode_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_event_control(struct mip_interface* device, uint8_t instance) +mip_cmd_result mip_3dm_save_event_control(mip_interface* device, uint8_t instance) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_event_control(struct mip_interface* device, uint8_t instance) +mip_cmd_result mip_3dm_load_event_control(mip_interface* device, uint8_t instance) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_event_control(struct mip_interface* device, uint8_t instance) +mip_cmd_result mip_3dm_default_event_control(mip_interface* device, uint8_t instance) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_get_event_trigger_status_command(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command* self) { @@ -3076,65 +2391,19 @@ void insert_mip_3dm_get_event_trigger_status_command(microstrain_serializer* ser void extract_mip_3dm_get_event_trigger_status_command(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command* self) { assert(self->requested_count); - microstrain_extract_count(serializer, &self->requested_count, - sizeof(self->requested_instances) / sizeof(self->requested_instances[0])); + microstrain_extract_count(serializer, &self->requested_count, sizeof(self->requested_instances)/sizeof(self->requested_instances[0])); for(unsigned int i=0; i < self->requested_count; i++) microstrain_extract_u8(serializer, &self->requested_instances[i]); } -void insert_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_response* self) -{ - microstrain_insert_u8(serializer, self->count); - - - for(unsigned int i=0; i < self->count; i++) - insert_mip_3dm_get_event_trigger_status_command_entry(serializer, &self->triggers[i]); - -} -void extract_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_response* self) -{ - assert(self->count); - microstrain_extract_count(serializer, &self->count, sizeof(self->triggers) / sizeof(self->triggers[0])); - - for(unsigned int i=0; i < self->count; i++) - extract_mip_3dm_get_event_trigger_status_command_entry(serializer, &self->triggers[i]); - -} - -void insert_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_entry* self) -{ - microstrain_insert_u8(serializer, self->type); - - insert_mip_3dm_get_event_trigger_status_command_status(serializer, self->status); - -} -void extract_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_entry* self) -{ - microstrain_extract_u8(serializer, &self->type); - - extract_mip_3dm_get_event_trigger_status_command_status(serializer, &self->status); - -} - -mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_trigger_status_command_entry* triggers_out) +mip_cmd_result mip_3dm_get_event_trigger_status(mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_trigger_status_command_entry* triggers_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_u8(&serializer, requested_count); assert(requested_instances || (requested_count == 0)); @@ -3144,8 +2413,7 @@ mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, ui assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_STATUS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_EVENT_TRIGGER_STATUS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_STATUS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_TRIGGER_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3159,7 +2427,7 @@ mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, ui for(unsigned int i=0; i < *count_out; i++) extract_mip_3dm_get_event_trigger_status_command_entry(&deserializer, &triggers_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3176,54 +2444,19 @@ void insert_mip_3dm_get_event_action_status_command(microstrain_serializer* seri void extract_mip_3dm_get_event_action_status_command(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command* self) { assert(self->requested_count); - microstrain_extract_count(serializer, &self->requested_count, - sizeof(self->requested_instances) / sizeof(self->requested_instances[0])); + microstrain_extract_count(serializer, &self->requested_count, sizeof(self->requested_instances)/sizeof(self->requested_instances[0])); for(unsigned int i=0; i < self->requested_count; i++) microstrain_extract_u8(serializer, &self->requested_instances[i]); } -void insert_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_response* self) -{ - microstrain_insert_u8(serializer, self->count); - - - for(unsigned int i=0; i < self->count; i++) - insert_mip_3dm_get_event_action_status_command_entry(serializer, &self->actions[i]); - -} -void extract_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, mip_3dm_get_event_action_status_response* self) -{ - assert(self->count); - microstrain_extract_count(serializer, &self->count, sizeof(self->actions) / sizeof(self->actions[0])); - - for(unsigned int i=0; i < self->count; i++) - extract_mip_3dm_get_event_action_status_command_entry(serializer, &self->actions[i]); - -} - -void insert_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command_entry* self) -{ - microstrain_insert_u8(serializer, self->action_type); - - microstrain_insert_u8(serializer, self->trigger_id); - -} -void extract_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command_entry* self) -{ - microstrain_extract_u8(serializer, &self->action_type); - - microstrain_extract_u8(serializer, &self->trigger_id); - -} - -mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_action_status_command_entry* actions_out) +mip_cmd_result mip_3dm_get_event_action_status(mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_action_status_command_entry* actions_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_u8(&serializer, requested_count); assert(requested_instances || (requested_count == 0)); @@ -3233,8 +2466,7 @@ mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uin assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_STATUS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_EVENT_ACTION_STATUS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_STATUS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_ACTION_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3248,7 +2480,7 @@ mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uin for(unsigned int i=0; i < *count_out; i++) extract_mip_3dm_get_event_action_status_command_entry(&deserializer, &actions_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -3256,7 +2488,7 @@ mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uin void insert_mip_3dm_event_trigger_command(microstrain_serializer* serializer, const mip_3dm_event_trigger_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->instance); if( self->function == MIP_FUNCTION_WRITE ) @@ -3283,7 +2515,7 @@ void insert_mip_3dm_event_trigger_command(microstrain_serializer* serializer, co void extract_mip_3dm_event_trigger_command(microstrain_serializer* serializer, mip_3dm_event_trigger_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->instance); if( self->function == MIP_FUNCTION_WRITE ) @@ -3308,187 +2540,14 @@ void extract_mip_3dm_event_trigger_command(microstrain_serializer* serializer, m } } -void insert_mip_3dm_event_trigger_response(microstrain_serializer* serializer, const mip_3dm_event_trigger_response* self) -{ - microstrain_insert_u8(serializer, self->instance); - - insert_mip_3dm_event_trigger_command_type(serializer, self->type); - - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_GPIO ) - { - insert_mip_3dm_event_trigger_command_gpio_params(serializer, &self->parameters.gpio); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_THRESHOLD ) - { - insert_mip_3dm_event_trigger_command_threshold_params(serializer, &self->parameters.threshold); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_COMBINATION ) - { - insert_mip_3dm_event_trigger_command_combination_params(serializer, &self->parameters.combination); - - } -} -void extract_mip_3dm_event_trigger_response(microstrain_serializer* serializer, mip_3dm_event_trigger_response* self) -{ - microstrain_extract_u8(serializer, &self->instance); - - extract_mip_3dm_event_trigger_command_type(serializer, &self->type); - - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_GPIO ) - { - extract_mip_3dm_event_trigger_command_gpio_params(serializer, &self->parameters.gpio); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_THRESHOLD ) - { - extract_mip_3dm_event_trigger_command_threshold_params(serializer, &self->parameters.threshold); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_COMBINATION ) - { - extract_mip_3dm_event_trigger_command_combination_params(serializer, &self->parameters.combination); - - } -} - -void insert_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params* self) -{ - microstrain_insert_u8(serializer, self->pin); - - insert_mip_3dm_event_trigger_command_gpio_params_mode(serializer, self->mode); - -} -void extract_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params* self) -{ - microstrain_extract_u8(serializer, &self->pin); - - extract_mip_3dm_event_trigger_command_gpio_params_mode(serializer, &self->mode); - -} - -void insert_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params* self) -{ - microstrain_insert_u8(serializer, self->desc_set); - - microstrain_insert_u8(serializer, self->field_desc); - - microstrain_insert_u8(serializer, self->param_id); - - insert_mip_3dm_event_trigger_command_threshold_params_type(serializer, self->type); - - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) - { - microstrain_insert_double(serializer, self->low_thres); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) - { - microstrain_insert_double(serializer, self->int_thres); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) - { - microstrain_insert_double(serializer, self->high_thres); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) - { - microstrain_insert_double(serializer, self->interval); - - } -} -void extract_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params* self) -{ - microstrain_extract_u8(serializer, &self->desc_set); - - microstrain_extract_u8(serializer, &self->field_desc); - - microstrain_extract_u8(serializer, &self->param_id); - - extract_mip_3dm_event_trigger_command_threshold_params_type(serializer, &self->type); - - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) - { - microstrain_extract_double(serializer, &self->low_thres); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) - { - microstrain_extract_double(serializer, &self->int_thres); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) - { - microstrain_extract_double(serializer, &self->high_thres); - - } - if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) - { - microstrain_extract_double(serializer, &self->interval); - - } -} - -void insert_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_combination_params* self) -{ - microstrain_insert_u16(serializer, self->logic_table); - - for(unsigned int i=0; i < 4; i++) - microstrain_insert_u8(serializer, self->input_triggers[i]); - -} -void extract_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_combination_params* self) -{ - microstrain_extract_u16(serializer, &self->logic_table); - - for(unsigned int i=0; i < 4; i++) - microstrain_extract_u8(serializer, &self->input_triggers[i]); - -} - -void insert_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_type self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_type* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_3dm_write_event_trigger(struct mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type type, const mip_3dm_event_trigger_command_parameters* parameters) +mip_cmd_result mip_3dm_write_event_trigger(mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type type, const mip_3dm_event_trigger_command_parameters* parameters) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, instance); insert_mip_3dm_event_trigger_command_type(&serializer, type); @@ -3510,30 +2569,28 @@ mip_cmd_result mip_3dm_write_event_trigger(struct mip_interface* device, uint8_t } assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type* type_out, mip_3dm_event_trigger_command_parameters* parameters_out) +mip_cmd_result mip_3dm_read_event_trigger(mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type* type_out, mip_3dm_event_trigger_command_parameters* parameters_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &instance); assert(type_out); @@ -3554,60 +2611,57 @@ mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t extract_mip_3dm_event_trigger_command_combination_params(&deserializer, ¶meters_out->combination); } - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_event_trigger(struct mip_interface* device, uint8_t instance) +mip_cmd_result mip_3dm_save_event_trigger(mip_interface* device, uint8_t instance) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_event_trigger(struct mip_interface* device, uint8_t instance) +mip_cmd_result mip_3dm_load_event_trigger(mip_interface* device, uint8_t instance) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_event_trigger(struct mip_interface* device, uint8_t instance) +mip_cmd_result mip_3dm_default_event_trigger(mip_interface* device, uint8_t instance) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_event_action_command(microstrain_serializer* serializer, const mip_3dm_event_action_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->instance); if( self->function == MIP_FUNCTION_WRITE ) @@ -3631,7 +2685,7 @@ void insert_mip_3dm_event_action_command(microstrain_serializer* serializer, con void extract_mip_3dm_event_action_command(microstrain_serializer* serializer, mip_3dm_event_action_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->instance); if( self->function == MIP_FUNCTION_WRITE ) @@ -3653,119 +2707,16 @@ void extract_mip_3dm_event_action_command(microstrain_serializer* serializer, mi } } -void insert_mip_3dm_event_action_response(microstrain_serializer* serializer, const mip_3dm_event_action_response* self) -{ - microstrain_insert_u8(serializer, self->instance); - - microstrain_insert_u8(serializer, self->trigger); - - insert_mip_3dm_event_action_command_type(serializer, self->type); - - if( self->type == MIP_3DM_EVENT_ACTION_COMMAND_TYPE_GPIO ) - { - insert_mip_3dm_event_action_command_gpio_params(serializer, &self->parameters.gpio); - - } - if( self->type == MIP_3DM_EVENT_ACTION_COMMAND_TYPE_MESSAGE ) - { - insert_mip_3dm_event_action_command_message_params(serializer, &self->parameters.message); - - } -} -void extract_mip_3dm_event_action_response(microstrain_serializer* serializer, mip_3dm_event_action_response* self) -{ - microstrain_extract_u8(serializer, &self->instance); - - microstrain_extract_u8(serializer, &self->trigger); - - extract_mip_3dm_event_action_command_type(serializer, &self->type); - - if( self->type == MIP_3DM_EVENT_ACTION_COMMAND_TYPE_GPIO ) - { - extract_mip_3dm_event_action_command_gpio_params(serializer, &self->parameters.gpio); - - } - if( self->type == MIP_3DM_EVENT_ACTION_COMMAND_TYPE_MESSAGE ) - { - extract_mip_3dm_event_action_command_message_params(serializer, &self->parameters.message); - - } -} - -void insert_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params* self) -{ - microstrain_insert_u8(serializer, self->pin); - - insert_mip_3dm_event_action_command_gpio_params_mode(serializer, self->mode); - -} -void extract_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params* self) -{ - microstrain_extract_u8(serializer, &self->pin); - - extract_mip_3dm_event_action_command_gpio_params_mode(serializer, &self->mode); - -} - -void insert_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_message_params* self) -{ - microstrain_insert_u8(serializer, self->desc_set); - - microstrain_insert_u16(serializer, self->decimation); - - microstrain_insert_u8(serializer, self->num_fields); - - - for(unsigned int i=0; i < self->num_fields; i++) - microstrain_insert_u8(serializer, self->descriptors[i]); - -} -void extract_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, mip_3dm_event_action_command_message_params* self) -{ - microstrain_extract_u8(serializer, &self->desc_set); - - microstrain_extract_u16(serializer, &self->decimation); - - assert(self->num_fields); - microstrain_extract_count(serializer, &self->num_fields, sizeof(self->descriptors) / sizeof(self->descriptors[0])); - - for(unsigned int i=0; i < self->num_fields; i++) - microstrain_extract_u8(serializer, &self->descriptors[i]); - -} - -void insert_mip_3dm_event_action_command_type(microstrain_serializer* serializer, const mip_3dm_event_action_command_type self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_3dm_event_action_command_type(microstrain_serializer* serializer, mip_3dm_event_action_command_type* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_3dm_write_event_action(struct mip_interface* device, uint8_t instance, uint8_t trigger, mip_3dm_event_action_command_type type, const mip_3dm_event_action_command_parameters* parameters) +mip_cmd_result mip_3dm_write_event_action(mip_interface* device, uint8_t instance, uint8_t trigger, mip_3dm_event_action_command_type type, const mip_3dm_event_action_command_parameters* parameters) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, instance); - + microstrain_insert_u8(&serializer, trigger); insert_mip_3dm_event_action_command_type(&serializer, type); @@ -3782,30 +2733,28 @@ mip_cmd_result mip_3dm_write_event_action(struct mip_interface* device, uint8_t } assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t instance, uint8_t* trigger_out, mip_3dm_event_action_command_type* type_out, mip_3dm_event_action_command_parameters* parameters_out) +mip_cmd_result mip_3dm_read_event_action(mip_interface* device, uint8_t instance, uint8_t* trigger_out, mip_3dm_event_action_command_type* type_out, mip_3dm_event_action_command_parameters* parameters_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_EVENT_ACTION_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_EVENT_ACTION_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &instance); assert(trigger_out); @@ -3824,55 +2773,52 @@ mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t i extract_mip_3dm_event_action_command_message_params(&deserializer, ¶meters_out->message); } - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_event_action(struct mip_interface* device, uint8_t instance) +mip_cmd_result mip_3dm_save_event_action(mip_interface* device, uint8_t instance) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_event_action(struct mip_interface* device, uint8_t instance) +mip_cmd_result mip_3dm_load_event_action(mip_interface* device, uint8_t instance) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_event_action(struct mip_interface* device, uint8_t instance) +mip_cmd_result mip_3dm_default_event_action(mip_interface* device, uint8_t instance) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, instance); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_ACTION_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_accel_bias_command(microstrain_serializer* serializer, const mip_3dm_accel_bias_command* self) { @@ -3880,8 +2826,7 @@ void insert_mip_3dm_accel_bias_command(microstrain_serializer* serializer, const if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias[i]); + insert_mip_vector3f(serializer, self->bias); } } @@ -3891,26 +2836,12 @@ void extract_mip_3dm_accel_bias_command(microstrain_serializer* serializer, mip_ if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias[i]); + extract_mip_vector3f(serializer, self->bias); } } -void insert_mip_3dm_accel_bias_response(microstrain_serializer* serializer, const mip_3dm_accel_bias_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias[i]); - -} -void extract_mip_3dm_accel_bias_response(microstrain_serializer* serializer, mip_3dm_accel_bias_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias[i]); - -} - -mip_cmd_result mip_3dm_write_accel_bias(struct mip_interface* device, const float* bias) +mip_cmd_result mip_3dm_write_accel_bias(mip_interface* device, const float* bias) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3918,16 +2849,15 @@ mip_cmd_result mip_3dm_write_accel_bias(struct mip_interface* device, const floa insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(bias || (3 == 0)); + assert(bias); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, bias[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias_out) +mip_cmd_result mip_3dm_read_accel_bias(mip_interface* device, float* bias_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3938,24 +2868,23 @@ mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_ACCEL_BIAS_VECTOR, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_ACCEL_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(bias_out || (3 == 0)); + assert(bias_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &bias_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_accel_bias(struct mip_interface* device) +mip_cmd_result mip_3dm_save_accel_bias(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3965,10 +2894,9 @@ mip_cmd_result mip_3dm_save_accel_bias(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_accel_bias(struct mip_interface* device) +mip_cmd_result mip_3dm_load_accel_bias(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3978,10 +2906,9 @@ mip_cmd_result mip_3dm_load_accel_bias(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_accel_bias(struct mip_interface* device) +mip_cmd_result mip_3dm_default_accel_bias(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3991,8 +2918,7 @@ mip_cmd_result mip_3dm_default_accel_bias(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ACCEL_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, const mip_3dm_gyro_bias_command* self) { @@ -4000,8 +2926,7 @@ void insert_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, const if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias[i]); + insert_mip_vector3f(serializer, self->bias); } } @@ -4011,26 +2936,12 @@ void extract_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, mip_3 if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias[i]); + extract_mip_vector3f(serializer, self->bias); } } -void insert_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_gyro_bias_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias[i]); - -} -void extract_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_gyro_bias_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias[i]); - -} - -mip_cmd_result mip_3dm_write_gyro_bias(struct mip_interface* device, const float* bias) +mip_cmd_result mip_3dm_write_gyro_bias(mip_interface* device, const float* bias) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4038,16 +2949,15 @@ mip_cmd_result mip_3dm_write_gyro_bias(struct mip_interface* device, const float insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(bias || (3 == 0)); + assert(bias); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, bias[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_out) +mip_cmd_result mip_3dm_read_gyro_bias(mip_interface* device, float* bias_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4058,24 +2968,23 @@ mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_ assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_GYRO_BIAS_VECTOR, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(bias_out || (3 == 0)); + assert(bias_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &bias_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_gyro_bias(struct mip_interface* device) +mip_cmd_result mip_3dm_save_gyro_bias(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4085,10 +2994,9 @@ mip_cmd_result mip_3dm_save_gyro_bias(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_gyro_bias(struct mip_interface* device) +mip_cmd_result mip_3dm_load_gyro_bias(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4098,10 +3006,9 @@ mip_cmd_result mip_3dm_load_gyro_bias(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_gyro_bias(struct mip_interface* device) +mip_cmd_result mip_3dm_default_gyro_bias(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4111,8 +3018,7 @@ mip_cmd_result mip_3dm_default_gyro_bias(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_capture_gyro_bias_command(microstrain_serializer* serializer, const mip_3dm_capture_gyro_bias_command* self) { @@ -4125,43 +3031,29 @@ void extract_mip_3dm_capture_gyro_bias_command(microstrain_serializer* serialize } -void insert_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_capture_gyro_bias_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias[i]); - -} -void extract_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_capture_gyro_bias_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias[i]); - -} - -mip_cmd_result mip_3dm_capture_gyro_bias(struct mip_interface* device, uint16_t averaging_time_ms, float* bias_out) +mip_cmd_result mip_3dm_capture_gyro_bias(mip_interface* device, uint16_t averaging_time_ms, float* bias_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_u16(&serializer, averaging_time_ms); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CAPTURE_GYRO_BIAS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_GYRO_BIAS_VECTOR, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CAPTURE_GYRO_BIAS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(bias_out || (3 == 0)); + assert(bias_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &bias_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -4172,8 +3064,7 @@ void insert_mip_3dm_mag_hard_iron_offset_command(microstrain_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset[i]); + insert_mip_vector3f(serializer, self->offset); } } @@ -4183,26 +3074,12 @@ void extract_mip_3dm_mag_hard_iron_offset_command(microstrain_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset[i]); + extract_mip_vector3f(serializer, self->offset); } } -void insert_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, const mip_3dm_mag_hard_iron_offset_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset[i]); - -} -void extract_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, mip_3dm_mag_hard_iron_offset_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset[i]); - -} - -mip_cmd_result mip_3dm_write_mag_hard_iron_offset(struct mip_interface* device, const float* offset) +mip_cmd_result mip_3dm_write_mag_hard_iron_offset(mip_interface* device, const float* offset) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4210,16 +3087,15 @@ mip_cmd_result mip_3dm_write_mag_hard_iron_offset(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(offset || (3 == 0)); + assert(offset); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, offset[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, float* offset_out) +mip_cmd_result mip_3dm_read_mag_hard_iron_offset(mip_interface* device, float* offset_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4230,24 +3106,23 @@ mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, f assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(offset_out || (3 == 0)); + assert(offset_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &offset_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_mag_hard_iron_offset(struct mip_interface* device) +mip_cmd_result mip_3dm_save_mag_hard_iron_offset(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4257,10 +3132,9 @@ mip_cmd_result mip_3dm_save_mag_hard_iron_offset(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_mag_hard_iron_offset(struct mip_interface* device) +mip_cmd_result mip_3dm_load_mag_hard_iron_offset(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4270,10 +3144,9 @@ mip_cmd_result mip_3dm_load_mag_hard_iron_offset(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_mag_hard_iron_offset(struct mip_interface* device) +mip_cmd_result mip_3dm_default_mag_hard_iron_offset(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4283,8 +3156,7 @@ mip_cmd_result mip_3dm_default_mag_hard_iron_offset(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_HARD_IRON_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_command* self) { @@ -4292,8 +3164,7 @@ void insert_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->offset[i]); + insert_mip_matrix3f(serializer, self->offset); } } @@ -4303,26 +3174,12 @@ void extract_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->offset[i]); + extract_mip_matrix3f(serializer, self->offset); } } -void insert_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_response* self) -{ - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->offset[i]); - -} -void extract_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, mip_3dm_mag_soft_iron_matrix_response* self) -{ - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->offset[i]); - -} - -mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(struct mip_interface* device, const float* offset) +mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(mip_interface* device, const float* offset) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4330,16 +3187,15 @@ mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(offset || (9 == 0)); + assert(offset); for(unsigned int i=0; i < 9; i++) microstrain_insert_float(&serializer, offset[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, float* offset_out) +mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(mip_interface* device, float* offset_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4350,24 +3206,23 @@ mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, f assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(offset_out || (9 == 0)); + assert(offset_out); for(unsigned int i=0; i < 9; i++) microstrain_extract_float(&deserializer, &offset_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_mag_soft_iron_matrix(struct mip_interface* device) +mip_cmd_result mip_3dm_save_mag_soft_iron_matrix(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4377,10 +3232,9 @@ mip_cmd_result mip_3dm_save_mag_soft_iron_matrix(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_mag_soft_iron_matrix(struct mip_interface* device) +mip_cmd_result mip_3dm_load_mag_soft_iron_matrix(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4390,10 +3244,9 @@ mip_cmd_result mip_3dm_load_mag_soft_iron_matrix(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(struct mip_interface* device) +mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4403,8 +3256,7 @@ mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SOFT_IRON_MATRIX, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_coning_sculling_enable_command(microstrain_serializer* serializer, const mip_3dm_coning_sculling_enable_command* self) { @@ -4427,33 +3279,21 @@ void extract_mip_3dm_coning_sculling_enable_command(microstrain_serializer* seri } } -void insert_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, const mip_3dm_coning_sculling_enable_response* self) -{ - microstrain_insert_bool(serializer, self->enable); - -} -void extract_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, mip_3dm_coning_sculling_enable_response* self) -{ - microstrain_extract_bool(serializer, &self->enable); - -} - -mip_cmd_result mip_3dm_write_coning_sculling_enable(struct mip_interface* device, bool enable) +mip_cmd_result mip_3dm_write_coning_sculling_enable(mip_interface* device, bool enable) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_bool(&serializer, enable); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, bool* enable_out) +mip_cmd_result mip_3dm_read_coning_sculling_enable(mip_interface* device, bool* enable_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4464,8 +3304,7 @@ mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4475,12 +3314,12 @@ mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, assert(enable_out); microstrain_extract_bool(&deserializer, enable_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_coning_sculling_enable(struct mip_interface* device) +mip_cmd_result mip_3dm_save_coning_sculling_enable(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4490,10 +3329,9 @@ mip_cmd_result mip_3dm_save_coning_sculling_enable(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_coning_sculling_enable(struct mip_interface* device) +mip_cmd_result mip_3dm_load_coning_sculling_enable(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4503,10 +3341,9 @@ mip_cmd_result mip_3dm_load_coning_sculling_enable(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_coning_sculling_enable(struct mip_interface* device) +mip_cmd_result mip_3dm_default_coning_sculling_enable(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4516,8 +3353,7 @@ mip_cmd_result mip_3dm_default_coning_sculling_enable(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_command* self) { @@ -4526,9 +3362,9 @@ void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_seriali if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_float(serializer, self->roll); - + microstrain_insert_float(serializer, self->pitch); - + microstrain_insert_float(serializer, self->yaw); } @@ -4540,53 +3376,33 @@ void extract_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_serial if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_float(serializer, &self->roll); - + microstrain_extract_float(serializer, &self->pitch); - + microstrain_extract_float(serializer, &self->yaw); } } -void insert_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_response* self) -{ - microstrain_insert_float(serializer, self->roll); - - microstrain_insert_float(serializer, self->pitch); - - microstrain_insert_float(serializer, self->yaw); - -} -void extract_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_response* self) -{ - microstrain_extract_float(serializer, &self->roll); - - microstrain_extract_float(serializer, &self->pitch); - - microstrain_extract_float(serializer, &self->yaw); - -} - -mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_euler(struct mip_interface* device, float roll, float pitch, float yaw) +mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_euler(mip_interface* device, float roll, float pitch, float yaw) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_float(&serializer, roll); - + microstrain_insert_float(&serializer, pitch); - + microstrain_insert_float(&serializer, yaw); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out) +mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4597,8 +3413,7 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interfac assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4614,12 +3429,12 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interfac assert(yaw_out); microstrain_extract_float(&deserializer, yaw_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_euler(struct mip_interface* device) +mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_euler(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4629,10 +3444,9 @@ mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_euler(struct mip_interfac assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_euler(struct mip_interface* device) +mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_euler(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4642,10 +3456,9 @@ mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_euler(struct mip_interfac assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(struct mip_interface* device) +mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4655,8 +3468,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(struct mip_inter assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_command* self) { @@ -4664,8 +3476,7 @@ void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_se if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 4; i++) - microstrain_insert_float(serializer, self->q[i]); + insert_mip_quatf(serializer, self->q); } } @@ -4675,26 +3486,12 @@ void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_s if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 4; i++) - microstrain_extract_float(serializer, &self->q[i]); + extract_mip_quatf(serializer, self->q); } } -void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) -{ - for(unsigned int i=0; i < 4; i++) - microstrain_insert_float(serializer, self->q[i]); - -} -void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) -{ - for(unsigned int i=0; i < 4; i++) - microstrain_extract_float(serializer, &self->q[i]); - -} - -mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(struct mip_interface* device, const float* q) +mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(mip_interface* device, const float* q) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4702,16 +3499,15 @@ mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(struct mip_in insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(q || (4 == 0)); + assert(q); for(unsigned int i=0; i < 4; i++) microstrain_insert_float(&serializer, q[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_interface* device, float* q_out) +mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(mip_interface* device, float* q_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4722,24 +3518,23 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_int assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(q_out || (4 == 0)); + assert(q_out); for(unsigned int i=0; i < 4; i++) microstrain_extract_float(&deserializer, &q_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_quaternion(struct mip_interface* device) +mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_quaternion(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4749,10 +3544,9 @@ mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_quaternion(struct mip_int assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_quaternion(struct mip_interface* device) +mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_quaternion(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4762,10 +3556,9 @@ mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_quaternion(struct mip_int assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(struct mip_interface* device) +mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4775,8 +3568,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(struct mip_ assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_command* self) { @@ -4784,8 +3576,7 @@ void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serialize if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->dcm[i]); + insert_mip_matrix3f(serializer, self->dcm); } } @@ -4795,26 +3586,12 @@ void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serializ if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->dcm[i]); + extract_mip_matrix3f(serializer, self->dcm); } } -void insert_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_response* self) -{ - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->dcm[i]); - -} -void extract_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_response* self) -{ - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->dcm[i]); - -} - -mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(struct mip_interface* device, const float* dcm) +mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(mip_interface* device, const float* dcm) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4822,16 +3599,15 @@ mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(struct mip_interface insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(dcm || (9 == 0)); + assert(dcm); for(unsigned int i=0; i < 9; i++) microstrain_insert_float(&serializer, dcm[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* device, float* dcm_out) +mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(mip_interface* device, float* dcm_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4842,24 +3618,23 @@ mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(dcm_out || (9 == 0)); + assert(dcm_out); for(unsigned int i=0; i < 9; i++) microstrain_extract_float(&deserializer, &dcm_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_dcm(struct mip_interface* device) +mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_dcm(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4869,10 +3644,9 @@ mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_dcm(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_dcm(struct mip_interface* device) +mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_dcm(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4882,10 +3656,9 @@ mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_dcm(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(struct mip_interface* device) +mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4895,8 +3668,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(struct mip_interfa assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_complementary_filter_command(microstrain_serializer* serializer, const mip_3dm_complementary_filter_command* self) { @@ -4905,11 +3677,11 @@ void insert_mip_3dm_complementary_filter_command(microstrain_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_bool(serializer, self->pitch_roll_enable); - + microstrain_insert_bool(serializer, self->heading_enable); - + microstrain_insert_float(serializer, self->pitch_roll_time_constant); - + microstrain_insert_float(serializer, self->heading_time_constant); } @@ -4921,61 +3693,37 @@ void extract_mip_3dm_complementary_filter_command(microstrain_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_bool(serializer, &self->pitch_roll_enable); - + microstrain_extract_bool(serializer, &self->heading_enable); - + microstrain_extract_float(serializer, &self->pitch_roll_time_constant); - + microstrain_extract_float(serializer, &self->heading_time_constant); } } -void insert_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, const mip_3dm_complementary_filter_response* self) -{ - microstrain_insert_bool(serializer, self->pitch_roll_enable); - - microstrain_insert_bool(serializer, self->heading_enable); - - microstrain_insert_float(serializer, self->pitch_roll_time_constant); - - microstrain_insert_float(serializer, self->heading_time_constant); - -} -void extract_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, mip_3dm_complementary_filter_response* self) -{ - microstrain_extract_bool(serializer, &self->pitch_roll_enable); - - microstrain_extract_bool(serializer, &self->heading_enable); - - microstrain_extract_float(serializer, &self->pitch_roll_time_constant); - - microstrain_extract_float(serializer, &self->heading_time_constant); - -} - -mip_cmd_result mip_3dm_write_complementary_filter(struct mip_interface* device, bool pitch_roll_enable, bool heading_enable, float pitch_roll_time_constant, float heading_time_constant) +mip_cmd_result mip_3dm_write_complementary_filter(mip_interface* device, bool pitch_roll_enable, bool heading_enable, float pitch_roll_time_constant, float heading_time_constant) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_bool(&serializer, pitch_roll_enable); - + microstrain_insert_bool(&serializer, heading_enable); - + microstrain_insert_float(&serializer, pitch_roll_time_constant); - + microstrain_insert_float(&serializer, heading_time_constant); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, bool* pitch_roll_enable_out, bool* heading_enable_out, float* pitch_roll_time_constant_out, float* heading_time_constant_out) +mip_cmd_result mip_3dm_read_complementary_filter(mip_interface* device, bool* pitch_roll_enable_out, bool* heading_enable_out, float* pitch_roll_time_constant_out, float* heading_time_constant_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4986,8 +3734,7 @@ mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, b assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_LEGACY_COMP_FILTER, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_LEGACY_COMP_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5006,12 +3753,12 @@ mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, b assert(heading_time_constant_out); microstrain_extract_float(&deserializer, heading_time_constant_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_complementary_filter(struct mip_interface* device) +mip_cmd_result mip_3dm_save_complementary_filter(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5021,10 +3768,9 @@ mip_cmd_result mip_3dm_save_complementary_filter(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_complementary_filter(struct mip_interface* device) +mip_cmd_result mip_3dm_load_complementary_filter(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5034,10 +3780,9 @@ mip_cmd_result mip_3dm_load_complementary_filter(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_complementary_filter(struct mip_interface* device) +mip_cmd_result mip_3dm_default_complementary_filter(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5047,8 +3792,7 @@ mip_cmd_result mip_3dm_default_complementary_filter(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LEGACY_COMP_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_sensor_range_command(microstrain_serializer* serializer, const mip_3dm_sensor_range_command* self) { @@ -5075,22 +3819,7 @@ void extract_mip_3dm_sensor_range_command(microstrain_serializer* serializer, mi } } -void insert_mip_3dm_sensor_range_response(microstrain_serializer* serializer, const mip_3dm_sensor_range_response* self) -{ - insert_mip_sensor_range_type(serializer, self->sensor); - - microstrain_insert_u8(serializer, self->setting); - -} -void extract_mip_3dm_sensor_range_response(microstrain_serializer* serializer, mip_3dm_sensor_range_response* self) -{ - extract_mip_sensor_range_type(serializer, &self->sensor); - - microstrain_extract_u8(serializer, &self->setting); - -} - -mip_cmd_result mip_3dm_write_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t setting) +mip_cmd_result mip_3dm_write_sensor_range(mip_interface* device, mip_sensor_range_type sensor, uint8_t setting) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5099,15 +3828,14 @@ mip_cmd_result mip_3dm_write_sensor_range(struct mip_interface* device, mip_sens insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_sensor_range_type(&serializer, sensor); - + microstrain_insert_u8(&serializer, setting); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t* setting_out) +mip_cmd_result mip_3dm_read_sensor_range(mip_interface* device, mip_sensor_range_type sensor, uint8_t* setting_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5120,8 +3848,7 @@ mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_senso assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_SENSOR_RANGE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_SENSOR_RANGE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5133,12 +3860,12 @@ mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_senso assert(setting_out); microstrain_extract_u8(&deserializer, setting_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor) +mip_cmd_result mip_3dm_save_sensor_range(mip_interface* device, mip_sensor_range_type sensor) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5150,10 +3877,9 @@ mip_cmd_result mip_3dm_save_sensor_range(struct mip_interface* device, mip_senso assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor) +mip_cmd_result mip_3dm_load_sensor_range(mip_interface* device, mip_sensor_range_type sensor) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5165,10 +3891,9 @@ mip_cmd_result mip_3dm_load_sensor_range(struct mip_interface* device, mip_senso assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor) +mip_cmd_result mip_3dm_default_sensor_range(mip_interface* device, mip_sensor_range_type sensor) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5180,8 +3905,7 @@ mip_cmd_result mip_3dm_default_sensor_range(struct mip_interface* device, mip_se assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command* self) { @@ -5194,45 +3918,7 @@ void extract_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* se } -void insert_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_response* self) -{ - insert_mip_sensor_range_type(serializer, self->sensor); - - microstrain_insert_u8(serializer, self->num_ranges); - - - for(unsigned int i=0; i < self->num_ranges; i++) - insert_mip_3dm_calibrated_sensor_ranges_command_entry(serializer, &self->ranges[i]); - -} -void extract_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_response* self) -{ - extract_mip_sensor_range_type(serializer, &self->sensor); - - assert(self->num_ranges); - microstrain_extract_count(serializer, &self->num_ranges, sizeof(self->ranges) / sizeof(self->ranges[0])); - - for(unsigned int i=0; i < self->num_ranges; i++) - extract_mip_3dm_calibrated_sensor_ranges_command_entry(serializer, &self->ranges[i]); - -} - -void insert_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command_entry* self) -{ - microstrain_insert_u8(serializer, self->setting); - - microstrain_insert_float(serializer, self->range); - -} -void extract_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command_entry* self) -{ - microstrain_extract_u8(serializer, &self->setting); - - microstrain_extract_float(serializer, &self->range); - -} - -mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t* num_ranges_out, uint8_t num_ranges_out_max, mip_3dm_calibrated_sensor_ranges_command_entry* ranges_out) +mip_cmd_result mip_3dm_calibrated_sensor_ranges(mip_interface* device, mip_sensor_range_type sensor, uint8_t* num_ranges_out, uint8_t num_ranges_out_max, mip_3dm_calibrated_sensor_ranges_command_entry* ranges_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5243,8 +3929,7 @@ mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mi assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CALIBRATED_RANGES, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_CALIBRATED_RANGES, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CALIBRATED_RANGES, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_CALIBRATED_RANGES, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5260,7 +3945,7 @@ mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mi for(unsigned int i=0; i < *num_ranges_out; i++) extract_mip_3dm_calibrated_sensor_ranges_command_entry(&deserializer, &ranges_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -5268,17 +3953,17 @@ mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mi void insert_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, const mip_3dm_lowpass_filter_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->desc_set); - + microstrain_insert_u8(serializer, self->field_desc); if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_bool(serializer, self->enable); - + microstrain_insert_bool(serializer, self->manual); - + microstrain_insert_float(serializer, self->frequency); } @@ -5286,97 +3971,68 @@ void insert_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, c void extract_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, mip_3dm_lowpass_filter_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->desc_set); - + microstrain_extract_u8(serializer, &self->field_desc); if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_bool(serializer, &self->enable); - + microstrain_extract_bool(serializer, &self->manual); - + microstrain_extract_float(serializer, &self->frequency); } } -void insert_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_lowpass_filter_response* self) -{ - microstrain_insert_u8(serializer, self->desc_set); - - microstrain_insert_u8(serializer, self->field_desc); - - microstrain_insert_bool(serializer, self->enable); - - microstrain_insert_bool(serializer, self->manual); - - microstrain_insert_float(serializer, self->frequency); - -} -void extract_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_lowpass_filter_response* self) -{ - microstrain_extract_u8(serializer, &self->desc_set); - - microstrain_extract_u8(serializer, &self->field_desc); - - microstrain_extract_bool(serializer, &self->enable); - - microstrain_extract_bool(serializer, &self->manual); - - microstrain_extract_float(serializer, &self->frequency); - -} - -mip_cmd_result mip_3dm_write_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool enable, bool manual, float frequency) +mip_cmd_result mip_3dm_write_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool enable, bool manual, float frequency) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, desc_set); - + microstrain_insert_u8(&serializer, field_desc); - + microstrain_insert_bool(&serializer, enable); - + microstrain_insert_bool(&serializer, manual); - + microstrain_insert_float(&serializer, frequency); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_read_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool* enable_out, bool* manual_out, float* frequency_out) +mip_cmd_result mip_3dm_read_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool* enable_out, bool* manual_out, float* frequency_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, desc_set); - + microstrain_insert_u8(&serializer, field_desc); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_3DM_LOWPASS_FILTER, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_3DM_LOWPASS_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &desc_set); - + microstrain_extract_u8(&deserializer, &field_desc); assert(enable_out); @@ -5388,61 +4044,58 @@ mip_cmd_result mip_3dm_read_lowpass_filter(struct mip_interface* device, uint8_t assert(frequency_out); microstrain_extract_float(&deserializer, frequency_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_3dm_save_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) +mip_cmd_result mip_3dm_save_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, desc_set); - + microstrain_insert_u8(&serializer, field_desc); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_load_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) +mip_cmd_result mip_3dm_load_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, desc_set); - + microstrain_insert_u8(&serializer, field_desc); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_3dm_default_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc) +mip_cmd_result mip_3dm_default_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, desc_set); - + microstrain_insert_u8(&serializer, field_desc); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_LOWPASS_FILTER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } #ifdef __cplusplus diff --git a/src/c/mip/definitions/commands_3dm.h b/src/c/mip/definitions/commands_3dm.h index 467678aba..d004ba10a 100644 --- a/src/c/mip/definitions/commands_3dm.h +++ b/src/c/mip/definitions/commands_3dm.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,8 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipCommands_c MIP Commands [C] @@ -144,23 +143,52 @@ enum // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -typedef uint8_t mip_nmea_message_message_id; -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_GGA = 1; ///< GPS System Fix Data. Source can be the Filter or GNSS1/2 datasets. -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_GLL = 2; ///< Geographic Position Lat/Lon. Source can be the Filter or GNSS1/2 datasets. -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_GSV = 3; ///< GNSS Satellites in View. Source must be either GNSS1 or GNSS2 datasets. The talker ID must be set to IGNORED. -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_RMC = 4; ///< Recommended Minimum Specific GNSS Data. Source can be the Filter or GNSS1/2 datasets. -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_VTG = 5; ///< Course over Ground. Source can be the Filter or GNSS1/2 datasets. -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_HDT = 6; ///< Heading, True. Source can be the Filter or GNSS1/2 datasets. -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_ZDA = 7; ///< Time & Date. Source must be the GNSS1 or GNSS2 datasets. -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_PKRA = 129; ///< Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. -static const mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_PKRR = 130; ///< Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. - -typedef uint8_t mip_nmea_message_talker_id; -static const mip_nmea_message_talker_id MIP_NMEA_MESSAGE_TALKER_ID_IGNORED = 0; ///< Talker ID cannot be changed. -static const mip_nmea_message_talker_id MIP_NMEA_MESSAGE_TALKER_ID_GNSS = 1; ///< NMEA message will be produced with talker id "GN". -static const mip_nmea_message_talker_id MIP_NMEA_MESSAGE_TALKER_ID_GPS = 2; ///< NMEA message will be produced with talker id "GP". -static const mip_nmea_message_talker_id MIP_NMEA_MESSAGE_TALKER_ID_GALILEO = 3; ///< NMEA message will be produced with talker id "GA". -static const mip_nmea_message_talker_id MIP_NMEA_MESSAGE_TALKER_ID_GLONASS = 4; ///< NMEA message will be produced with talker id "GL". +enum mip_nmea_message_message_id +{ + MIP_NMEA_MESSAGE_MESSAGE_ID_GGA = 1, ///< GPS System Fix Data. Source can be the Filter or GNSS1/2 datasets. + MIP_NMEA_MESSAGE_MESSAGE_ID_GLL = 2, ///< Geographic Position Lat/Lon. Source can be the Filter or GNSS1/2 datasets. + MIP_NMEA_MESSAGE_MESSAGE_ID_GSV = 3, ///< GNSS Satellites in View. Source must be either GNSS1 or GNSS2 datasets. The talker ID must be set to IGNORED. + MIP_NMEA_MESSAGE_MESSAGE_ID_RMC = 4, ///< Recommended Minimum Specific GNSS Data. Source can be the Filter or GNSS1/2 datasets. + MIP_NMEA_MESSAGE_MESSAGE_ID_VTG = 5, ///< Course over Ground. Source can be the Filter or GNSS1/2 datasets. + MIP_NMEA_MESSAGE_MESSAGE_ID_HDT = 6, ///< Heading, True. Source can be the Filter or GNSS1/2 datasets. + MIP_NMEA_MESSAGE_MESSAGE_ID_ZDA = 7, ///< Time & Date. Source must be the GNSS1 or GNSS2 datasets. + MIP_NMEA_MESSAGE_MESSAGE_ID_PKRA = 129, ///< Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. + MIP_NMEA_MESSAGE_MESSAGE_ID_PKRR = 130, ///< Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. +}; +typedef enum mip_nmea_message_message_id mip_nmea_message_message_id; + +inline void insert_mip_nmea_message_message_id(microstrain_serializer* serializer, const mip_nmea_message_message_id self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_nmea_message_message_id(microstrain_serializer* serializer, mip_nmea_message_message_id* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + +enum mip_nmea_message_talker_id +{ + MIP_NMEA_MESSAGE_TALKER_ID_IGNORED = 0, ///< Talker ID cannot be changed. + MIP_NMEA_MESSAGE_TALKER_ID_GNSS = 1, ///< NMEA message will be produced with talker id "GN". + MIP_NMEA_MESSAGE_TALKER_ID_GPS = 2, ///< NMEA message will be produced with talker id "GP". + MIP_NMEA_MESSAGE_TALKER_ID_GALILEO = 3, ///< NMEA message will be produced with talker id "GA". + MIP_NMEA_MESSAGE_TALKER_ID_GLONASS = 4, ///< NMEA message will be produced with talker id "GL". +}; +typedef enum mip_nmea_message_talker_id mip_nmea_message_talker_id; + +inline void insert_mip_nmea_message_talker_id(microstrain_serializer* serializer, const mip_nmea_message_talker_id self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_nmea_message_talker_id(microstrain_serializer* serializer, mip_nmea_message_talker_id* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_nmea_message { @@ -168,27 +196,32 @@ struct mip_nmea_message mip_nmea_message_talker_id talker_id; ///< NMEA talker ID. Ignored for proprietary sentences. uint8_t source_desc_set; ///< Data descriptor set where the data will be sourced. Available options depend on the sentence. uint16_t decimation; ///< Decimation from the base rate for source_desc_set. Frequency is limited to 10 Hz or the base rate, whichever is lower. Must be 0 when polling. - }; typedef struct mip_nmea_message mip_nmea_message; + void insert_mip_nmea_message(microstrain_serializer* serializer, const mip_nmea_message* self); void extract_mip_nmea_message(microstrain_serializer* serializer, mip_nmea_message* self); -void insert_mip_nmea_message_message_id(microstrain_serializer* serializer, const mip_nmea_message_message_id self); -void extract_mip_nmea_message_message_id(microstrain_serializer* serializer, mip_nmea_message_message_id* self); - -void insert_mip_nmea_message_talker_id(microstrain_serializer* serializer, const mip_nmea_message_talker_id self); -void extract_mip_nmea_message_talker_id(microstrain_serializer* serializer, mip_nmea_message_talker_id* self); - -typedef uint8_t mip_sensor_range_type; -static const mip_sensor_range_type MIP_SENSOR_RANGE_TYPE_ALL = 0; ///< Only allowed for SAVE, LOAD, and DEFAULT function selectors. -static const mip_sensor_range_type MIP_SENSOR_RANGE_TYPE_ACCEL = 1; ///< Accelerometer. Range is specified in g. -static const mip_sensor_range_type MIP_SENSOR_RANGE_TYPE_GYRO = 2; ///< Gyroscope. Range is specified in degrees/s. -static const mip_sensor_range_type MIP_SENSOR_RANGE_TYPE_MAG = 3; ///< Magnetometer. Range is specified in Gauss. -static const mip_sensor_range_type MIP_SENSOR_RANGE_TYPE_PRESS = 4; ///< Pressure sensor. Range is specified in hPa. +enum mip_sensor_range_type +{ + MIP_SENSOR_RANGE_TYPE_ALL = 0, ///< Only allowed for SAVE, LOAD, and DEFAULT function selectors. + MIP_SENSOR_RANGE_TYPE_ACCEL = 1, ///< Accelerometer. Range is specified in g. + MIP_SENSOR_RANGE_TYPE_GYRO = 2, ///< Gyroscope. Range is specified in degrees/s. + MIP_SENSOR_RANGE_TYPE_MAG = 3, ///< Magnetometer. Range is specified in Gauss. + MIP_SENSOR_RANGE_TYPE_PRESS = 4, ///< Pressure sensor. Range is specified in hPa. +}; +typedef enum mip_sensor_range_type mip_sensor_range_type; -void insert_mip_sensor_range_type(microstrain_serializer* serializer, const mip_sensor_range_type self); -void extract_mip_sensor_range_type(microstrain_serializer* serializer, mip_sensor_range_type* self); +inline void insert_mip_sensor_range_type(microstrain_serializer* serializer, const mip_sensor_range_type self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_sensor_range_type(microstrain_serializer* serializer, mip_sensor_range_type* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} //////////////////////////////////////////////////////////////////////////////// @@ -213,13 +246,13 @@ struct mip_3dm_poll_imu_message_command bool suppress_ack; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors; ///< Number of descriptors in the descriptor list. mip_descriptor_rate descriptors[83]; ///< Descriptor list. - }; typedef struct mip_3dm_poll_imu_message_command mip_3dm_poll_imu_message_command; + void insert_mip_3dm_poll_imu_message_command(microstrain_serializer* serializer, const mip_3dm_poll_imu_message_command* self); void extract_mip_3dm_poll_imu_message_command(microstrain_serializer* serializer, mip_3dm_poll_imu_message_command* self); -mip_cmd_result mip_3dm_poll_imu_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); +mip_cmd_result mip_3dm_poll_imu_message(mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); ///@} /// @@ -241,13 +274,13 @@ struct mip_3dm_poll_gnss_message_command bool suppress_ack; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors; ///< Number of descriptors in the descriptor list. mip_descriptor_rate descriptors[83]; ///< Descriptor list. - }; typedef struct mip_3dm_poll_gnss_message_command mip_3dm_poll_gnss_message_command; + void insert_mip_3dm_poll_gnss_message_command(microstrain_serializer* serializer, const mip_3dm_poll_gnss_message_command* self); void extract_mip_3dm_poll_gnss_message_command(microstrain_serializer* serializer, mip_3dm_poll_gnss_message_command* self); -mip_cmd_result mip_3dm_poll_gnss_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); +mip_cmd_result mip_3dm_poll_gnss_message(mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); ///@} /// @@ -269,13 +302,13 @@ struct mip_3dm_poll_filter_message_command bool suppress_ack; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors; ///< Number of descriptors in the format list. mip_descriptor_rate descriptors[83]; ///< Descriptor format list. - }; typedef struct mip_3dm_poll_filter_message_command mip_3dm_poll_filter_message_command; + void insert_mip_3dm_poll_filter_message_command(microstrain_serializer* serializer, const mip_3dm_poll_filter_message_command* self); void extract_mip_3dm_poll_filter_message_command(microstrain_serializer* serializer, mip_3dm_poll_filter_message_command* self); -mip_cmd_result mip_3dm_poll_filter_message(struct mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); +mip_cmd_result mip_3dm_poll_filter_message(mip_interface* device, bool suppress_ack, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); ///@} /// @@ -292,9 +325,9 @@ struct mip_3dm_imu_message_format_command mip_function_selector function; uint8_t num_descriptors; ///< Number of descriptors mip_descriptor_rate descriptors[82]; ///< Descriptor format list. - }; typedef struct mip_3dm_imu_message_format_command mip_3dm_imu_message_format_command; + void insert_mip_3dm_imu_message_format_command(microstrain_serializer* serializer, const mip_3dm_imu_message_format_command* self); void extract_mip_3dm_imu_message_format_command(microstrain_serializer* serializer, mip_3dm_imu_message_format_command* self); @@ -302,17 +335,17 @@ struct mip_3dm_imu_message_format_response { uint8_t num_descriptors; ///< Number of descriptors mip_descriptor_rate descriptors[82]; ///< Descriptor format list. - }; typedef struct mip_3dm_imu_message_format_response mip_3dm_imu_message_format_response; + void insert_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, const mip_3dm_imu_message_format_response* self); void extract_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, mip_3dm_imu_message_format_response* self); -mip_cmd_result mip_3dm_write_imu_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); -mip_cmd_result mip_3dm_read_imu_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); -mip_cmd_result mip_3dm_save_imu_message_format(struct mip_interface* device); -mip_cmd_result mip_3dm_load_imu_message_format(struct mip_interface* device); -mip_cmd_result mip_3dm_default_imu_message_format(struct mip_interface* device); +mip_cmd_result mip_3dm_write_imu_message_format(mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); +mip_cmd_result mip_3dm_read_imu_message_format(mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); +mip_cmd_result mip_3dm_save_imu_message_format(mip_interface* device); +mip_cmd_result mip_3dm_load_imu_message_format(mip_interface* device); +mip_cmd_result mip_3dm_default_imu_message_format(mip_interface* device); ///@} /// @@ -329,9 +362,9 @@ struct mip_3dm_gps_message_format_command mip_function_selector function; uint8_t num_descriptors; ///< Number of descriptors mip_descriptor_rate descriptors[82]; ///< Descriptor format list. - }; typedef struct mip_3dm_gps_message_format_command mip_3dm_gps_message_format_command; + void insert_mip_3dm_gps_message_format_command(microstrain_serializer* serializer, const mip_3dm_gps_message_format_command* self); void extract_mip_3dm_gps_message_format_command(microstrain_serializer* serializer, mip_3dm_gps_message_format_command* self); @@ -339,17 +372,17 @@ struct mip_3dm_gps_message_format_response { uint8_t num_descriptors; ///< Number of descriptors mip_descriptor_rate descriptors[82]; ///< Descriptor format list. - }; typedef struct mip_3dm_gps_message_format_response mip_3dm_gps_message_format_response; + void insert_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, const mip_3dm_gps_message_format_response* self); void extract_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, mip_3dm_gps_message_format_response* self); -mip_cmd_result mip_3dm_write_gps_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); -mip_cmd_result mip_3dm_read_gps_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); -mip_cmd_result mip_3dm_save_gps_message_format(struct mip_interface* device); -mip_cmd_result mip_3dm_load_gps_message_format(struct mip_interface* device); -mip_cmd_result mip_3dm_default_gps_message_format(struct mip_interface* device); +mip_cmd_result mip_3dm_write_gps_message_format(mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); +mip_cmd_result mip_3dm_read_gps_message_format(mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); +mip_cmd_result mip_3dm_save_gps_message_format(mip_interface* device); +mip_cmd_result mip_3dm_load_gps_message_format(mip_interface* device); +mip_cmd_result mip_3dm_default_gps_message_format(mip_interface* device); ///@} /// @@ -366,9 +399,9 @@ struct mip_3dm_filter_message_format_command mip_function_selector function; uint8_t num_descriptors; ///< Number of descriptors (limited by payload size) mip_descriptor_rate descriptors[82]; - }; typedef struct mip_3dm_filter_message_format_command mip_3dm_filter_message_format_command; + void insert_mip_3dm_filter_message_format_command(microstrain_serializer* serializer, const mip_3dm_filter_message_format_command* self); void extract_mip_3dm_filter_message_format_command(microstrain_serializer* serializer, mip_3dm_filter_message_format_command* self); @@ -376,17 +409,17 @@ struct mip_3dm_filter_message_format_response { uint8_t num_descriptors; ///< Number of descriptors (limited by payload size) mip_descriptor_rate descriptors[82]; - }; typedef struct mip_3dm_filter_message_format_response mip_3dm_filter_message_format_response; + void insert_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, const mip_3dm_filter_message_format_response* self); void extract_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, mip_3dm_filter_message_format_response* self); -mip_cmd_result mip_3dm_write_filter_message_format(struct mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); -mip_cmd_result mip_3dm_read_filter_message_format(struct mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); -mip_cmd_result mip_3dm_save_filter_message_format(struct mip_interface* device); -mip_cmd_result mip_3dm_load_filter_message_format(struct mip_interface* device); -mip_cmd_result mip_3dm_default_filter_message_format(struct mip_interface* device); +mip_cmd_result mip_3dm_write_filter_message_format(mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); +mip_cmd_result mip_3dm_read_filter_message_format(mip_interface* device, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); +mip_cmd_result mip_3dm_save_filter_message_format(mip_interface* device); +mip_cmd_result mip_3dm_load_filter_message_format(mip_interface* device); +mip_cmd_result mip_3dm_default_filter_message_format(mip_interface* device); ///@} /// @@ -402,13 +435,13 @@ mip_cmd_result mip_3dm_default_filter_message_format(struct mip_interface* devic struct mip_3dm_imu_get_base_rate_response { uint16_t rate; ///< [hz] - }; typedef struct mip_3dm_imu_get_base_rate_response mip_3dm_imu_get_base_rate_response; + void insert_mip_3dm_imu_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_imu_get_base_rate_response* self); void extract_mip_3dm_imu_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_imu_get_base_rate_response* self); -mip_cmd_result mip_3dm_imu_get_base_rate(struct mip_interface* device, uint16_t* rate_out); +mip_cmd_result mip_3dm_imu_get_base_rate(mip_interface* device, uint16_t* rate_out); ///@} /// @@ -424,13 +457,13 @@ mip_cmd_result mip_3dm_imu_get_base_rate(struct mip_interface* device, uint16_t* struct mip_3dm_gps_get_base_rate_response { uint16_t rate; ///< [hz] - }; typedef struct mip_3dm_gps_get_base_rate_response mip_3dm_gps_get_base_rate_response; + void insert_mip_3dm_gps_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_gps_get_base_rate_response* self); void extract_mip_3dm_gps_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_gps_get_base_rate_response* self); -mip_cmd_result mip_3dm_gps_get_base_rate(struct mip_interface* device, uint16_t* rate_out); +mip_cmd_result mip_3dm_gps_get_base_rate(mip_interface* device, uint16_t* rate_out); ///@} /// @@ -446,13 +479,13 @@ mip_cmd_result mip_3dm_gps_get_base_rate(struct mip_interface* device, uint16_t* struct mip_3dm_filter_get_base_rate_response { uint16_t rate; ///< [hz] - }; typedef struct mip_3dm_filter_get_base_rate_response mip_3dm_filter_get_base_rate_response; + void insert_mip_3dm_filter_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_filter_get_base_rate_response* self); void extract_mip_3dm_filter_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_filter_get_base_rate_response* self); -mip_cmd_result mip_3dm_filter_get_base_rate(struct mip_interface* device, uint16_t* rate_out); +mip_cmd_result mip_3dm_filter_get_base_rate(mip_interface* device, uint16_t* rate_out); ///@} /// @@ -475,13 +508,13 @@ struct mip_3dm_poll_data_command bool suppress_ack; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors; ///< Number of descriptors in the format list. uint8_t descriptors[82]; ///< Descriptor format list. - }; typedef struct mip_3dm_poll_data_command mip_3dm_poll_data_command; + void insert_mip_3dm_poll_data_command(microstrain_serializer* serializer, const mip_3dm_poll_data_command* self); void extract_mip_3dm_poll_data_command(microstrain_serializer* serializer, mip_3dm_poll_data_command* self); -mip_cmd_result mip_3dm_poll_data(struct mip_interface* device, uint8_t desc_set, bool suppress_ack, uint8_t num_descriptors, const uint8_t* descriptors); +mip_cmd_result mip_3dm_poll_data(mip_interface* device, uint8_t desc_set, bool suppress_ack, uint8_t num_descriptors, const uint8_t* descriptors); ///@} /// @@ -494,9 +527,9 @@ mip_cmd_result mip_3dm_poll_data(struct mip_interface* device, uint8_t desc_set, struct mip_3dm_get_base_rate_command { uint8_t desc_set; ///< This is the data descriptor set. It must be a supported descriptor. - }; typedef struct mip_3dm_get_base_rate_command mip_3dm_get_base_rate_command; + void insert_mip_3dm_get_base_rate_command(microstrain_serializer* serializer, const mip_3dm_get_base_rate_command* self); void extract_mip_3dm_get_base_rate_command(microstrain_serializer* serializer, mip_3dm_get_base_rate_command* self); @@ -504,13 +537,13 @@ struct mip_3dm_get_base_rate_response { uint8_t desc_set; ///< Echoes the parameter in the command. uint16_t rate; ///< Base rate in Hz (0 = variable, unknown, or user-defined rate. Data will be sent when received). - }; typedef struct mip_3dm_get_base_rate_response mip_3dm_get_base_rate_response; + void insert_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_get_base_rate_response* self); void extract_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_get_base_rate_response* self); -mip_cmd_result mip_3dm_get_base_rate(struct mip_interface* device, uint8_t desc_set, uint16_t* rate_out); +mip_cmd_result mip_3dm_get_base_rate(mip_interface* device, uint8_t desc_set, uint16_t* rate_out); ///@} /// @@ -528,9 +561,9 @@ struct mip_3dm_message_format_command uint8_t desc_set; ///< Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets. uint8_t num_descriptors; ///< Number of descriptors (limited by payload size) mip_descriptor_rate descriptors[82]; ///< List of descriptors and decimations. - }; typedef struct mip_3dm_message_format_command mip_3dm_message_format_command; + void insert_mip_3dm_message_format_command(microstrain_serializer* serializer, const mip_3dm_message_format_command* self); void extract_mip_3dm_message_format_command(microstrain_serializer* serializer, mip_3dm_message_format_command* self); @@ -539,17 +572,17 @@ struct mip_3dm_message_format_response uint8_t desc_set; ///< Echoes the descriptor set from the command. uint8_t num_descriptors; ///< Number of descriptors in the list. mip_descriptor_rate descriptors[82]; ///< List of descriptors and decimations. - }; typedef struct mip_3dm_message_format_response mip_3dm_message_format_response; + void insert_mip_3dm_message_format_response(microstrain_serializer* serializer, const mip_3dm_message_format_response* self); void extract_mip_3dm_message_format_response(microstrain_serializer* serializer, mip_3dm_message_format_response* self); -mip_cmd_result mip_3dm_write_message_format(struct mip_interface* device, uint8_t desc_set, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); -mip_cmd_result mip_3dm_read_message_format(struct mip_interface* device, uint8_t desc_set, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); -mip_cmd_result mip_3dm_save_message_format(struct mip_interface* device, uint8_t desc_set); -mip_cmd_result mip_3dm_load_message_format(struct mip_interface* device, uint8_t desc_set); -mip_cmd_result mip_3dm_default_message_format(struct mip_interface* device, uint8_t desc_set); +mip_cmd_result mip_3dm_write_message_format(mip_interface* device, uint8_t desc_set, uint8_t num_descriptors, const mip_descriptor_rate* descriptors); +mip_cmd_result mip_3dm_read_message_format(mip_interface* device, uint8_t desc_set, uint8_t* num_descriptors_out, uint8_t num_descriptors_out_max, mip_descriptor_rate* descriptors_out); +mip_cmd_result mip_3dm_save_message_format(mip_interface* device, uint8_t desc_set); +mip_cmd_result mip_3dm_load_message_format(mip_interface* device, uint8_t desc_set); +mip_cmd_result mip_3dm_default_message_format(mip_interface* device, uint8_t desc_set); ///@} /// @@ -570,13 +603,13 @@ struct mip_3dm_nmea_poll_data_command bool suppress_ack; ///< Suppress the usual ACK/NACK reply. uint8_t count; ///< Number of format entries (limited by payload size) mip_nmea_message format_entries[40]; ///< List of format entries. - }; typedef struct mip_3dm_nmea_poll_data_command mip_3dm_nmea_poll_data_command; + void insert_mip_3dm_nmea_poll_data_command(microstrain_serializer* serializer, const mip_3dm_nmea_poll_data_command* self); void extract_mip_3dm_nmea_poll_data_command(microstrain_serializer* serializer, mip_3dm_nmea_poll_data_command* self); -mip_cmd_result mip_3dm_nmea_poll_data(struct mip_interface* device, bool suppress_ack, uint8_t count, const mip_nmea_message* format_entries); +mip_cmd_result mip_3dm_nmea_poll_data(mip_interface* device, bool suppress_ack, uint8_t count, const mip_nmea_message* format_entries); ///@} /// @@ -591,9 +624,9 @@ struct mip_3dm_nmea_message_format_command mip_function_selector function; uint8_t count; ///< Number of format entries (limited by payload size) mip_nmea_message format_entries[40]; ///< List of format entries. - }; typedef struct mip_3dm_nmea_message_format_command mip_3dm_nmea_message_format_command; + void insert_mip_3dm_nmea_message_format_command(microstrain_serializer* serializer, const mip_3dm_nmea_message_format_command* self); void extract_mip_3dm_nmea_message_format_command(microstrain_serializer* serializer, mip_3dm_nmea_message_format_command* self); @@ -601,17 +634,17 @@ struct mip_3dm_nmea_message_format_response { uint8_t count; ///< Number of format entries (limited by payload size) mip_nmea_message format_entries[40]; ///< List of format entries. - }; typedef struct mip_3dm_nmea_message_format_response mip_3dm_nmea_message_format_response; + void insert_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, const mip_3dm_nmea_message_format_response* self); void extract_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, mip_3dm_nmea_message_format_response* self); -mip_cmd_result mip_3dm_write_nmea_message_format(struct mip_interface* device, uint8_t count, const mip_nmea_message* format_entries); -mip_cmd_result mip_3dm_read_nmea_message_format(struct mip_interface* device, uint8_t* count_out, uint8_t count_out_max, mip_nmea_message* format_entries_out); -mip_cmd_result mip_3dm_save_nmea_message_format(struct mip_interface* device); -mip_cmd_result mip_3dm_load_nmea_message_format(struct mip_interface* device); -mip_cmd_result mip_3dm_default_nmea_message_format(struct mip_interface* device); +mip_cmd_result mip_3dm_write_nmea_message_format(mip_interface* device, uint8_t count, const mip_nmea_message* format_entries); +mip_cmd_result mip_3dm_read_nmea_message_format(mip_interface* device, uint8_t* count_out, uint8_t count_out_max, mip_nmea_message* format_entries_out); +mip_cmd_result mip_3dm_save_nmea_message_format(mip_interface* device); +mip_cmd_result mip_3dm_load_nmea_message_format(mip_interface* device); +mip_cmd_result mip_3dm_default_nmea_message_format(mip_interface* device); ///@} /// @@ -628,15 +661,15 @@ mip_cmd_result mip_3dm_default_nmea_message_format(struct mip_interface* device) struct mip_3dm_device_settings_command { mip_function_selector function; - }; typedef struct mip_3dm_device_settings_command mip_3dm_device_settings_command; + void insert_mip_3dm_device_settings_command(microstrain_serializer* serializer, const mip_3dm_device_settings_command* self); void extract_mip_3dm_device_settings_command(microstrain_serializer* serializer, mip_3dm_device_settings_command* self); -mip_cmd_result mip_3dm_save_device_settings(struct mip_interface* device); -mip_cmd_result mip_3dm_load_device_settings(struct mip_interface* device); -mip_cmd_result mip_3dm_default_device_settings(struct mip_interface* device); +mip_cmd_result mip_3dm_save_device_settings(mip_interface* device); +mip_cmd_result mip_3dm_load_device_settings(mip_interface* device); +mip_cmd_result mip_3dm_default_device_settings(mip_interface* device); ///@} /// @@ -664,26 +697,26 @@ struct mip_3dm_uart_baudrate_command { mip_function_selector function; uint32_t baud; - }; typedef struct mip_3dm_uart_baudrate_command mip_3dm_uart_baudrate_command; + void insert_mip_3dm_uart_baudrate_command(microstrain_serializer* serializer, const mip_3dm_uart_baudrate_command* self); void extract_mip_3dm_uart_baudrate_command(microstrain_serializer* serializer, mip_3dm_uart_baudrate_command* self); struct mip_3dm_uart_baudrate_response { uint32_t baud; - }; typedef struct mip_3dm_uart_baudrate_response mip_3dm_uart_baudrate_response; + void insert_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, const mip_3dm_uart_baudrate_response* self); void extract_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, mip_3dm_uart_baudrate_response* self); -mip_cmd_result mip_3dm_write_uart_baudrate(struct mip_interface* device, uint32_t baud); -mip_cmd_result mip_3dm_read_uart_baudrate(struct mip_interface* device, uint32_t* baud_out); -mip_cmd_result mip_3dm_save_uart_baudrate(struct mip_interface* device); -mip_cmd_result mip_3dm_load_uart_baudrate(struct mip_interface* device); -mip_cmd_result mip_3dm_default_uart_baudrate(struct mip_interface* device); +mip_cmd_result mip_3dm_write_uart_baudrate(mip_interface* device, uint32_t baud); +mip_cmd_result mip_3dm_read_uart_baudrate(mip_interface* device, uint32_t* baud_out); +mip_cmd_result mip_3dm_save_uart_baudrate(mip_interface* device); +mip_cmd_result mip_3dm_load_uart_baudrate(mip_interface* device); +mip_cmd_result mip_3dm_default_uart_baudrate(mip_interface* device); ///@} /// @@ -696,25 +729,37 @@ mip_cmd_result mip_3dm_default_uart_baudrate(struct mip_interface* device); /// ///@{ -typedef uint8_t mip_3dm_factory_streaming_command_action; -static const mip_3dm_factory_streaming_command_action MIP_3DM_FACTORY_STREAMING_COMMAND_ACTION_OVERWRITE = 0; ///< Replaces the message format(s), removing any existing descriptors. -static const mip_3dm_factory_streaming_command_action MIP_3DM_FACTORY_STREAMING_COMMAND_ACTION_MERGE = 1; ///< Merges support descriptors into existing format(s). May reorder descriptors. -static const mip_3dm_factory_streaming_command_action MIP_3DM_FACTORY_STREAMING_COMMAND_ACTION_ADD = 2; ///< Adds descriptors to the current message format(s) without changing existing descriptors. May result in duplicates. +enum mip_3dm_factory_streaming_command_action +{ + MIP_3DM_FACTORY_STREAMING_COMMAND_ACTION_OVERWRITE = 0, ///< Replaces the message format(s), removing any existing descriptors. + MIP_3DM_FACTORY_STREAMING_COMMAND_ACTION_MERGE = 1, ///< Merges support descriptors into existing format(s). May reorder descriptors. + MIP_3DM_FACTORY_STREAMING_COMMAND_ACTION_ADD = 2, ///< Adds descriptors to the current message format(s) without changing existing descriptors. May result in duplicates. +}; +typedef enum mip_3dm_factory_streaming_command_action mip_3dm_factory_streaming_command_action; + +inline void insert_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command_action self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, mip_3dm_factory_streaming_command_action* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_factory_streaming_command { mip_3dm_factory_streaming_command_action action; uint8_t reserved; ///< Reserved. Set to 0x00. - }; typedef struct mip_3dm_factory_streaming_command mip_3dm_factory_streaming_command; + void insert_mip_3dm_factory_streaming_command(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command* self); void extract_mip_3dm_factory_streaming_command(microstrain_serializer* serializer, mip_3dm_factory_streaming_command* self); -void insert_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command_action self); -void extract_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, mip_3dm_factory_streaming_command_action* self); - -mip_cmd_result mip_3dm_factory_streaming(struct mip_interface* device, mip_3dm_factory_streaming_command_action action, uint8_t reserved); +mip_cmd_result mip_3dm_factory_streaming(mip_interface* device, mip_3dm_factory_streaming_command_action action, uint8_t reserved); ///@} /// @@ -733,14 +778,15 @@ enum { MIP_3DM_DATASTREAM_CONTROL_COMMAND_LEGACY_IMU_STREAM = 0x01 }; enum { MIP_3DM_DATASTREAM_CONTROL_COMMAND_LEGACY_GNSS_STREAM = 0x02 }; enum { MIP_3DM_DATASTREAM_CONTROL_COMMAND_LEGACY_FILTER_STREAM = 0x03 }; enum { MIP_3DM_DATASTREAM_CONTROL_COMMAND_ALL_STREAMS = 0x00 }; + struct mip_3dm_datastream_control_command { mip_function_selector function; uint8_t desc_set; ///< The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets. On Generation 5 products, this must be one of the above legacy constants. bool enable; ///< True or false to enable or disable the stream. - }; typedef struct mip_3dm_datastream_control_command mip_3dm_datastream_control_command; + void insert_mip_3dm_datastream_control_command(microstrain_serializer* serializer, const mip_3dm_datastream_control_command* self); void extract_mip_3dm_datastream_control_command(microstrain_serializer* serializer, mip_3dm_datastream_control_command* self); @@ -748,17 +794,17 @@ struct mip_3dm_datastream_control_response { uint8_t desc_set; bool enabled; - }; typedef struct mip_3dm_datastream_control_response mip_3dm_datastream_control_response; + void insert_mip_3dm_datastream_control_response(microstrain_serializer* serializer, const mip_3dm_datastream_control_response* self); void extract_mip_3dm_datastream_control_response(microstrain_serializer* serializer, mip_3dm_datastream_control_response* self); -mip_cmd_result mip_3dm_write_datastream_control(struct mip_interface* device, uint8_t desc_set, bool enable); -mip_cmd_result mip_3dm_read_datastream_control(struct mip_interface* device, uint8_t desc_set, bool* enabled_out); -mip_cmd_result mip_3dm_save_datastream_control(struct mip_interface* device, uint8_t desc_set); -mip_cmd_result mip_3dm_load_datastream_control(struct mip_interface* device, uint8_t desc_set); -mip_cmd_result mip_3dm_default_datastream_control(struct mip_interface* device, uint8_t desc_set); +mip_cmd_result mip_3dm_write_datastream_control(mip_interface* device, uint8_t desc_set, bool enable); +mip_cmd_result mip_3dm_read_datastream_control(mip_interface* device, uint8_t desc_set, bool* enabled_out); +mip_cmd_result mip_3dm_save_datastream_control(mip_interface* device, uint8_t desc_set); +mip_cmd_result mip_3dm_load_datastream_control(mip_interface* device, uint8_t desc_set); +mip_cmd_result mip_3dm_default_datastream_control(mip_interface* device, uint8_t desc_set); ///@} /// @@ -785,18 +831,42 @@ mip_cmd_result mip_3dm_default_datastream_control(struct mip_interface* device, /// ///@{ -typedef uint8_t mip_3dm_constellation_settings_command_constellation_id; -static const mip_3dm_constellation_settings_command_constellation_id MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_GPS = 0; ///< GPS (G1-G32) -static const mip_3dm_constellation_settings_command_constellation_id MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_SBAS = 1; ///< SBAS (S120-S158) -static const mip_3dm_constellation_settings_command_constellation_id MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_GALILEO = 2; ///< GALILEO (E1-E36) -static const mip_3dm_constellation_settings_command_constellation_id MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_BEIDOU = 3; ///< BeiDou (B1-B37) -static const mip_3dm_constellation_settings_command_constellation_id MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_QZSS = 5; ///< QZSS (Q1-Q5) -static const mip_3dm_constellation_settings_command_constellation_id MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_GLONASS = 6; ///< GLONASS (R1-R32) +enum mip_3dm_constellation_settings_command_constellation_id +{ + MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_GPS = 0, ///< GPS (G1-G32) + MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_SBAS = 1, ///< SBAS (S120-S158) + MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_GALILEO = 2, ///< GALILEO (E1-E36) + MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_BEIDOU = 3, ///< BeiDou (B1-B37) + MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_QZSS = 5, ///< QZSS (Q1-Q5) + MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_CONSTELLATION_ID_GLONASS = 6, ///< GLONASS (R1-R32) +}; +typedef enum mip_3dm_constellation_settings_command_constellation_id mip_3dm_constellation_settings_command_constellation_id; + +inline void insert_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_3dm_constellation_settings_command_option_flags; static const mip_3dm_constellation_settings_command_option_flags MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_OPTION_FLAGS_NONE = 0x0000; static const mip_3dm_constellation_settings_command_option_flags MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_OPTION_FLAGS_L1SAIF = 0x0001; ///< Available only for QZSS static const mip_3dm_constellation_settings_command_option_flags MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_OPTION_FLAGS_ALL = 0x0001; +inline void insert_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} struct mip_3dm_constellation_settings_command_settings { @@ -805,47 +875,42 @@ struct mip_3dm_constellation_settings_command_settings uint8_t reserved_channels; ///< Minimum number of channels reserved for this constellation uint8_t max_channels; ///< Maximum number of channels to use for this constallation mip_3dm_constellation_settings_command_option_flags option_flags; ///< Constellation option Flags - }; typedef struct mip_3dm_constellation_settings_command_settings mip_3dm_constellation_settings_command_settings; + +void insert_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_settings* self); +void extract_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_settings* self); + + struct mip_3dm_constellation_settings_command { mip_function_selector function; uint16_t max_channels; uint8_t config_count; mip_3dm_constellation_settings_command_settings settings[42]; - }; typedef struct mip_3dm_constellation_settings_command mip_3dm_constellation_settings_command; + void insert_mip_3dm_constellation_settings_command(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command* self); void extract_mip_3dm_constellation_settings_command(microstrain_serializer* serializer, mip_3dm_constellation_settings_command* self); -void insert_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self); -void extract_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self); - -void insert_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self); -void extract_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self); - -void insert_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_settings* self); -void extract_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_settings* self); - struct mip_3dm_constellation_settings_response { uint16_t max_channels_available; ///< Maximum channels available uint16_t max_channels_use; ///< Maximum channels to use uint8_t config_count; ///< Number of constellation configurations mip_3dm_constellation_settings_command_settings settings[42]; ///< Constellation Settings - }; typedef struct mip_3dm_constellation_settings_response mip_3dm_constellation_settings_response; + void insert_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, const mip_3dm_constellation_settings_response* self); void extract_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, mip_3dm_constellation_settings_response* self); -mip_cmd_result mip_3dm_write_constellation_settings(struct mip_interface* device, uint16_t max_channels, uint8_t config_count, const mip_3dm_constellation_settings_command_settings* settings); -mip_cmd_result mip_3dm_read_constellation_settings(struct mip_interface* device, uint16_t* max_channels_available_out, uint16_t* max_channels_use_out, uint8_t* config_count_out, uint8_t config_count_out_max, mip_3dm_constellation_settings_command_settings* settings_out); -mip_cmd_result mip_3dm_save_constellation_settings(struct mip_interface* device); -mip_cmd_result mip_3dm_load_constellation_settings(struct mip_interface* device); -mip_cmd_result mip_3dm_default_constellation_settings(struct mip_interface* device); +mip_cmd_result mip_3dm_write_constellation_settings(mip_interface* device, uint16_t max_channels, uint8_t config_count, const mip_3dm_constellation_settings_command_settings* settings); +mip_cmd_result mip_3dm_read_constellation_settings(mip_interface* device, uint16_t* max_channels_available_out, uint16_t* max_channels_use_out, uint8_t* config_count_out, uint8_t config_count_out_max, mip_3dm_constellation_settings_command_settings* settings_out); +mip_cmd_result mip_3dm_save_constellation_settings(mip_interface* device); +mip_cmd_result mip_3dm_load_constellation_settings(mip_interface* device); +mip_cmd_result mip_3dm_default_constellation_settings(mip_interface* device); ///@} /// @@ -864,6 +929,17 @@ static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SE static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SETTINGS_COMMAND_SBASOPTIONS_ENABLE_CORRECTIONS = 0x0002; ///< Use SBAS differential corrections static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SETTINGS_COMMAND_SBASOPTIONS_APPLY_INTEGRITY = 0x0004; ///< Use SBAS integrity information. If enabled, only GPS satellites for which integrity information is available will be used. static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SETTINGS_COMMAND_SBASOPTIONS_ALL = 0x0007; +inline void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_gnss_sbas_settings_command { @@ -872,32 +948,29 @@ struct mip_3dm_gnss_sbas_settings_command mip_3dm_gnss_sbas_settings_command_sbasoptions sbas_options; ///< SBAS options, see definition uint8_t num_included_prns; ///< Number of SBAS PRNs to include in search (0 = include all) uint16_t included_prns[39]; ///< List of specific SBAS PRNs to search for - }; typedef struct mip_3dm_gnss_sbas_settings_command mip_3dm_gnss_sbas_settings_command; + void insert_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command* self); void extract_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command* self); -void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self); -void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self); - struct mip_3dm_gnss_sbas_settings_response { uint8_t enable_sbas; ///< 0 - SBAS Disabled, 1 - SBAS enabled mip_3dm_gnss_sbas_settings_command_sbasoptions sbas_options; ///< SBAS options, see definition uint8_t num_included_prns; ///< Number of SBAS PRNs to include in search (0 = include all) uint16_t included_prns[39]; ///< List of specific SBAS PRNs to search for - }; typedef struct mip_3dm_gnss_sbas_settings_response mip_3dm_gnss_sbas_settings_response; + void insert_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_response* self); void extract_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_response* self); -mip_cmd_result mip_3dm_write_gnss_sbas_settings(struct mip_interface* device, uint8_t enable_sbas, mip_3dm_gnss_sbas_settings_command_sbasoptions sbas_options, uint8_t num_included_prns, const uint16_t* included_prns); -mip_cmd_result mip_3dm_read_gnss_sbas_settings(struct mip_interface* device, uint8_t* enable_sbas_out, mip_3dm_gnss_sbas_settings_command_sbasoptions* sbas_options_out, uint8_t* num_included_prns_out, uint8_t num_included_prns_out_max, uint16_t* included_prns_out); -mip_cmd_result mip_3dm_save_gnss_sbas_settings(struct mip_interface* device); -mip_cmd_result mip_3dm_load_gnss_sbas_settings(struct mip_interface* device); -mip_cmd_result mip_3dm_default_gnss_sbas_settings(struct mip_interface* device); +mip_cmd_result mip_3dm_write_gnss_sbas_settings(mip_interface* device, uint8_t enable_sbas, mip_3dm_gnss_sbas_settings_command_sbasoptions sbas_options, uint8_t num_included_prns, const uint16_t* included_prns); +mip_cmd_result mip_3dm_read_gnss_sbas_settings(mip_interface* device, uint8_t* enable_sbas_out, mip_3dm_gnss_sbas_settings_command_sbasoptions* sbas_options_out, uint8_t* num_included_prns_out, uint8_t num_included_prns_out_max, uint16_t* included_prns_out); +mip_cmd_result mip_3dm_save_gnss_sbas_settings(mip_interface* device); +mip_cmd_result mip_3dm_load_gnss_sbas_settings(mip_interface* device); +mip_cmd_result mip_3dm_default_gnss_sbas_settings(mip_interface* device); ///@} /// @@ -917,39 +990,51 @@ mip_cmd_result mip_3dm_default_gnss_sbas_settings(struct mip_interface* device); /// ///@{ -typedef uint8_t mip_3dm_gnss_assisted_fix_command_assisted_fix_option; -static const mip_3dm_gnss_assisted_fix_command_assisted_fix_option MIP_3DM_GNSS_ASSISTED_FIX_COMMAND_ASSISTED_FIX_OPTION_NONE = 0; ///< No assisted fix (default) -static const mip_3dm_gnss_assisted_fix_command_assisted_fix_option MIP_3DM_GNSS_ASSISTED_FIX_COMMAND_ASSISTED_FIX_OPTION_ENABLED = 1; ///< Enable assisted fix +enum mip_3dm_gnss_assisted_fix_command_assisted_fix_option +{ + MIP_3DM_GNSS_ASSISTED_FIX_COMMAND_ASSISTED_FIX_OPTION_NONE = 0, ///< No assisted fix (default) + MIP_3DM_GNSS_ASSISTED_FIX_COMMAND_ASSISTED_FIX_OPTION_ENABLED = 1, ///< Enable assisted fix +}; +typedef enum mip_3dm_gnss_assisted_fix_command_assisted_fix_option mip_3dm_gnss_assisted_fix_command_assisted_fix_option; + +inline void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_gnss_assisted_fix_command { mip_function_selector function; mip_3dm_gnss_assisted_fix_command_assisted_fix_option option; ///< Assisted fix options uint8_t flags; ///< Assisted fix flags (set to 0xFF) - }; typedef struct mip_3dm_gnss_assisted_fix_command mip_3dm_gnss_assisted_fix_command; + void insert_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command* self); void extract_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command* self); -void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self); -void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self); - struct mip_3dm_gnss_assisted_fix_response { mip_3dm_gnss_assisted_fix_command_assisted_fix_option option; ///< Assisted fix options uint8_t flags; ///< Assisted fix flags (set to 0xFF) - }; typedef struct mip_3dm_gnss_assisted_fix_response mip_3dm_gnss_assisted_fix_response; + void insert_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_response* self); void extract_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_response* self); -mip_cmd_result mip_3dm_write_gnss_assisted_fix(struct mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option option, uint8_t flags); -mip_cmd_result mip_3dm_read_gnss_assisted_fix(struct mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* option_out, uint8_t* flags_out); -mip_cmd_result mip_3dm_save_gnss_assisted_fix(struct mip_interface* device); -mip_cmd_result mip_3dm_load_gnss_assisted_fix(struct mip_interface* device); -mip_cmd_result mip_3dm_default_gnss_assisted_fix(struct mip_interface* device); +mip_cmd_result mip_3dm_write_gnss_assisted_fix(mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option option, uint8_t flags); +mip_cmd_result mip_3dm_read_gnss_assisted_fix(mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* option_out, uint8_t* flags_out); +mip_cmd_result mip_3dm_save_gnss_assisted_fix(mip_interface* device); +mip_cmd_result mip_3dm_load_gnss_assisted_fix(mip_interface* device); +mip_cmd_result mip_3dm_default_gnss_assisted_fix(mip_interface* device); ///@} /// @@ -968,9 +1053,9 @@ struct mip_3dm_gnss_time_assistance_command double tow; ///< GPS Time of week [seconds] uint16_t week_number; ///< GPS Weeks since 1980 [weeks] float accuracy; ///< Accuracy of time information [seconds] - }; typedef struct mip_3dm_gnss_time_assistance_command mip_3dm_gnss_time_assistance_command; + void insert_mip_3dm_gnss_time_assistance_command(microstrain_serializer* serializer, const mip_3dm_gnss_time_assistance_command* self); void extract_mip_3dm_gnss_time_assistance_command(microstrain_serializer* serializer, mip_3dm_gnss_time_assistance_command* self); @@ -979,14 +1064,14 @@ struct mip_3dm_gnss_time_assistance_response double tow; ///< GPS Time of week [seconds] uint16_t week_number; ///< GPS Weeks since 1980 [weeks] float accuracy; ///< Accuracy of time information [seconds] - }; typedef struct mip_3dm_gnss_time_assistance_response mip_3dm_gnss_time_assistance_response; + void insert_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, const mip_3dm_gnss_time_assistance_response* self); void extract_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, mip_3dm_gnss_time_assistance_response* self); -mip_cmd_result mip_3dm_write_gnss_time_assistance(struct mip_interface* device, double tow, uint16_t week_number, float accuracy); -mip_cmd_result mip_3dm_read_gnss_time_assistance(struct mip_interface* device, double* tow_out, uint16_t* week_number_out, float* accuracy_out); +mip_cmd_result mip_3dm_write_gnss_time_assistance(mip_interface* device, double tow, uint16_t week_number, float accuracy); +mip_cmd_result mip_3dm_read_gnss_time_assistance(mip_interface* device, double* tow_out, uint16_t* week_number_out, float* accuracy_out); ///@} /// @@ -1019,9 +1104,9 @@ struct mip_3dm_imu_lowpass_filter_command bool manual; ///< If false, the cutoff frequency is set to half of the streaming rate as configured by the message format command. Otherwise, the cutoff frequency is set according to the following 'frequency' parameter. uint16_t frequency; ///< -3dB cutoff frequency in Hz. Will not affect filtering if 'manual' is false. uint8_t reserved; ///< Reserved, set to 0x00. - }; typedef struct mip_3dm_imu_lowpass_filter_command mip_3dm_imu_lowpass_filter_command; + void insert_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serializer, const mip_3dm_imu_lowpass_filter_command* self); void extract_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serializer, mip_3dm_imu_lowpass_filter_command* self); @@ -1032,17 +1117,17 @@ struct mip_3dm_imu_lowpass_filter_response bool manual; ///< True if the filter cutoff was manually configured. uint16_t frequency; ///< The cutoff frequency of the filter. If the filter is in auto mode, this value is unspecified. uint8_t reserved; ///< Reserved and must be ignored. - }; typedef struct mip_3dm_imu_lowpass_filter_response mip_3dm_imu_lowpass_filter_response; + void insert_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_imu_lowpass_filter_response* self); void extract_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_imu_lowpass_filter_response* self); -mip_cmd_result mip_3dm_write_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved); -mip_cmd_result mip_3dm_read_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor, bool* enable_out, bool* manual_out, uint16_t* frequency_out, uint8_t* reserved_out); -mip_cmd_result mip_3dm_save_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor); -mip_cmd_result mip_3dm_load_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor); -mip_cmd_result mip_3dm_default_imu_lowpass_filter(struct mip_interface* device, uint8_t target_descriptor); +mip_cmd_result mip_3dm_write_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved); +mip_cmd_result mip_3dm_read_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor, bool* enable_out, bool* manual_out, uint16_t* frequency_out, uint8_t* reserved_out); +mip_cmd_result mip_3dm_save_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor); +mip_cmd_result mip_3dm_load_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor); +mip_cmd_result mip_3dm_default_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor); ///@} /// @@ -1052,40 +1137,52 @@ mip_cmd_result mip_3dm_default_imu_lowpass_filter(struct mip_interface* device, /// ///@{ -typedef uint8_t mip_3dm_pps_source_command_source; -static const mip_3dm_pps_source_command_source MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_DISABLED = 0; ///< PPS output is disabled. Not valid for PPS source command. -static const mip_3dm_pps_source_command_source MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_RECEIVER_1 = 1; ///< PPS is provided by GNSS receiver 1. -static const mip_3dm_pps_source_command_source MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_RECEIVER_2 = 2; ///< PPS is provided by GNSS receiver 2. -static const mip_3dm_pps_source_command_source MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_GPIO = 3; ///< PPS is provided to an external GPIO pin. Use the GPIO Setup command to choose and configure the pin. -static const mip_3dm_pps_source_command_source MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_GENERATED = 4; ///< PPS is generated from the system oscillator. +enum mip_3dm_pps_source_command_source +{ + MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_DISABLED = 0, ///< PPS output is disabled. Not valid for PPS source command. + MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_RECEIVER_1 = 1, ///< PPS is provided by GNSS receiver 1. + MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_RECEIVER_2 = 2, ///< PPS is provided by GNSS receiver 2. + MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_GPIO = 3, ///< PPS is provided to an external GPIO pin. Use the GPIO Setup command to choose and configure the pin. + MIP_3DM_PPS_SOURCE_COMMAND_SOURCE_GENERATED = 4, ///< PPS is generated from the system oscillator. +}; +typedef enum mip_3dm_pps_source_command_source mip_3dm_pps_source_command_source; + +inline void insert_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, const mip_3dm_pps_source_command_source self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, mip_3dm_pps_source_command_source* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_pps_source_command { mip_function_selector function; mip_3dm_pps_source_command_source source; - }; typedef struct mip_3dm_pps_source_command mip_3dm_pps_source_command; + void insert_mip_3dm_pps_source_command(microstrain_serializer* serializer, const mip_3dm_pps_source_command* self); void extract_mip_3dm_pps_source_command(microstrain_serializer* serializer, mip_3dm_pps_source_command* self); -void insert_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, const mip_3dm_pps_source_command_source self); -void extract_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, mip_3dm_pps_source_command_source* self); - struct mip_3dm_pps_source_response { mip_3dm_pps_source_command_source source; - }; typedef struct mip_3dm_pps_source_response mip_3dm_pps_source_response; + void insert_mip_3dm_pps_source_response(microstrain_serializer* serializer, const mip_3dm_pps_source_response* self); void extract_mip_3dm_pps_source_response(microstrain_serializer* serializer, mip_3dm_pps_source_response* self); -mip_cmd_result mip_3dm_write_pps_source(struct mip_interface* device, mip_3dm_pps_source_command_source source); -mip_cmd_result mip_3dm_read_pps_source(struct mip_interface* device, mip_3dm_pps_source_command_source* source_out); -mip_cmd_result mip_3dm_save_pps_source(struct mip_interface* device); -mip_cmd_result mip_3dm_load_pps_source(struct mip_interface* device); -mip_cmd_result mip_3dm_default_pps_source(struct mip_interface* device); +mip_cmd_result mip_3dm_write_pps_source(mip_interface* device, mip_3dm_pps_source_command_source source); +mip_cmd_result mip_3dm_read_pps_source(mip_interface* device, mip_3dm_pps_source_command_source* source_out); +mip_cmd_result mip_3dm_save_pps_source(mip_interface* device); +mip_cmd_result mip_3dm_load_pps_source(mip_interface* device); +mip_cmd_result mip_3dm_default_pps_source(mip_interface* device); ///@} /// @@ -1111,30 +1208,58 @@ mip_cmd_result mip_3dm_default_pps_source(struct mip_interface* device); /// ///@{ -typedef uint8_t mip_3dm_gpio_config_command_feature; -static const mip_3dm_gpio_config_command_feature MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_UNUSED = 0; ///< The pin is not used. It may be technically possible to read the pin state in this mode, but this is not guaranteed to be true of all devices or pins. -static const mip_3dm_gpio_config_command_feature MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_GPIO = 1; ///< General purpose input or output. Use this for direct control of pin output state or to stream the state of the pin. -static const mip_3dm_gpio_config_command_feature MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_PPS = 2; ///< Pulse per second input or output. -static const mip_3dm_gpio_config_command_feature MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_ENCODER = 3; ///< Motor encoder/odometer input. -static const mip_3dm_gpio_config_command_feature MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_TIMESTAMP = 4; ///< Precision Timestamping. Use with Event Trigger Configuration (0x0C,0x2E). -static const mip_3dm_gpio_config_command_feature MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_UART = 5; ///< UART data or control lines. - -typedef uint8_t mip_3dm_gpio_config_command_behavior; -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UNUSED = 0; ///< Use 0 unless otherwise specified. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_GPIO_INPUT = 1; ///< Pin will be an input. This can be used to stream or poll the value and is the default setting. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_GPIO_OUTPUT_LOW = 2; ///< Pin is an output initially in the LOW state. This state will be restored during system startup if the configuration is saved. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_GPIO_OUTPUT_HIGH = 3; ///< Pin is an output initially in the HIGH state. This state will be restored during system startup if the configuration is saved. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_PPS_INPUT = 1; ///< Pin will receive the pulse-per-second signal. Only one pin can have this behavior. This will only work if the PPS Source command is configured to GPIO. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_PPS_OUTPUT = 2; ///< Pin will transmit the pulse-per-second signal from the device. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_ENCODER_A = 1; ///< Encoder "A" quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_ENCODER_B = 2; ///< Encoder "B" quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_TIMESTAMP_RISING = 1; ///< Rising edges will be timestamped. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_TIMESTAMP_FALLING = 2; ///< Falling edges will be timestamped. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_TIMESTAMP_EITHER = 3; ///< Both rising and falling edges will be timestamped. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UART_PORT2_TX = 33; ///< (0x21) UART port 2 transmit. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UART_PORT2_RX = 34; ///< (0x22) UART port 2 receive. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UART_PORT3_TX = 49; ///< (0x31) UART port 3 transmit. -static const mip_3dm_gpio_config_command_behavior MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UART_PORT3_RX = 50; ///< (0x32) UART port 3 receive. +enum mip_3dm_gpio_config_command_feature +{ + MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_UNUSED = 0, ///< The pin is not used. It may be technically possible to read the pin state in this mode, but this is not guaranteed to be true of all devices or pins. + MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_GPIO = 1, ///< General purpose input or output. Use this for direct control of pin output state or to stream the state of the pin. + MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_PPS = 2, ///< Pulse per second input or output. + MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_ENCODER = 3, ///< Motor encoder/odometer input. + MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_TIMESTAMP = 4, ///< Precision Timestamping. Use with Event Trigger Configuration (0x0C,0x2E). + MIP_3DM_GPIO_CONFIG_COMMAND_FEATURE_UART = 5, ///< UART data or control lines. +}; +typedef enum mip_3dm_gpio_config_command_feature mip_3dm_gpio_config_command_feature; + +inline void insert_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_feature self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, mip_3dm_gpio_config_command_feature* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + +enum mip_3dm_gpio_config_command_behavior +{ + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UNUSED = 0, ///< Use 0 unless otherwise specified. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_GPIO_INPUT = 1, ///< Pin will be an input. This can be used to stream or poll the value and is the default setting. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_GPIO_OUTPUT_LOW = 2, ///< Pin is an output initially in the LOW state. This state will be restored during system startup if the configuration is saved. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_GPIO_OUTPUT_HIGH = 3, ///< Pin is an output initially in the HIGH state. This state will be restored during system startup if the configuration is saved. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_PPS_INPUT = 1, ///< Pin will receive the pulse-per-second signal. Only one pin can have this behavior. This will only work if the PPS Source command is configured to GPIO. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_PPS_OUTPUT = 2, ///< Pin will transmit the pulse-per-second signal from the device. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_ENCODER_A = 1, ///< Encoder "A" quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_ENCODER_B = 2, ///< Encoder "B" quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_TIMESTAMP_RISING = 1, ///< Rising edges will be timestamped. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_TIMESTAMP_FALLING = 2, ///< Falling edges will be timestamped. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_TIMESTAMP_EITHER = 3, ///< Both rising and falling edges will be timestamped. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UART_PORT2_TX = 33, ///< (0x21) UART port 2 transmit. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UART_PORT2_RX = 34, ///< (0x22) UART port 2 receive. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UART_PORT3_TX = 49, ///< (0x31) UART port 3 transmit. + MIP_3DM_GPIO_CONFIG_COMMAND_BEHAVIOR_UART_PORT3_RX = 50, ///< (0x32) UART port 3 receive. +}; +typedef enum mip_3dm_gpio_config_command_behavior mip_3dm_gpio_config_command_behavior; + +inline void insert_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_behavior self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, mip_3dm_gpio_config_command_behavior* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint8_t mip_3dm_gpio_config_command_pin_mode; static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PIN_MODE_NONE = 0x00; @@ -1142,6 +1267,17 @@ static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PI static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PIN_MODE_PULLDOWN = 0x02; ///< The pin will have an internal pull-down resistor enabled. This is useful for connecting inputs to signals which can only be pulled high such as mechanical switches. Cannot be used in combination with pull-up. See the device specifications for the resistance value. static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PIN_MODE_PULLUP = 0x04; ///< The pin will have an internal pull-up resistor enabled. Useful for connecting inputs to signals which can only be pulled low such as mechanical switches, or in combination with an open drain output. Cannot be used in combination with pull-down. See the device specifications for the resistance value. Use of this mode may restrict the maximum allowed input voltage. See the device datasheet for details. static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PIN_MODE_ALL = 0x07; +inline void insert_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_gpio_config_command { @@ -1150,38 +1286,29 @@ struct mip_3dm_gpio_config_command mip_3dm_gpio_config_command_feature feature; ///< Determines how the pin will be used. mip_3dm_gpio_config_command_behavior behavior; ///< Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.) mip_3dm_gpio_config_command_pin_mode pin_mode; ///< GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual. - }; typedef struct mip_3dm_gpio_config_command mip_3dm_gpio_config_command; + void insert_mip_3dm_gpio_config_command(microstrain_serializer* serializer, const mip_3dm_gpio_config_command* self); void extract_mip_3dm_gpio_config_command(microstrain_serializer* serializer, mip_3dm_gpio_config_command* self); -void insert_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_feature self); -void extract_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, mip_3dm_gpio_config_command_feature* self); - -void insert_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_behavior self); -void extract_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, mip_3dm_gpio_config_command_behavior* self); - -void insert_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self); -void extract_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self); - struct mip_3dm_gpio_config_response { uint8_t pin; ///< GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins. mip_3dm_gpio_config_command_feature feature; ///< Determines how the pin will be used. mip_3dm_gpio_config_command_behavior behavior; ///< Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.) mip_3dm_gpio_config_command_pin_mode pin_mode; ///< GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual. - }; typedef struct mip_3dm_gpio_config_response mip_3dm_gpio_config_response; + void insert_mip_3dm_gpio_config_response(microstrain_serializer* serializer, const mip_3dm_gpio_config_response* self); void extract_mip_3dm_gpio_config_response(microstrain_serializer* serializer, mip_3dm_gpio_config_response* self); -mip_cmd_result mip_3dm_write_gpio_config(struct mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature feature, mip_3dm_gpio_config_command_behavior behavior, mip_3dm_gpio_config_command_pin_mode pin_mode); -mip_cmd_result mip_3dm_read_gpio_config(struct mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature* feature_out, mip_3dm_gpio_config_command_behavior* behavior_out, mip_3dm_gpio_config_command_pin_mode* pin_mode_out); -mip_cmd_result mip_3dm_save_gpio_config(struct mip_interface* device, uint8_t pin); -mip_cmd_result mip_3dm_load_gpio_config(struct mip_interface* device, uint8_t pin); -mip_cmd_result mip_3dm_default_gpio_config(struct mip_interface* device, uint8_t pin); +mip_cmd_result mip_3dm_write_gpio_config(mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature feature, mip_3dm_gpio_config_command_behavior behavior, mip_3dm_gpio_config_command_pin_mode pin_mode); +mip_cmd_result mip_3dm_read_gpio_config(mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature* feature_out, mip_3dm_gpio_config_command_behavior* behavior_out, mip_3dm_gpio_config_command_pin_mode* pin_mode_out); +mip_cmd_result mip_3dm_save_gpio_config(mip_interface* device, uint8_t pin); +mip_cmd_result mip_3dm_load_gpio_config(mip_interface* device, uint8_t pin); +mip_cmd_result mip_3dm_default_gpio_config(mip_interface* device, uint8_t pin); ///@} /// @@ -1211,9 +1338,9 @@ struct mip_3dm_gpio_state_command mip_function_selector function; uint8_t pin; ///< GPIO pin number counting from 1. Cannot be 0. bool state; ///< The pin state. - }; typedef struct mip_3dm_gpio_state_command mip_3dm_gpio_state_command; + void insert_mip_3dm_gpio_state_command(microstrain_serializer* serializer, const mip_3dm_gpio_state_command* self); void extract_mip_3dm_gpio_state_command(microstrain_serializer* serializer, mip_3dm_gpio_state_command* self); @@ -1221,14 +1348,14 @@ struct mip_3dm_gpio_state_response { uint8_t pin; ///< GPIO pin number counting from 1. Cannot be 0. bool state; ///< The pin state. - }; typedef struct mip_3dm_gpio_state_response mip_3dm_gpio_state_response; + void insert_mip_3dm_gpio_state_response(microstrain_serializer* serializer, const mip_3dm_gpio_state_response* self); void extract_mip_3dm_gpio_state_response(microstrain_serializer* serializer, mip_3dm_gpio_state_response* self); -mip_cmd_result mip_3dm_write_gpio_state(struct mip_interface* device, uint8_t pin, bool state); -mip_cmd_result mip_3dm_read_gpio_state(struct mip_interface* device, uint8_t pin, bool* state_out); +mip_cmd_result mip_3dm_write_gpio_state(mip_interface* device, uint8_t pin, bool state); +mip_cmd_result mip_3dm_read_gpio_state(mip_interface* device, uint8_t pin, bool* state_out); ///@} /// @@ -1239,9 +1366,24 @@ mip_cmd_result mip_3dm_read_gpio_state(struct mip_interface* device, uint8_t pin /// ///@{ -typedef uint8_t mip_3dm_odometer_command_mode; -static const mip_3dm_odometer_command_mode MIP_3DM_ODOMETER_COMMAND_MODE_DISABLED = 0; ///< Encoder is disabled. -static const mip_3dm_odometer_command_mode MIP_3DM_ODOMETER_COMMAND_MODE_QUADRATURE = 2; ///< Quadrature encoder mode. +enum mip_3dm_odometer_command_mode +{ + MIP_3DM_ODOMETER_COMMAND_MODE_DISABLED = 0, ///< Encoder is disabled. + MIP_3DM_ODOMETER_COMMAND_MODE_QUADRATURE = 2, ///< Quadrature encoder mode. +}; +typedef enum mip_3dm_odometer_command_mode mip_3dm_odometer_command_mode; + +inline void insert_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, const mip_3dm_odometer_command_mode self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, mip_3dm_odometer_command_mode* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_odometer_command { @@ -1249,31 +1391,28 @@ struct mip_3dm_odometer_command mip_3dm_odometer_command_mode mode; ///< Mode setting. float scaling; ///< Encoder pulses per meter of distance traveled [pulses/m]. Distance traveled is computed using the formula d = p / N * 2R * pi, where d is distance, p is the number of pulses received, N is the encoder resolution, and R is the wheel radius. By simplifying all of the parameters into one, the formula d = p / S is obtained, where s is the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and has units of pulses / meter. N is in units of "A" pulses per revolution and R is in meters. Make this value negative if the odometer is mounted so that it rotates backwards. float uncertainty; ///< Uncertainty in encoder counts to distance translation (1-sigma value) [m/m]. - }; typedef struct mip_3dm_odometer_command mip_3dm_odometer_command; + void insert_mip_3dm_odometer_command(microstrain_serializer* serializer, const mip_3dm_odometer_command* self); void extract_mip_3dm_odometer_command(microstrain_serializer* serializer, mip_3dm_odometer_command* self); -void insert_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, const mip_3dm_odometer_command_mode self); -void extract_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, mip_3dm_odometer_command_mode* self); - struct mip_3dm_odometer_response { mip_3dm_odometer_command_mode mode; ///< Mode setting. float scaling; ///< Encoder pulses per meter of distance traveled [pulses/m]. Distance traveled is computed using the formula d = p / N * 2R * pi, where d is distance, p is the number of pulses received, N is the encoder resolution, and R is the wheel radius. By simplifying all of the parameters into one, the formula d = p / S is obtained, where s is the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and has units of pulses / meter. N is in units of "A" pulses per revolution and R is in meters. Make this value negative if the odometer is mounted so that it rotates backwards. float uncertainty; ///< Uncertainty in encoder counts to distance translation (1-sigma value) [m/m]. - }; typedef struct mip_3dm_odometer_response mip_3dm_odometer_response; + void insert_mip_3dm_odometer_response(microstrain_serializer* serializer, const mip_3dm_odometer_response* self); void extract_mip_3dm_odometer_response(microstrain_serializer* serializer, mip_3dm_odometer_response* self); -mip_cmd_result mip_3dm_write_odometer(struct mip_interface* device, mip_3dm_odometer_command_mode mode, float scaling, float uncertainty); -mip_cmd_result mip_3dm_read_odometer(struct mip_interface* device, mip_3dm_odometer_command_mode* mode_out, float* scaling_out, float* uncertainty_out); -mip_cmd_result mip_3dm_save_odometer(struct mip_interface* device); -mip_cmd_result mip_3dm_load_odometer(struct mip_interface* device); -mip_cmd_result mip_3dm_default_odometer(struct mip_interface* device); +mip_cmd_result mip_3dm_write_odometer(mip_interface* device, mip_3dm_odometer_command_mode mode, float scaling, float uncertainty); +mip_cmd_result mip_3dm_read_odometer(mip_interface* device, mip_3dm_odometer_command_mode* mode_out, float* scaling_out, float* uncertainty_out); +mip_cmd_result mip_3dm_save_odometer(mip_interface* device); +mip_cmd_result mip_3dm_load_odometer(mip_interface* device); +mip_cmd_result mip_3dm_default_odometer(mip_interface* device); ///@} /// @@ -1299,45 +1438,57 @@ mip_cmd_result mip_3dm_default_odometer(struct mip_interface* device); /// ///@{ -typedef uint8_t mip_3dm_get_event_support_command_query; -static const mip_3dm_get_event_support_command_query MIP_3DM_GET_EVENT_SUPPORT_COMMAND_QUERY_TRIGGER_TYPES = 1; ///< Query the supported trigger types and max count for each. -static const mip_3dm_get_event_support_command_query MIP_3DM_GET_EVENT_SUPPORT_COMMAND_QUERY_ACTION_TYPES = 2; ///< Query the supported action types and max count for each. +enum mip_3dm_get_event_support_command_query +{ + MIP_3DM_GET_EVENT_SUPPORT_COMMAND_QUERY_TRIGGER_TYPES = 1, ///< Query the supported trigger types and max count for each. + MIP_3DM_GET_EVENT_SUPPORT_COMMAND_QUERY_ACTION_TYPES = 2, ///< Query the supported action types and max count for each. +}; +typedef enum mip_3dm_get_event_support_command_query mip_3dm_get_event_support_command_query; + +inline void insert_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_query self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, mip_3dm_get_event_support_command_query* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} struct mip_3dm_get_event_support_command_info { uint8_t type; ///< Trigger or action type, as defined in the respective setup command. uint8_t count; ///< This is the maximum number of instances supported for this type. - }; typedef struct mip_3dm_get_event_support_command_info mip_3dm_get_event_support_command_info; + +void insert_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_info* self); +void extract_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, mip_3dm_get_event_support_command_info* self); + + struct mip_3dm_get_event_support_command { mip_3dm_get_event_support_command_query query; ///< What type of information to retrieve. - }; typedef struct mip_3dm_get_event_support_command mip_3dm_get_event_support_command; + void insert_mip_3dm_get_event_support_command(microstrain_serializer* serializer, const mip_3dm_get_event_support_command* self); void extract_mip_3dm_get_event_support_command(microstrain_serializer* serializer, mip_3dm_get_event_support_command* self); -void insert_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_query self); -void extract_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, mip_3dm_get_event_support_command_query* self); - -void insert_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_info* self); -void extract_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, mip_3dm_get_event_support_command_info* self); - struct mip_3dm_get_event_support_response { mip_3dm_get_event_support_command_query query; ///< Query type specified in the command. uint8_t max_instances; ///< Number of slots available. The 'instance' number for the configuration or control commands must be between 1 and this value. uint8_t num_entries; ///< Number of supported types. mip_3dm_get_event_support_command_info entries[126]; ///< List of supported types. - }; typedef struct mip_3dm_get_event_support_response mip_3dm_get_event_support_response; + void insert_mip_3dm_get_event_support_response(microstrain_serializer* serializer, const mip_3dm_get_event_support_response* self); void extract_mip_3dm_get_event_support_response(microstrain_serializer* serializer, mip_3dm_get_event_support_response* self); -mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_get_event_support_command_query query, uint8_t* max_instances_out, uint8_t* num_entries_out, uint8_t num_entries_out_max, mip_3dm_get_event_support_command_info* entries_out); +mip_cmd_result mip_3dm_get_event_support(mip_interface* device, mip_3dm_get_event_support_command_query query, uint8_t* max_instances_out, uint8_t* num_entries_out, uint8_t num_entries_out_max, mip_3dm_get_event_support_command_info* entries_out); ///@} /// @@ -1356,41 +1507,53 @@ mip_cmd_result mip_3dm_get_event_support(struct mip_interface* device, mip_3dm_g /// ///@{ -typedef uint8_t mip_3dm_event_control_command_mode; -static const mip_3dm_event_control_command_mode MIP_3DM_EVENT_CONTROL_COMMAND_MODE_DISABLED = 0; ///< Trigger is disabled. -static const mip_3dm_event_control_command_mode MIP_3DM_EVENT_CONTROL_COMMAND_MODE_ENABLED = 1; ///< Trigger is enabled and will work normally. -static const mip_3dm_event_control_command_mode MIP_3DM_EVENT_CONTROL_COMMAND_MODE_TEST = 2; ///< Forces the trigger to the active state for testing purposes. -static const mip_3dm_event_control_command_mode MIP_3DM_EVENT_CONTROL_COMMAND_MODE_TEST_PULSE = 3; ///< Trigger is forced to the active state for one event cycle only. After the test cycle, the mode reverts to the previous state (either enabled or disabled). +enum mip_3dm_event_control_command_mode +{ + MIP_3DM_EVENT_CONTROL_COMMAND_MODE_DISABLED = 0, ///< Trigger is disabled. + MIP_3DM_EVENT_CONTROL_COMMAND_MODE_ENABLED = 1, ///< Trigger is enabled and will work normally. + MIP_3DM_EVENT_CONTROL_COMMAND_MODE_TEST = 2, ///< Forces the trigger to the active state for testing purposes. + MIP_3DM_EVENT_CONTROL_COMMAND_MODE_TEST_PULSE = 3, ///< Trigger is forced to the active state for one event cycle only. After the test cycle, the mode reverts to the previous state (either enabled or disabled). +}; +typedef enum mip_3dm_event_control_command_mode mip_3dm_event_control_command_mode; + +inline void insert_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, const mip_3dm_event_control_command_mode self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, mip_3dm_event_control_command_mode* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_event_control_command { mip_function_selector function; uint8_t instance; ///< Trigger instance to affect. 0 can be used to apply the mode to all configured triggers, except when the function selector is READ. mip_3dm_event_control_command_mode mode; ///< How to change the trigger state. Except when instance is 0, the corresponding trigger must be configured, i.e. not have type 0. - }; typedef struct mip_3dm_event_control_command mip_3dm_event_control_command; + void insert_mip_3dm_event_control_command(microstrain_serializer* serializer, const mip_3dm_event_control_command* self); void extract_mip_3dm_event_control_command(microstrain_serializer* serializer, mip_3dm_event_control_command* self); -void insert_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, const mip_3dm_event_control_command_mode self); -void extract_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, mip_3dm_event_control_command_mode* self); - struct mip_3dm_event_control_response { uint8_t instance; ///< Trigger instance to affect. 0 can be used to apply the mode to all configured triggers, except when the function selector is READ. mip_3dm_event_control_command_mode mode; ///< How to change the trigger state. Except when instance is 0, the corresponding trigger must be configured, i.e. not have type 0. - }; typedef struct mip_3dm_event_control_response mip_3dm_event_control_response; + void insert_mip_3dm_event_control_response(microstrain_serializer* serializer, const mip_3dm_event_control_response* self); void extract_mip_3dm_event_control_response(microstrain_serializer* serializer, mip_3dm_event_control_response* self); -mip_cmd_result mip_3dm_write_event_control(struct mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode mode); -mip_cmd_result mip_3dm_read_event_control(struct mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode* mode_out); -mip_cmd_result mip_3dm_save_event_control(struct mip_interface* device, uint8_t instance); -mip_cmd_result mip_3dm_load_event_control(struct mip_interface* device, uint8_t instance); -mip_cmd_result mip_3dm_default_event_control(struct mip_interface* device, uint8_t instance); +mip_cmd_result mip_3dm_write_event_control(mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode mode); +mip_cmd_result mip_3dm_read_event_control(mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode* mode_out); +mip_cmd_result mip_3dm_save_event_control(mip_interface* device, uint8_t instance); +mip_cmd_result mip_3dm_load_event_control(mip_interface* device, uint8_t instance); +mip_cmd_result mip_3dm_default_event_control(mip_interface* device, uint8_t instance); ///@} /// @@ -1405,41 +1568,49 @@ static const mip_3dm_get_event_trigger_status_command_status MIP_3DM_GET_EVENT_T static const mip_3dm_get_event_trigger_status_command_status MIP_3DM_GET_EVENT_TRIGGER_STATUS_COMMAND_STATUS_ENABLED = 0x02; ///< True if the trigger is enabled. static const mip_3dm_get_event_trigger_status_command_status MIP_3DM_GET_EVENT_TRIGGER_STATUS_COMMAND_STATUS_TEST = 0x04; ///< True if the trigger is in test mode. static const mip_3dm_get_event_trigger_status_command_status MIP_3DM_GET_EVENT_TRIGGER_STATUS_COMMAND_STATUS_ALL = 0x07; +inline void insert_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} struct mip_3dm_get_event_trigger_status_command_entry { uint8_t type; ///< Configured trigger type. mip_3dm_get_event_trigger_status_command_status status; ///< Trigger status. - }; typedef struct mip_3dm_get_event_trigger_status_command_entry mip_3dm_get_event_trigger_status_command_entry; + +void insert_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_entry* self); +void extract_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_entry* self); + + struct mip_3dm_get_event_trigger_status_command { uint8_t requested_count; ///< Number of entries requested. If 0, requests all trigger slots. uint8_t requested_instances[20]; ///< List of trigger instances to query. - }; typedef struct mip_3dm_get_event_trigger_status_command mip_3dm_get_event_trigger_status_command; + void insert_mip_3dm_get_event_trigger_status_command(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command* self); void extract_mip_3dm_get_event_trigger_status_command(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command* self); -void insert_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self); -void extract_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self); - -void insert_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_entry* self); -void extract_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_entry* self); - struct mip_3dm_get_event_trigger_status_response { uint8_t count; ///< Number of entries requested. If requested_count was 0, this is the number of supported trigger slots. mip_3dm_get_event_trigger_status_command_entry triggers[20]; ///< A list of the configured triggers. Entries are in the order requested, or in increasing order if count was 0. - }; typedef struct mip_3dm_get_event_trigger_status_response mip_3dm_get_event_trigger_status_response; + void insert_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_response* self); void extract_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_response* self); -mip_cmd_result mip_3dm_get_event_trigger_status(struct mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_trigger_status_command_entry* triggers_out); +mip_cmd_result mip_3dm_get_event_trigger_status(mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_trigger_status_command_entry* triggers_out); ///@} /// @@ -1452,33 +1623,34 @@ struct mip_3dm_get_event_action_status_command_entry { uint8_t action_type; ///< Configured action type. uint8_t trigger_id; ///< Associated trigger instance. - }; typedef struct mip_3dm_get_event_action_status_command_entry mip_3dm_get_event_action_status_command_entry; + +void insert_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command_entry* self); +void extract_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command_entry* self); + + struct mip_3dm_get_event_action_status_command { uint8_t requested_count; ///< Number of entries requested. If 0, requests all action slots. uint8_t requested_instances[20]; ///< List of action instances to query. - }; typedef struct mip_3dm_get_event_action_status_command mip_3dm_get_event_action_status_command; + void insert_mip_3dm_get_event_action_status_command(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command* self); void extract_mip_3dm_get_event_action_status_command(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command* self); -void insert_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command_entry* self); -void extract_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command_entry* self); - struct mip_3dm_get_event_action_status_response { uint8_t count; ///< Number of entries requested. If requested_count was 0, this is the number of supported action slots. mip_3dm_get_event_action_status_command_entry actions[20]; ///< A list of the configured actions. Entries are in the order requested, or in increasing order if count was 0. - }; typedef struct mip_3dm_get_event_action_status_response mip_3dm_get_event_action_status_response; + void insert_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_response* self); void extract_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, mip_3dm_get_event_action_status_response* self); -mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_action_status_command_entry* actions_out); +mip_cmd_result mip_3dm_get_event_action_status(mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_action_status_command_entry* actions_out); ///@} /// @@ -1488,22 +1660,55 @@ mip_cmd_result mip_3dm_get_event_action_status(struct mip_interface* device, uin /// ///@{ -typedef uint8_t mip_3dm_event_trigger_command_gpio_params_mode; -static const mip_3dm_event_trigger_command_gpio_params_mode MIP_3DM_EVENT_TRIGGER_COMMAND_GPIO_PARAMS_MODE_DISABLED = 0; ///< The pin will have no effect and the trigger will never activate. -static const mip_3dm_event_trigger_command_gpio_params_mode MIP_3DM_EVENT_TRIGGER_COMMAND_GPIO_PARAMS_MODE_WHILE_HIGH = 1; ///< The trigger will be active while the pin is high. -static const mip_3dm_event_trigger_command_gpio_params_mode MIP_3DM_EVENT_TRIGGER_COMMAND_GPIO_PARAMS_MODE_WHILE_LOW = 2; ///< The trigger will be active while the pin is low. -static const mip_3dm_event_trigger_command_gpio_params_mode MIP_3DM_EVENT_TRIGGER_COMMAND_GPIO_PARAMS_MODE_EDGE = 4; ///< Use if the pin is configured for timestamping via the 3DM Gpio Configuration command (0x0C41). +enum mip_3dm_event_trigger_command_gpio_params_mode +{ + MIP_3DM_EVENT_TRIGGER_COMMAND_GPIO_PARAMS_MODE_DISABLED = 0, ///< The pin will have no effect and the trigger will never activate. + MIP_3DM_EVENT_TRIGGER_COMMAND_GPIO_PARAMS_MODE_WHILE_HIGH = 1, ///< The trigger will be active while the pin is high. + MIP_3DM_EVENT_TRIGGER_COMMAND_GPIO_PARAMS_MODE_WHILE_LOW = 2, ///< The trigger will be active while the pin is low. + MIP_3DM_EVENT_TRIGGER_COMMAND_GPIO_PARAMS_MODE_EDGE = 4, ///< Use if the pin is configured for timestamping via the 3DM Gpio Configuration command (0x0C41). +}; +typedef enum mip_3dm_event_trigger_command_gpio_params_mode mip_3dm_event_trigger_command_gpio_params_mode; + +inline void insert_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_event_trigger_command_gpio_params { uint8_t pin; ///< GPIO pin number. mip_3dm_event_trigger_command_gpio_params_mode mode; ///< How the pin state affects the trigger. - }; typedef struct mip_3dm_event_trigger_command_gpio_params mip_3dm_event_trigger_command_gpio_params; -typedef uint8_t mip_3dm_event_trigger_command_threshold_params_type; -static const mip_3dm_event_trigger_command_threshold_params_type MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW = 1; ///< Window comparison. Trigger is active if low_thres <= value <= high_thres. If the thresholds are reversed, the trigger is active when value < high_thres or value > low_thres. -static const mip_3dm_event_trigger_command_threshold_params_type MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL = 2; ///< Trigger at evenly-spaced intervals. Normally used with time fields to trigger periodically. Trigger is active when (value % interval) <= int_thres. If the thresholds are reversed (high_thres < low_thres) then the trigger is active when (value % low_thres) > high_thres. + +void insert_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params* self); +void extract_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params* self); + +enum mip_3dm_event_trigger_command_threshold_params_type +{ + MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW = 1, ///< Window comparison. Trigger is active if low_thres <= value <= high_thres. If the thresholds are reversed, the trigger is active when value < high_thres or value > low_thres. + MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL = 2, ///< Trigger at evenly-spaced intervals. Normally used with time fields to trigger periodically. Trigger is active when (value % interval) <= int_thres. If the thresholds are reversed (high_thres < low_thres) then the trigger is active when (value % low_thres) > high_thres. +}; +typedef enum mip_3dm_event_trigger_command_threshold_params_type mip_3dm_event_trigger_command_threshold_params_type; + +inline void insert_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_event_trigger_command_threshold_params { @@ -1521,9 +1726,12 @@ struct mip_3dm_event_trigger_command_threshold_params double high_thres; double interval; }; - }; typedef struct mip_3dm_event_trigger_command_threshold_params mip_3dm_event_trigger_command_threshold_params; + +void insert_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params* self); +void extract_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params* self); + enum { MIP_3DM_EVENT_TRIGGER_COMMAND_COMBINATION_PARAMS_LOGIC_NEVER = 0x0000 }; enum { MIP_3DM_EVENT_TRIGGER_COMMAND_COMBINATION_PARAMS_LOGIC_ALWAYS = 0xFFFF }; enum { MIP_3DM_EVENT_TRIGGER_COMMAND_COMBINATION_PARAMS_LOGIC_NONE = 0x0001 }; @@ -1537,18 +1745,36 @@ enum { MIP_3DM_EVENT_TRIGGER_COMMAND_COMBINATION_PARAMS_LOGIC_ONLY_D = 0x0100 }; enum { MIP_3DM_EVENT_TRIGGER_COMMAND_COMBINATION_PARAMS_LOGIC_AND_AB = 0x8888 }; enum { MIP_3DM_EVENT_TRIGGER_COMMAND_COMBINATION_PARAMS_LOGIC_AB_OR_C = 0xF8F8 }; enum { MIP_3DM_EVENT_TRIGGER_COMMAND_COMBINATION_PARAMS_LOGIC_AND = 0x8000 }; + struct mip_3dm_event_trigger_command_combination_params { uint16_t logic_table; ///< The last column of a truth table describing the output given the state of each input. uint8_t input_triggers[4]; ///< List of trigger IDs for inputs. Use 0 for unused inputs. - }; typedef struct mip_3dm_event_trigger_command_combination_params mip_3dm_event_trigger_command_combination_params; -typedef uint8_t mip_3dm_event_trigger_command_type; -static const mip_3dm_event_trigger_command_type MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_NONE = 0; ///< No trigger selected. The state will always be inactive. -static const mip_3dm_event_trigger_command_type MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_GPIO = 1; ///< Trigger based on the state of a GPIO pin. See GpioParams. -static const mip_3dm_event_trigger_command_type MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_THRESHOLD = 2; ///< Compare a data quantity against a high and low threshold. See ThresholdParams. -static const mip_3dm_event_trigger_command_type MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_COMBINATION = 3; ///< Logical combination of two or more triggers. See CombinationParams. + +void insert_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_combination_params* self); +void extract_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_combination_params* self); + +enum mip_3dm_event_trigger_command_type +{ + MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_NONE = 0, ///< No trigger selected. The state will always be inactive. + MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_GPIO = 1, ///< Trigger based on the state of a GPIO pin. See GpioParams. + MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_THRESHOLD = 2, ///< Compare a data quantity against a high and low threshold. See ThresholdParams. + MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_COMBINATION = 3, ///< Logical combination of two or more triggers. See CombinationParams. +}; +typedef enum mip_3dm_event_trigger_command_type mip_3dm_event_trigger_command_type; + +inline void insert_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_type self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_type* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} union mip_3dm_event_trigger_command_parameters { @@ -1564,46 +1790,28 @@ struct mip_3dm_event_trigger_command uint8_t instance; ///< Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances. mip_3dm_event_trigger_command_type type; ///< Type of trigger to configure. mip_3dm_event_trigger_command_parameters parameters; - }; typedef struct mip_3dm_event_trigger_command mip_3dm_event_trigger_command; + void insert_mip_3dm_event_trigger_command(microstrain_serializer* serializer, const mip_3dm_event_trigger_command* self); void extract_mip_3dm_event_trigger_command(microstrain_serializer* serializer, mip_3dm_event_trigger_command* self); -void insert_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params* self); -void extract_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params* self); - -void insert_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self); -void extract_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self); - -void insert_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params* self); -void extract_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params* self); - -void insert_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self); -void extract_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self); - -void insert_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_combination_params* self); -void extract_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_combination_params* self); - -void insert_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_type self); -void extract_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_type* self); - struct mip_3dm_event_trigger_response { uint8_t instance; ///< Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances. mip_3dm_event_trigger_command_type type; ///< Type of trigger to configure. mip_3dm_event_trigger_command_parameters parameters; - }; typedef struct mip_3dm_event_trigger_response mip_3dm_event_trigger_response; + void insert_mip_3dm_event_trigger_response(microstrain_serializer* serializer, const mip_3dm_event_trigger_response* self); void extract_mip_3dm_event_trigger_response(microstrain_serializer* serializer, mip_3dm_event_trigger_response* self); -mip_cmd_result mip_3dm_write_event_trigger(struct mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type type, const mip_3dm_event_trigger_command_parameters* parameters); -mip_cmd_result mip_3dm_read_event_trigger(struct mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type* type_out, mip_3dm_event_trigger_command_parameters* parameters_out); -mip_cmd_result mip_3dm_save_event_trigger(struct mip_interface* device, uint8_t instance); -mip_cmd_result mip_3dm_load_event_trigger(struct mip_interface* device, uint8_t instance); -mip_cmd_result mip_3dm_default_event_trigger(struct mip_interface* device, uint8_t instance); +mip_cmd_result mip_3dm_write_event_trigger(mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type type, const mip_3dm_event_trigger_command_parameters* parameters); +mip_cmd_result mip_3dm_read_event_trigger(mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type* type_out, mip_3dm_event_trigger_command_parameters* parameters_out); +mip_cmd_result mip_3dm_save_event_trigger(mip_interface* device, uint8_t instance); +mip_cmd_result mip_3dm_load_event_trigger(mip_interface* device, uint8_t instance); +mip_cmd_result mip_3dm_default_event_trigger(mip_interface* device, uint8_t instance); ///@} /// @@ -1613,34 +1821,69 @@ mip_cmd_result mip_3dm_default_event_trigger(struct mip_interface* device, uint8 /// ///@{ -typedef uint8_t mip_3dm_event_action_command_gpio_params_mode; -static const mip_3dm_event_action_command_gpio_params_mode MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_DISABLED = 0; ///< Pin state will not be changed. -static const mip_3dm_event_action_command_gpio_params_mode MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_ACTIVE_HIGH = 1; ///< Pin will be set high when the trigger is active and low otherwise. -static const mip_3dm_event_action_command_gpio_params_mode MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_ACTIVE_LOW = 2; ///< Pin will be set low when the trigger is active and high otherwise. -static const mip_3dm_event_action_command_gpio_params_mode MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_ONESHOT_HIGH = 5; ///< Pin will be set high each time the trigger activates. It will not be set low. -static const mip_3dm_event_action_command_gpio_params_mode MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_ONESHOT_LOW = 6; ///< Pin will be set low each time the trigger activates. It will not be set high. -static const mip_3dm_event_action_command_gpio_params_mode MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_TOGGLE = 7; ///< Pin will change to the opposite state each time the trigger activates. +enum mip_3dm_event_action_command_gpio_params_mode +{ + MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_DISABLED = 0, ///< Pin state will not be changed. + MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_ACTIVE_HIGH = 1, ///< Pin will be set high when the trigger is active and low otherwise. + MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_ACTIVE_LOW = 2, ///< Pin will be set low when the trigger is active and high otherwise. + MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_ONESHOT_HIGH = 5, ///< Pin will be set high each time the trigger activates. It will not be set low. + MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_ONESHOT_LOW = 6, ///< Pin will be set low each time the trigger activates. It will not be set high. + MIP_3DM_EVENT_ACTION_COMMAND_GPIO_PARAMS_MODE_TOGGLE = 7, ///< Pin will change to the opposite state each time the trigger activates. +}; +typedef enum mip_3dm_event_action_command_gpio_params_mode mip_3dm_event_action_command_gpio_params_mode; + +inline void insert_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_3dm_event_action_command_gpio_params { uint8_t pin; ///< GPIO pin number. mip_3dm_event_action_command_gpio_params_mode mode; ///< Behavior of the pin. - }; typedef struct mip_3dm_event_action_command_gpio_params mip_3dm_event_action_command_gpio_params; + +void insert_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params* self); +void extract_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params* self); + struct mip_3dm_event_action_command_message_params { uint8_t desc_set; ///< MIP data descriptor set. uint16_t decimation; ///< Decimation from the base rate. If 0, a packet is emitted each time the trigger activates. Otherwise, packets will be streamed while the trigger is active. The internal decimation counter is reset if the trigger deactivates. uint8_t num_fields; ///< Number of mip fields in the packet. Limited to 12. uint8_t descriptors[20]; ///< List of field descriptors. - }; typedef struct mip_3dm_event_action_command_message_params mip_3dm_event_action_command_message_params; -typedef uint8_t mip_3dm_event_action_command_type; -static const mip_3dm_event_action_command_type MIP_3DM_EVENT_ACTION_COMMAND_TYPE_NONE = 0; ///< No action. Parameters should be empty. -static const mip_3dm_event_action_command_type MIP_3DM_EVENT_ACTION_COMMAND_TYPE_GPIO = 1; ///< Control the state of a GPIO pin. See GpioParameters. -static const mip_3dm_event_action_command_type MIP_3DM_EVENT_ACTION_COMMAND_TYPE_MESSAGE = 2; ///< Output a data packet. See MessageParameters. + +void insert_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_message_params* self); +void extract_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, mip_3dm_event_action_command_message_params* self); + +enum mip_3dm_event_action_command_type +{ + MIP_3DM_EVENT_ACTION_COMMAND_TYPE_NONE = 0, ///< No action. Parameters should be empty. + MIP_3DM_EVENT_ACTION_COMMAND_TYPE_GPIO = 1, ///< Control the state of a GPIO pin. See GpioParameters. + MIP_3DM_EVENT_ACTION_COMMAND_TYPE_MESSAGE = 2, ///< Output a data packet. See MessageParameters. +}; +typedef enum mip_3dm_event_action_command_type mip_3dm_event_action_command_type; + +inline void insert_mip_3dm_event_action_command_type(microstrain_serializer* serializer, const mip_3dm_event_action_command_type self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_3dm_event_action_command_type(microstrain_serializer* serializer, mip_3dm_event_action_command_type* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} union mip_3dm_event_action_command_parameters { @@ -1656,41 +1899,29 @@ struct mip_3dm_event_action_command uint8_t trigger; ///< Trigger ID number. mip_3dm_event_action_command_type type; ///< Type of action to configure. mip_3dm_event_action_command_parameters parameters; - }; typedef struct mip_3dm_event_action_command mip_3dm_event_action_command; + void insert_mip_3dm_event_action_command(microstrain_serializer* serializer, const mip_3dm_event_action_command* self); void extract_mip_3dm_event_action_command(microstrain_serializer* serializer, mip_3dm_event_action_command* self); -void insert_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params* self); -void extract_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params* self); - -void insert_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self); -void extract_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self); - -void insert_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_message_params* self); -void extract_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, mip_3dm_event_action_command_message_params* self); - -void insert_mip_3dm_event_action_command_type(microstrain_serializer* serializer, const mip_3dm_event_action_command_type self); -void extract_mip_3dm_event_action_command_type(microstrain_serializer* serializer, mip_3dm_event_action_command_type* self); - struct mip_3dm_event_action_response { uint8_t instance; ///< Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances. uint8_t trigger; ///< Trigger ID number. mip_3dm_event_action_command_type type; ///< Type of action to configure. mip_3dm_event_action_command_parameters parameters; - }; typedef struct mip_3dm_event_action_response mip_3dm_event_action_response; + void insert_mip_3dm_event_action_response(microstrain_serializer* serializer, const mip_3dm_event_action_response* self); void extract_mip_3dm_event_action_response(microstrain_serializer* serializer, mip_3dm_event_action_response* self); -mip_cmd_result mip_3dm_write_event_action(struct mip_interface* device, uint8_t instance, uint8_t trigger, mip_3dm_event_action_command_type type, const mip_3dm_event_action_command_parameters* parameters); -mip_cmd_result mip_3dm_read_event_action(struct mip_interface* device, uint8_t instance, uint8_t* trigger_out, mip_3dm_event_action_command_type* type_out, mip_3dm_event_action_command_parameters* parameters_out); -mip_cmd_result mip_3dm_save_event_action(struct mip_interface* device, uint8_t instance); -mip_cmd_result mip_3dm_load_event_action(struct mip_interface* device, uint8_t instance); -mip_cmd_result mip_3dm_default_event_action(struct mip_interface* device, uint8_t instance); +mip_cmd_result mip_3dm_write_event_action(mip_interface* device, uint8_t instance, uint8_t trigger, mip_3dm_event_action_command_type type, const mip_3dm_event_action_command_parameters* parameters); +mip_cmd_result mip_3dm_read_event_action(mip_interface* device, uint8_t instance, uint8_t* trigger_out, mip_3dm_event_action_command_type* type_out, mip_3dm_event_action_command_parameters* parameters_out); +mip_cmd_result mip_3dm_save_event_action(mip_interface* device, uint8_t instance); +mip_cmd_result mip_3dm_load_event_action(mip_interface* device, uint8_t instance); +mip_cmd_result mip_3dm_default_event_action(mip_interface* device, uint8_t instance); ///@} /// @@ -1706,26 +1937,26 @@ struct mip_3dm_accel_bias_command { mip_function_selector function; mip_vector3f bias; ///< accelerometer bias in the sensor frame (x,y,z) [g] - }; typedef struct mip_3dm_accel_bias_command mip_3dm_accel_bias_command; + void insert_mip_3dm_accel_bias_command(microstrain_serializer* serializer, const mip_3dm_accel_bias_command* self); void extract_mip_3dm_accel_bias_command(microstrain_serializer* serializer, mip_3dm_accel_bias_command* self); struct mip_3dm_accel_bias_response { mip_vector3f bias; ///< accelerometer bias in the sensor frame (x,y,z) [g] - }; typedef struct mip_3dm_accel_bias_response mip_3dm_accel_bias_response; + void insert_mip_3dm_accel_bias_response(microstrain_serializer* serializer, const mip_3dm_accel_bias_response* self); void extract_mip_3dm_accel_bias_response(microstrain_serializer* serializer, mip_3dm_accel_bias_response* self); -mip_cmd_result mip_3dm_write_accel_bias(struct mip_interface* device, const float* bias); -mip_cmd_result mip_3dm_read_accel_bias(struct mip_interface* device, float* bias_out); -mip_cmd_result mip_3dm_save_accel_bias(struct mip_interface* device); -mip_cmd_result mip_3dm_load_accel_bias(struct mip_interface* device); -mip_cmd_result mip_3dm_default_accel_bias(struct mip_interface* device); +mip_cmd_result mip_3dm_write_accel_bias(mip_interface* device, const float* bias); +mip_cmd_result mip_3dm_read_accel_bias(mip_interface* device, float* bias_out); +mip_cmd_result mip_3dm_save_accel_bias(mip_interface* device); +mip_cmd_result mip_3dm_load_accel_bias(mip_interface* device); +mip_cmd_result mip_3dm_default_accel_bias(mip_interface* device); ///@} /// @@ -1741,26 +1972,26 @@ struct mip_3dm_gyro_bias_command { mip_function_selector function; mip_vector3f bias; ///< gyro bias in the sensor frame (x,y,z) [radians/second] - }; typedef struct mip_3dm_gyro_bias_command mip_3dm_gyro_bias_command; + void insert_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, const mip_3dm_gyro_bias_command* self); void extract_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, mip_3dm_gyro_bias_command* self); struct mip_3dm_gyro_bias_response { mip_vector3f bias; ///< gyro bias in the sensor frame (x,y,z) [radians/second] - }; typedef struct mip_3dm_gyro_bias_response mip_3dm_gyro_bias_response; + void insert_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_gyro_bias_response* self); void extract_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_gyro_bias_response* self); -mip_cmd_result mip_3dm_write_gyro_bias(struct mip_interface* device, const float* bias); -mip_cmd_result mip_3dm_read_gyro_bias(struct mip_interface* device, float* bias_out); -mip_cmd_result mip_3dm_save_gyro_bias(struct mip_interface* device); -mip_cmd_result mip_3dm_load_gyro_bias(struct mip_interface* device); -mip_cmd_result mip_3dm_default_gyro_bias(struct mip_interface* device); +mip_cmd_result mip_3dm_write_gyro_bias(mip_interface* device, const float* bias); +mip_cmd_result mip_3dm_read_gyro_bias(mip_interface* device, float* bias_out); +mip_cmd_result mip_3dm_save_gyro_bias(mip_interface* device); +mip_cmd_result mip_3dm_load_gyro_bias(mip_interface* device); +mip_cmd_result mip_3dm_default_gyro_bias(mip_interface* device); ///@} /// @@ -1778,22 +2009,22 @@ mip_cmd_result mip_3dm_default_gyro_bias(struct mip_interface* device); struct mip_3dm_capture_gyro_bias_command { uint16_t averaging_time_ms; ///< Averaging time [milliseconds] - }; typedef struct mip_3dm_capture_gyro_bias_command mip_3dm_capture_gyro_bias_command; + void insert_mip_3dm_capture_gyro_bias_command(microstrain_serializer* serializer, const mip_3dm_capture_gyro_bias_command* self); void extract_mip_3dm_capture_gyro_bias_command(microstrain_serializer* serializer, mip_3dm_capture_gyro_bias_command* self); struct mip_3dm_capture_gyro_bias_response { mip_vector3f bias; ///< gyro bias in the sensor frame (x,y,z) [radians/second] - }; typedef struct mip_3dm_capture_gyro_bias_response mip_3dm_capture_gyro_bias_response; + void insert_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_capture_gyro_bias_response* self); void extract_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_capture_gyro_bias_response* self); -mip_cmd_result mip_3dm_capture_gyro_bias(struct mip_interface* device, uint16_t averaging_time_ms, float* bias_out); +mip_cmd_result mip_3dm_capture_gyro_bias(mip_interface* device, uint16_t averaging_time_ms, float* bias_out); ///@} /// @@ -1813,26 +2044,26 @@ struct mip_3dm_mag_hard_iron_offset_command { mip_function_selector function; mip_vector3f offset; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] - }; typedef struct mip_3dm_mag_hard_iron_offset_command mip_3dm_mag_hard_iron_offset_command; + void insert_mip_3dm_mag_hard_iron_offset_command(microstrain_serializer* serializer, const mip_3dm_mag_hard_iron_offset_command* self); void extract_mip_3dm_mag_hard_iron_offset_command(microstrain_serializer* serializer, mip_3dm_mag_hard_iron_offset_command* self); struct mip_3dm_mag_hard_iron_offset_response { mip_vector3f offset; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] - }; typedef struct mip_3dm_mag_hard_iron_offset_response mip_3dm_mag_hard_iron_offset_response; + void insert_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, const mip_3dm_mag_hard_iron_offset_response* self); void extract_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, mip_3dm_mag_hard_iron_offset_response* self); -mip_cmd_result mip_3dm_write_mag_hard_iron_offset(struct mip_interface* device, const float* offset); -mip_cmd_result mip_3dm_read_mag_hard_iron_offset(struct mip_interface* device, float* offset_out); -mip_cmd_result mip_3dm_save_mag_hard_iron_offset(struct mip_interface* device); -mip_cmd_result mip_3dm_load_mag_hard_iron_offset(struct mip_interface* device); -mip_cmd_result mip_3dm_default_mag_hard_iron_offset(struct mip_interface* device); +mip_cmd_result mip_3dm_write_mag_hard_iron_offset(mip_interface* device, const float* offset); +mip_cmd_result mip_3dm_read_mag_hard_iron_offset(mip_interface* device, float* offset_out); +mip_cmd_result mip_3dm_save_mag_hard_iron_offset(mip_interface* device); +mip_cmd_result mip_3dm_load_mag_hard_iron_offset(mip_interface* device); +mip_cmd_result mip_3dm_default_mag_hard_iron_offset(mip_interface* device); ///@} /// @@ -1856,26 +2087,26 @@ struct mip_3dm_mag_soft_iron_matrix_command { mip_function_selector function; mip_matrix3f offset; ///< soft iron matrix [dimensionless] - }; typedef struct mip_3dm_mag_soft_iron_matrix_command mip_3dm_mag_soft_iron_matrix_command; + void insert_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_command* self); void extract_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* serializer, mip_3dm_mag_soft_iron_matrix_command* self); struct mip_3dm_mag_soft_iron_matrix_response { mip_matrix3f offset; ///< soft iron matrix [dimensionless] - }; typedef struct mip_3dm_mag_soft_iron_matrix_response mip_3dm_mag_soft_iron_matrix_response; + void insert_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_response* self); void extract_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, mip_3dm_mag_soft_iron_matrix_response* self); -mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(struct mip_interface* device, const float* offset); -mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(struct mip_interface* device, float* offset_out); -mip_cmd_result mip_3dm_save_mag_soft_iron_matrix(struct mip_interface* device); -mip_cmd_result mip_3dm_load_mag_soft_iron_matrix(struct mip_interface* device); -mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(struct mip_interface* device); +mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(mip_interface* device, const float* offset); +mip_cmd_result mip_3dm_read_mag_soft_iron_matrix(mip_interface* device, float* offset_out); +mip_cmd_result mip_3dm_save_mag_soft_iron_matrix(mip_interface* device); +mip_cmd_result mip_3dm_load_mag_soft_iron_matrix(mip_interface* device); +mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(mip_interface* device); ///@} /// @@ -1889,26 +2120,26 @@ struct mip_3dm_coning_sculling_enable_command { mip_function_selector function; bool enable; ///< If true, coning and sculling compensation is enabled. - }; typedef struct mip_3dm_coning_sculling_enable_command mip_3dm_coning_sculling_enable_command; + void insert_mip_3dm_coning_sculling_enable_command(microstrain_serializer* serializer, const mip_3dm_coning_sculling_enable_command* self); void extract_mip_3dm_coning_sculling_enable_command(microstrain_serializer* serializer, mip_3dm_coning_sculling_enable_command* self); struct mip_3dm_coning_sculling_enable_response { bool enable; ///< If true, coning and sculling compensation is enabled. - }; typedef struct mip_3dm_coning_sculling_enable_response mip_3dm_coning_sculling_enable_response; + void insert_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, const mip_3dm_coning_sculling_enable_response* self); void extract_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, mip_3dm_coning_sculling_enable_response* self); -mip_cmd_result mip_3dm_write_coning_sculling_enable(struct mip_interface* device, bool enable); -mip_cmd_result mip_3dm_read_coning_sculling_enable(struct mip_interface* device, bool* enable_out); -mip_cmd_result mip_3dm_save_coning_sculling_enable(struct mip_interface* device); -mip_cmd_result mip_3dm_load_coning_sculling_enable(struct mip_interface* device); -mip_cmd_result mip_3dm_default_coning_sculling_enable(struct mip_interface* device); +mip_cmd_result mip_3dm_write_coning_sculling_enable(mip_interface* device, bool enable); +mip_cmd_result mip_3dm_read_coning_sculling_enable(mip_interface* device, bool* enable_out); +mip_cmd_result mip_3dm_save_coning_sculling_enable(mip_interface* device); +mip_cmd_result mip_3dm_load_coning_sculling_enable(mip_interface* device); +mip_cmd_result mip_3dm_default_coning_sculling_enable(mip_interface* device); ///@} /// @@ -1948,9 +2179,9 @@ struct mip_3dm_sensor_2_vehicle_transform_euler_command float roll; ///< [radians] float pitch; ///< [radians] float yaw; ///< [radians] - }; typedef struct mip_3dm_sensor_2_vehicle_transform_euler_command mip_3dm_sensor_2_vehicle_transform_euler_command; + void insert_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_command* self); void extract_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_command* self); @@ -1959,17 +2190,17 @@ struct mip_3dm_sensor_2_vehicle_transform_euler_response float roll; ///< [radians] float pitch; ///< [radians] float yaw; ///< [radians] - }; typedef struct mip_3dm_sensor_2_vehicle_transform_euler_response mip_3dm_sensor_2_vehicle_transform_euler_response; + void insert_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_response* self); void extract_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_response* self); -mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_euler(struct mip_interface* device, float roll, float pitch, float yaw); -mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out); -mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_euler(struct mip_interface* device); -mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_euler(struct mip_interface* device); -mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(struct mip_interface* device); +mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_euler(mip_interface* device, float roll, float pitch, float yaw); +mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_euler(mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out); +mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_euler(mip_interface* device); +mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_euler(mip_interface* device); +mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(mip_interface* device); ///@} /// @@ -2015,26 +2246,26 @@ struct mip_3dm_sensor_2_vehicle_transform_quaternion_command { mip_function_selector function; mip_quatf q; ///< Unit length quaternion representing transform [w, i, j, k] - }; typedef struct mip_3dm_sensor_2_vehicle_transform_quaternion_command mip_3dm_sensor_2_vehicle_transform_quaternion_command; + void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_command* self); void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_command* self); struct mip_3dm_sensor_2_vehicle_transform_quaternion_response { mip_quatf q; ///< Unit length quaternion representing transform [w, i, j, k] - }; typedef struct mip_3dm_sensor_2_vehicle_transform_quaternion_response mip_3dm_sensor_2_vehicle_transform_quaternion_response; + void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_response* self); void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_response* self); -mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(struct mip_interface* device, const float* q); -mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(struct mip_interface* device, float* q_out); -mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_quaternion(struct mip_interface* device); -mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_quaternion(struct mip_interface* device); -mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(struct mip_interface* device); +mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(mip_interface* device, const float* q); +mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_quaternion(mip_interface* device, float* q_out); +mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_quaternion(mip_interface* device); +mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_quaternion(mip_interface* device); +mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(mip_interface* device); ///@} /// @@ -2078,26 +2309,26 @@ struct mip_3dm_sensor_2_vehicle_transform_dcm_command { mip_function_selector function; mip_matrix3f dcm; ///< 3 x 3 direction cosine matrix, stored in row-major order - }; typedef struct mip_3dm_sensor_2_vehicle_transform_dcm_command mip_3dm_sensor_2_vehicle_transform_dcm_command; + void insert_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_command* self); void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_command* self); struct mip_3dm_sensor_2_vehicle_transform_dcm_response { mip_matrix3f dcm; ///< 3 x 3 direction cosine matrix, stored in row-major order - }; typedef struct mip_3dm_sensor_2_vehicle_transform_dcm_response mip_3dm_sensor_2_vehicle_transform_dcm_response; + void insert_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_response* self); void extract_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_response* self); -mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(struct mip_interface* device, const float* dcm); -mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(struct mip_interface* device, float* dcm_out); -mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_dcm(struct mip_interface* device); -mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_dcm(struct mip_interface* device); -mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(struct mip_interface* device); +mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(mip_interface* device, const float* dcm); +mip_cmd_result mip_3dm_read_sensor_2_vehicle_transform_dcm(mip_interface* device, float* dcm_out); +mip_cmd_result mip_3dm_save_sensor_2_vehicle_transform_dcm(mip_interface* device); +mip_cmd_result mip_3dm_load_sensor_2_vehicle_transform_dcm(mip_interface* device); +mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(mip_interface* device); ///@} /// @@ -2118,9 +2349,9 @@ struct mip_3dm_complementary_filter_command bool heading_enable; ///< Enable Heading corrections (only available on devices with magnetometer) float pitch_roll_time_constant; ///< Time constant associated with the pitch/roll corrections [s] float heading_time_constant; ///< Time constant associated with the heading corrections [s] - }; typedef struct mip_3dm_complementary_filter_command mip_3dm_complementary_filter_command; + void insert_mip_3dm_complementary_filter_command(microstrain_serializer* serializer, const mip_3dm_complementary_filter_command* self); void extract_mip_3dm_complementary_filter_command(microstrain_serializer* serializer, mip_3dm_complementary_filter_command* self); @@ -2130,17 +2361,17 @@ struct mip_3dm_complementary_filter_response bool heading_enable; ///< Enable Heading corrections (only available on devices with magnetometer) float pitch_roll_time_constant; ///< Time constant associated with the pitch/roll corrections [s] float heading_time_constant; ///< Time constant associated with the heading corrections [s] - }; typedef struct mip_3dm_complementary_filter_response mip_3dm_complementary_filter_response; + void insert_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, const mip_3dm_complementary_filter_response* self); void extract_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, mip_3dm_complementary_filter_response* self); -mip_cmd_result mip_3dm_write_complementary_filter(struct mip_interface* device, bool pitch_roll_enable, bool heading_enable, float pitch_roll_time_constant, float heading_time_constant); -mip_cmd_result mip_3dm_read_complementary_filter(struct mip_interface* device, bool* pitch_roll_enable_out, bool* heading_enable_out, float* pitch_roll_time_constant_out, float* heading_time_constant_out); -mip_cmd_result mip_3dm_save_complementary_filter(struct mip_interface* device); -mip_cmd_result mip_3dm_load_complementary_filter(struct mip_interface* device); -mip_cmd_result mip_3dm_default_complementary_filter(struct mip_interface* device); +mip_cmd_result mip_3dm_write_complementary_filter(mip_interface* device, bool pitch_roll_enable, bool heading_enable, float pitch_roll_time_constant, float heading_time_constant); +mip_cmd_result mip_3dm_read_complementary_filter(mip_interface* device, bool* pitch_roll_enable_out, bool* heading_enable_out, float* pitch_roll_time_constant_out, float* heading_time_constant_out); +mip_cmd_result mip_3dm_save_complementary_filter(mip_interface* device); +mip_cmd_result mip_3dm_load_complementary_filter(mip_interface* device); +mip_cmd_result mip_3dm_default_complementary_filter(mip_interface* device); ///@} /// @@ -2162,9 +2393,9 @@ struct mip_3dm_sensor_range_command mip_function_selector function; mip_sensor_range_type sensor; ///< Which type of sensor will get the new range value. uint8_t setting; ///< Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value. - }; typedef struct mip_3dm_sensor_range_command mip_3dm_sensor_range_command; + void insert_mip_3dm_sensor_range_command(microstrain_serializer* serializer, const mip_3dm_sensor_range_command* self); void extract_mip_3dm_sensor_range_command(microstrain_serializer* serializer, mip_3dm_sensor_range_command* self); @@ -2172,17 +2403,17 @@ struct mip_3dm_sensor_range_response { mip_sensor_range_type sensor; ///< Which type of sensor will get the new range value. uint8_t setting; ///< Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value. - }; typedef struct mip_3dm_sensor_range_response mip_3dm_sensor_range_response; + void insert_mip_3dm_sensor_range_response(microstrain_serializer* serializer, const mip_3dm_sensor_range_response* self); void extract_mip_3dm_sensor_range_response(microstrain_serializer* serializer, mip_3dm_sensor_range_response* self); -mip_cmd_result mip_3dm_write_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t setting); -mip_cmd_result mip_3dm_read_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t* setting_out); -mip_cmd_result mip_3dm_save_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor); -mip_cmd_result mip_3dm_load_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor); -mip_cmd_result mip_3dm_default_sensor_range(struct mip_interface* device, mip_sensor_range_type sensor); +mip_cmd_result mip_3dm_write_sensor_range(mip_interface* device, mip_sensor_range_type sensor, uint8_t setting); +mip_cmd_result mip_3dm_read_sensor_range(mip_interface* device, mip_sensor_range_type sensor, uint8_t* setting_out); +mip_cmd_result mip_3dm_save_sensor_range(mip_interface* device, mip_sensor_range_type sensor); +mip_cmd_result mip_3dm_load_sensor_range(mip_interface* device, mip_sensor_range_type sensor); +mip_cmd_result mip_3dm_default_sensor_range(mip_interface* device, mip_sensor_range_type sensor); ///@} /// @@ -2199,33 +2430,34 @@ struct mip_3dm_calibrated_sensor_ranges_command_entry { uint8_t setting; ///< The value used in the 3DM Sensor Range command and response. float range; ///< The actual range value. Units depend on the sensor type. - }; typedef struct mip_3dm_calibrated_sensor_ranges_command_entry mip_3dm_calibrated_sensor_ranges_command_entry; + +void insert_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command_entry* self); +void extract_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command_entry* self); + + struct mip_3dm_calibrated_sensor_ranges_command { mip_sensor_range_type sensor; ///< The sensor to query. Cannot be ALL. - }; typedef struct mip_3dm_calibrated_sensor_ranges_command mip_3dm_calibrated_sensor_ranges_command; + void insert_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command* self); void extract_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command* self); -void insert_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command_entry* self); -void extract_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command_entry* self); - struct mip_3dm_calibrated_sensor_ranges_response { mip_sensor_range_type sensor; ///< The sensor type from the command. uint8_t num_ranges; ///< Number of supported ranges. mip_3dm_calibrated_sensor_ranges_command_entry ranges[50]; ///< List of possible range settings. - }; typedef struct mip_3dm_calibrated_sensor_ranges_response mip_3dm_calibrated_sensor_ranges_response; + void insert_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_response* self); void extract_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_response* self); -mip_cmd_result mip_3dm_calibrated_sensor_ranges(struct mip_interface* device, mip_sensor_range_type sensor, uint8_t* num_ranges_out, uint8_t num_ranges_out_max, mip_3dm_calibrated_sensor_ranges_command_entry* ranges_out); +mip_cmd_result mip_3dm_calibrated_sensor_ranges(mip_interface* device, mip_sensor_range_type sensor, uint8_t* num_ranges_out, uint8_t num_ranges_out_max, mip_3dm_calibrated_sensor_ranges_command_entry* ranges_out); ///@} /// @@ -2256,9 +2488,9 @@ struct mip_3dm_lowpass_filter_command bool enable; ///< The filter will be enabled if this is true. bool manual; ///< If false, the frequency parameter is ignored and the filter will track to half of the configured message format frequency. float frequency; ///< Cutoff frequency in Hz. This will return the actual frequency when read out in automatic mode. - }; typedef struct mip_3dm_lowpass_filter_command mip_3dm_lowpass_filter_command; + void insert_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, const mip_3dm_lowpass_filter_command* self); void extract_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, mip_3dm_lowpass_filter_command* self); @@ -2269,17 +2501,17 @@ struct mip_3dm_lowpass_filter_response bool enable; ///< The filter will be enabled if this is true. bool manual; ///< If false, the frequency parameter is ignored and the filter will track to half of the configured message format frequency. float frequency; ///< Cutoff frequency in Hz. This will return the actual frequency when read out in automatic mode. - }; typedef struct mip_3dm_lowpass_filter_response mip_3dm_lowpass_filter_response; + void insert_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_lowpass_filter_response* self); void extract_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_lowpass_filter_response* self); -mip_cmd_result mip_3dm_write_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool enable, bool manual, float frequency); -mip_cmd_result mip_3dm_read_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool* enable_out, bool* manual_out, float* frequency_out); -mip_cmd_result mip_3dm_save_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc); -mip_cmd_result mip_3dm_load_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc); -mip_cmd_result mip_3dm_default_lowpass_filter(struct mip_interface* device, uint8_t desc_set, uint8_t field_desc); +mip_cmd_result mip_3dm_write_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool enable, bool manual, float frequency); +mip_cmd_result mip_3dm_read_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool* enable_out, bool* manual_out, float* frequency_out); +mip_cmd_result mip_3dm_save_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc); +mip_cmd_result mip_3dm_load_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc); +mip_cmd_result mip_3dm_default_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc); ///@} /// diff --git a/src/c/mip/definitions/commands_aiding.c b/src/c/mip/definitions/commands_aiding.c index fc2ee182c..7beb7f79b 100644 --- a/src/c/mip/definitions/commands_aiding.c +++ b/src/c/mip/definitions/commands_aiding.c @@ -13,54 +13,35 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions +// Mip Fields //////////////////////////////////////////////////////////////////////////////// void insert_mip_time(microstrain_serializer* serializer, const mip_time* self) { insert_mip_time_timebase(serializer, self->timebase); - + microstrain_insert_u8(serializer, self->reserved); - + microstrain_insert_u64(serializer, self->nanoseconds); } void extract_mip_time(microstrain_serializer* serializer, mip_time* self) { extract_mip_time_timebase(serializer, &self->timebase); - + microstrain_extract_u8(serializer, &self->reserved); - + microstrain_extract_u64(serializer, &self->nanoseconds); } -void insert_mip_time_timebase(microstrain_serializer* serializer, const mip_time_timebase self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_time_timebase(microstrain_serializer* serializer, mip_time_timebase* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - - -//////////////////////////////////////////////////////////////////////////////// -// Mip Fields -//////////////////////////////////////////////////////////////////////////////// - void insert_mip_aiding_frame_config_command(microstrain_serializer* serializer, const mip_aiding_frame_config_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->frame_id); if( self->function == MIP_FUNCTION_WRITE || self->function == MIP_FUNCTION_READ ) @@ -72,8 +53,7 @@ void insert_mip_aiding_frame_config_command(microstrain_serializer* serializer, { microstrain_insert_bool(serializer, self->tracking_enabled); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->translation[i]); + insert_mip_vector3f(serializer, self->translation); if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) { @@ -90,7 +70,7 @@ void insert_mip_aiding_frame_config_command(microstrain_serializer* serializer, void extract_mip_aiding_frame_config_command(microstrain_serializer* serializer, mip_aiding_frame_config_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->frame_id); if( self->function == MIP_FUNCTION_WRITE || self->function == MIP_FUNCTION_READ ) @@ -102,8 +82,7 @@ void extract_mip_aiding_frame_config_command(microstrain_serializer* serializer, { microstrain_extract_bool(serializer, &self->tracking_enabled); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->translation[i]); + extract_mip_vector3f(serializer, self->translation); if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) { @@ -118,77 +97,21 @@ void extract_mip_aiding_frame_config_command(microstrain_serializer* serializer, } } -void insert_mip_aiding_frame_config_response(microstrain_serializer* serializer, const mip_aiding_frame_config_response* self) -{ - microstrain_insert_u8(serializer, self->frame_id); - - insert_mip_aiding_frame_config_command_format(serializer, self->format); - - microstrain_insert_bool(serializer, self->tracking_enabled); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->translation[i]); - - if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) - { - insert_mip_vector3f(serializer, self->rotation.euler); - - } - if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_QUATERNION ) - { - insert_mip_quatf(serializer, self->rotation.quaternion); - - } -} -void extract_mip_aiding_frame_config_response(microstrain_serializer* serializer, mip_aiding_frame_config_response* self) -{ - microstrain_extract_u8(serializer, &self->frame_id); - - extract_mip_aiding_frame_config_command_format(serializer, &self->format); - - microstrain_extract_bool(serializer, &self->tracking_enabled); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->translation[i]); - - if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) - { - extract_mip_vector3f(serializer, self->rotation.euler); - - } - if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_QUATERNION ) - { - extract_mip_quatf(serializer, self->rotation.quaternion); - - } -} - -void insert_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_aiding_write_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool tracking_enabled, const float* translation, const mip_aiding_frame_config_command_rotation* rotation) +mip_cmd_result mip_aiding_write_frame_config(mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool tracking_enabled, const float* translation, const mip_aiding_frame_config_command_rotation* rotation) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, frame_id); insert_mip_aiding_frame_config_command_format(&serializer, format); - + microstrain_insert_bool(&serializer, tracking_enabled); - assert(translation || (3 == 0)); + assert(translation); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, translation[i]); @@ -204,17 +127,16 @@ mip_cmd_result mip_aiding_write_frame_config(struct mip_interface* device, uint8 } assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool* tracking_enabled_out, float* translation_out, mip_aiding_frame_config_command_rotation* rotation_out) +mip_cmd_result mip_aiding_read_frame_config(mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool* tracking_enabled_out, float* translation_out, mip_aiding_frame_config_command_rotation* rotation_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, frame_id); insert_mip_aiding_frame_config_command_format(&serializer, format); @@ -222,14 +144,13 @@ mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_ assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_AIDING_FRAME_CONFIG, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_AIDING_FRAME_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &frame_id); extract_mip_aiding_frame_config_command_format(&deserializer, &format); @@ -237,7 +158,7 @@ mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_ assert(tracking_enabled_out); microstrain_extract_bool(&deserializer, tracking_enabled_out); - assert(translation_out || (3 == 0)); + assert(translation_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &translation_out[i]); @@ -251,55 +172,52 @@ mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_ extract_mip_quatf(&deserializer, rotation_out->quaternion); } - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_aiding_save_frame_config(struct mip_interface* device, uint8_t frame_id) +mip_cmd_result mip_aiding_save_frame_config(mip_interface* device, uint8_t frame_id) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, frame_id); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_load_frame_config(struct mip_interface* device, uint8_t frame_id) +mip_cmd_result mip_aiding_load_frame_config(mip_interface* device, uint8_t frame_id) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, frame_id); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_default_frame_config(struct mip_interface* device, uint8_t frame_id) +mip_cmd_result mip_aiding_default_frame_config(mip_interface* device, uint8_t frame_id) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, frame_id); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self) { @@ -322,29 +240,7 @@ void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* seri } } -void insert_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self) -{ - insert_mip_aiding_aiding_echo_control_command_mode(serializer, self->mode); - -} -void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self) -{ - extract_mip_aiding_aiding_echo_control_command_mode(serializer, &self->mode); - -} - -void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_aiding_write_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode) +mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -356,10 +252,9 @@ mip_cmd_result mip_aiding_write_aiding_echo_control(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out) +mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -370,8 +265,7 @@ mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_AIDING_ECHO_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_AIDING_ECHO_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -381,12 +275,12 @@ mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, assert(mode_out); extract_mip_aiding_aiding_echo_control_command_mode(&deserializer, mode_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_aiding_save_aiding_echo_control(struct mip_interface* device) +mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -396,10 +290,9 @@ mip_cmd_result mip_aiding_save_aiding_echo_control(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_load_aiding_echo_control(struct mip_interface* device) +mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -409,10 +302,9 @@ mip_cmd_result mip_aiding_load_aiding_echo_control(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_default_aiding_echo_control(struct mip_interface* device) +mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -422,20 +314,17 @@ mip_cmd_result mip_aiding_default_aiding_echo_control(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self) { insert_mip_time(serializer, &self->time); - + microstrain_insert_u8(serializer, self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_double(serializer, self->position[i]); + insert_mip_vector3d(serializer, self->position); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->uncertainty[i]); + insert_mip_vector3f(serializer, self->uncertainty); insert_mip_aiding_ecef_pos_command_valid_flags(serializer, self->valid_flags); @@ -443,31 +332,18 @@ void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, cons void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self) { extract_mip_time(serializer, &self->time); - + microstrain_extract_u8(serializer, &self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_double(serializer, &self->position[i]); + extract_mip_vector3d(serializer, self->position); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->uncertainty[i]); + extract_mip_vector3f(serializer, self->uncertainty); extract_mip_aiding_ecef_pos_command_valid_flags(serializer, &self->valid_flags); } -void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_aiding_ecef_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -475,14 +351,14 @@ mip_cmd_result mip_aiding_ecef_pos(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); - + microstrain_insert_u8(&serializer, frame_id); - assert(position || (3 == 0)); + assert(position); for(unsigned int i=0; i < 3; i++) microstrain_insert_double(&serializer, position[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); @@ -490,23 +366,21 @@ mip_cmd_result mip_aiding_ecef_pos(struct mip_interface* device, const mip_time* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_ECEF, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self) { insert_mip_time(serializer, &self->time); - + microstrain_insert_u8(serializer, self->frame_id); - + microstrain_insert_double(serializer, self->latitude); - + microstrain_insert_double(serializer, self->longitude); - + microstrain_insert_double(serializer, self->height); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->uncertainty[i]); + insert_mip_vector3f(serializer, self->uncertainty); insert_mip_aiding_llh_pos_command_valid_flags(serializer, self->valid_flags); @@ -514,34 +388,22 @@ void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self) { extract_mip_time(serializer, &self->time); - + microstrain_extract_u8(serializer, &self->frame_id); - + microstrain_extract_double(serializer, &self->latitude); - + microstrain_extract_double(serializer, &self->longitude); - + microstrain_extract_double(serializer, &self->height); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->uncertainty[i]); + extract_mip_vector3f(serializer, self->uncertainty); extract_mip_aiding_llh_pos_command_valid_flags(serializer, &self->valid_flags); } -void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_aiding_llh_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -549,16 +411,16 @@ mip_cmd_result mip_aiding_llh_pos(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); - + microstrain_insert_u8(&serializer, frame_id); - + microstrain_insert_double(&serializer, latitude); - + microstrain_insert_double(&serializer, longitude); - + microstrain_insert_double(&serializer, height); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); @@ -566,37 +428,36 @@ mip_cmd_result mip_aiding_llh_pos(struct mip_interface* device, const mip_time* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self) { insert_mip_time(serializer, &self->time); - + microstrain_insert_u8(serializer, self->frame_id); - + microstrain_insert_float(serializer, self->height); - + microstrain_insert_float(serializer, self->uncertainty); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self) { extract_mip_time(serializer, &self->time); - + microstrain_extract_u8(serializer, &self->frame_id); - + microstrain_extract_float(serializer, &self->height); - + microstrain_extract_float(serializer, &self->uncertainty); - + microstrain_extract_u16(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_height(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) +mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -604,31 +465,28 @@ mip_cmd_result mip_aiding_height(struct mip_interface* device, const mip_time* t assert(time); insert_mip_time(&serializer, time); - + microstrain_insert_u8(&serializer, frame_id); - + microstrain_insert_float(&serializer, height); - + microstrain_insert_float(&serializer, uncertainty); - + microstrain_insert_u16(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self) { insert_mip_time(serializer, &self->time); - + microstrain_insert_u8(serializer, self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->velocity[i]); + insert_mip_vector3f(serializer, self->velocity); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->uncertainty[i]); + insert_mip_vector3f(serializer, self->uncertainty); insert_mip_aiding_ecef_vel_command_valid_flags(serializer, self->valid_flags); @@ -636,31 +494,18 @@ void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, cons void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self) { extract_mip_time(serializer, &self->time); - + microstrain_extract_u8(serializer, &self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->velocity[i]); + extract_mip_vector3f(serializer, self->velocity); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->uncertainty[i]); + extract_mip_vector3f(serializer, self->uncertainty); extract_mip_aiding_ecef_vel_command_valid_flags(serializer, &self->valid_flags); } -void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_aiding_ecef_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -668,14 +513,14 @@ mip_cmd_result mip_aiding_ecef_vel(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); - + microstrain_insert_u8(&serializer, frame_id); - assert(velocity || (3 == 0)); + assert(velocity); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, velocity[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); @@ -683,20 +528,17 @@ mip_cmd_result mip_aiding_ecef_vel(struct mip_interface* device, const mip_time* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ECEF, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self) { insert_mip_time(serializer, &self->time); - + microstrain_insert_u8(serializer, self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->velocity[i]); + insert_mip_vector3f(serializer, self->velocity); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->uncertainty[i]); + insert_mip_vector3f(serializer, self->uncertainty); insert_mip_aiding_ned_vel_command_valid_flags(serializer, self->valid_flags); @@ -704,31 +546,18 @@ void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self) { extract_mip_time(serializer, &self->time); - + microstrain_extract_u8(serializer, &self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->velocity[i]); + extract_mip_vector3f(serializer, self->velocity); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->uncertainty[i]); + extract_mip_vector3f(serializer, self->uncertainty); extract_mip_aiding_ned_vel_command_valid_flags(serializer, &self->valid_flags); } -void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_aiding_ned_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -736,14 +565,14 @@ mip_cmd_result mip_aiding_ned_vel(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); - + microstrain_insert_u8(&serializer, frame_id); - assert(velocity || (3 == 0)); + assert(velocity); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, velocity[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); @@ -751,20 +580,17 @@ mip_cmd_result mip_aiding_ned_vel(struct mip_interface* device, const mip_time* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self) { insert_mip_time(serializer, &self->time); - + microstrain_insert_u8(serializer, self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->velocity[i]); + insert_mip_vector3f(serializer, self->velocity); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->uncertainty[i]); + insert_mip_vector3f(serializer, self->uncertainty); insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, self->valid_flags); @@ -772,31 +598,18 @@ void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializ void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self) { extract_mip_time(serializer, &self->time); - + microstrain_extract_u8(serializer, &self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->velocity[i]); + extract_mip_vector3f(serializer, self->velocity); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->uncertainty[i]); + extract_mip_vector3f(serializer, self->uncertainty); extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, &self->valid_flags); } -void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -804,14 +617,14 @@ mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(struct mip_interface* dev assert(time); insert_mip_time(&serializer, time); - + microstrain_insert_u8(&serializer, frame_id); - assert(velocity || (3 == 0)); + assert(velocity); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, velocity[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); @@ -819,37 +632,36 @@ mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(struct mip_interface* dev assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ODOM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ODOM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self) { insert_mip_time(serializer, &self->time); - + microstrain_insert_u8(serializer, self->frame_id); - + microstrain_insert_float(serializer, self->heading); - + microstrain_insert_float(serializer, self->uncertainty); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self) { extract_mip_time(serializer, &self->time); - + microstrain_extract_u8(serializer, &self->frame_id); - + microstrain_extract_float(serializer, &self->heading); - + microstrain_extract_float(serializer, &self->uncertainty); - + microstrain_extract_u16(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_true_heading(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) +mip_cmd_result mip_aiding_true_heading(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -857,31 +669,28 @@ mip_cmd_result mip_aiding_true_heading(struct mip_interface* device, const mip_t assert(time); insert_mip_time(&serializer, time); - + microstrain_insert_u8(&serializer, frame_id); - + microstrain_insert_float(&serializer, heading); - + microstrain_insert_float(&serializer, uncertainty); - + microstrain_insert_u16(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEADING_TRUE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEADING_TRUE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_magnetic_field_command(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command* self) { insert_mip_time(serializer, &self->time); - + microstrain_insert_u8(serializer, self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->magnetic_field[i]); + insert_mip_vector3f(serializer, self->magnetic_field); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->uncertainty[i]); + insert_mip_vector3f(serializer, self->uncertainty); insert_mip_aiding_magnetic_field_command_valid_flags(serializer, self->valid_flags); @@ -889,31 +698,18 @@ void insert_mip_aiding_magnetic_field_command(microstrain_serializer* serializer void extract_mip_aiding_magnetic_field_command(microstrain_serializer* serializer, mip_aiding_magnetic_field_command* self) { extract_mip_time(serializer, &self->time); - + microstrain_extract_u8(serializer, &self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->magnetic_field[i]); + extract_mip_vector3f(serializer, self->magnetic_field); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->uncertainty[i]); + extract_mip_vector3f(serializer, self->uncertainty); extract_mip_aiding_magnetic_field_command_valid_flags(serializer, &self->valid_flags); } -void insert_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_aiding_magnetic_field(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* magnetic_field, const float* uncertainty, mip_aiding_magnetic_field_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_magnetic_field(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* magnetic_field, const float* uncertainty, mip_aiding_magnetic_field_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -921,14 +717,14 @@ mip_cmd_result mip_aiding_magnetic_field(struct mip_interface* device, const mip assert(time); insert_mip_time(&serializer, time); - + microstrain_insert_u8(&serializer, frame_id); - assert(magnetic_field || (3 == 0)); + assert(magnetic_field); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, magnetic_field[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); @@ -936,37 +732,36 @@ mip_cmd_result mip_aiding_magnetic_field(struct mip_interface* device, const mip assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_MAGNETIC_FIELD, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_MAGNETIC_FIELD, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_aiding_pressure_command(microstrain_serializer* serializer, const mip_aiding_pressure_command* self) { insert_mip_time(serializer, &self->time); - + microstrain_insert_u8(serializer, self->frame_id); - + microstrain_insert_float(serializer, self->pressure); - + microstrain_insert_float(serializer, self->uncertainty); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_aiding_pressure_command(microstrain_serializer* serializer, mip_aiding_pressure_command* self) { extract_mip_time(serializer, &self->time); - + microstrain_extract_u8(serializer, &self->frame_id); - + microstrain_extract_float(serializer, &self->pressure); - + microstrain_extract_float(serializer, &self->uncertainty); - + microstrain_extract_u16(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_pressure(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float pressure, float uncertainty, uint16_t valid_flags) +mip_cmd_result mip_aiding_pressure(mip_interface* device, const mip_time* time, uint8_t frame_id, float pressure, float uncertainty, uint16_t valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -974,19 +769,18 @@ mip_cmd_result mip_aiding_pressure(struct mip_interface* device, const mip_time* assert(time); insert_mip_time(&serializer, time); - + microstrain_insert_u8(&serializer, frame_id); - + microstrain_insert_float(&serializer, pressure); - + microstrain_insert_float(&serializer, uncertainty); - + microstrain_insert_u16(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_PRESSURE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_PRESSURE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } #ifdef __cplusplus diff --git a/src/c/mip/definitions/commands_aiding.h b/src/c/mip/definitions/commands_aiding.h index 55b1bb374..bfa412195 100644 --- a/src/c/mip/definitions/commands_aiding.h +++ b/src/c/mip/definitions/commands_aiding.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,9 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipCommands_c MIP Commands [C] @@ -60,25 +58,37 @@ enum // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -typedef uint8_t mip_time_timebase; -static const mip_time_timebase MIP_TIME_TIMEBASE_INTERNAL_REFERENCE = 1; ///< Timestamp provided is with respect to internal clock. -static const mip_time_timebase MIP_TIME_TIMEBASE_EXTERNAL_TIME = 2; ///< Timestamp provided is with respect to external clock, synced by PPS source. -static const mip_time_timebase MIP_TIME_TIMEBASE_TIME_OF_ARRIVAL = 3; ///< Timestamp provided is a fixed latency relative to time of message arrival. +enum mip_time_timebase +{ + MIP_TIME_TIMEBASE_INTERNAL_REFERENCE = 1, ///< Timestamp provided is with respect to internal clock. + MIP_TIME_TIMEBASE_EXTERNAL_TIME = 2, ///< Timestamp provided is with respect to external clock, synced by PPS source. + MIP_TIME_TIMEBASE_TIME_OF_ARRIVAL = 3, ///< Timestamp provided is a fixed latency relative to time of message arrival. +}; +typedef enum mip_time_timebase mip_time_timebase; + +inline void insert_mip_time_timebase(microstrain_serializer* serializer, const mip_time_timebase self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_time_timebase(microstrain_serializer* serializer, mip_time_timebase* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_time { mip_time_timebase timebase; ///< Timebase reference, e.g. internal, external, GPS, UTC, etc. uint8_t reserved; ///< Reserved, set to 0x01. uint64_t nanoseconds; ///< Nanoseconds since the timebase epoch. - }; typedef struct mip_time mip_time; + void insert_mip_time(microstrain_serializer* serializer, const mip_time* self); void extract_mip_time(microstrain_serializer* serializer, mip_time* self); -void insert_mip_time_timebase(microstrain_serializer* serializer, const mip_time_timebase self); -void extract_mip_time_timebase(microstrain_serializer* serializer, mip_time_timebase* self); - //////////////////////////////////////////////////////////////////////////////// // Mip Fields @@ -113,9 +123,23 @@ void extract_mip_time_timebase(microstrain_serializer* serializer, mip_time_time /// ///@{ -typedef uint8_t mip_aiding_frame_config_command_format; -static const mip_aiding_frame_config_command_format MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER = 1; ///< Translation vector followed by euler angles (roll, pitch, yaw). -static const mip_aiding_frame_config_command_format MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_QUATERNION = 2; ///< Translation vector followed by quaternion (w, x, y, z). +enum mip_aiding_frame_config_command_format +{ + MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER = 1, ///< Translation vector followed by euler angles (roll, pitch, yaw). + MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_QUATERNION = 2, ///< Translation vector followed by quaternion (w, x, y, z). +}; +typedef enum mip_aiding_frame_config_command_format mip_aiding_frame_config_command_format; + +inline void insert_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} union mip_aiding_frame_config_command_rotation { @@ -132,15 +156,12 @@ struct mip_aiding_frame_config_command bool tracking_enabled; ///< If enabled, the Kalman filter will track errors. mip_vector3f translation; ///< Translation X, Y, and Z. mip_aiding_frame_config_command_rotation rotation; ///< Rotation as specified by format. - }; typedef struct mip_aiding_frame_config_command mip_aiding_frame_config_command; + void insert_mip_aiding_frame_config_command(microstrain_serializer* serializer, const mip_aiding_frame_config_command* self); void extract_mip_aiding_frame_config_command(microstrain_serializer* serializer, mip_aiding_frame_config_command* self); -void insert_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self); -void extract_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self); - struct mip_aiding_frame_config_response { uint8_t frame_id; ///< Reference frame number. Limit 4. @@ -148,17 +169,17 @@ struct mip_aiding_frame_config_response bool tracking_enabled; ///< If enabled, the Kalman filter will track errors. mip_vector3f translation; ///< Translation X, Y, and Z. mip_aiding_frame_config_command_rotation rotation; ///< Rotation as specified by format. - }; typedef struct mip_aiding_frame_config_response mip_aiding_frame_config_response; + void insert_mip_aiding_frame_config_response(microstrain_serializer* serializer, const mip_aiding_frame_config_response* self); void extract_mip_aiding_frame_config_response(microstrain_serializer* serializer, mip_aiding_frame_config_response* self); -mip_cmd_result mip_aiding_write_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool tracking_enabled, const float* translation, const mip_aiding_frame_config_command_rotation* rotation); -mip_cmd_result mip_aiding_read_frame_config(struct mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool* tracking_enabled_out, float* translation_out, mip_aiding_frame_config_command_rotation* rotation_out); -mip_cmd_result mip_aiding_save_frame_config(struct mip_interface* device, uint8_t frame_id); -mip_cmd_result mip_aiding_load_frame_config(struct mip_interface* device, uint8_t frame_id); -mip_cmd_result mip_aiding_default_frame_config(struct mip_interface* device, uint8_t frame_id); +mip_cmd_result mip_aiding_write_frame_config(mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool tracking_enabled, const float* translation, const mip_aiding_frame_config_command_rotation* rotation); +mip_cmd_result mip_aiding_read_frame_config(mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool* tracking_enabled_out, float* translation_out, mip_aiding_frame_config_command_rotation* rotation_out); +mip_cmd_result mip_aiding_save_frame_config(mip_interface* device, uint8_t frame_id); +mip_cmd_result mip_aiding_load_frame_config(mip_interface* device, uint8_t frame_id); +mip_cmd_result mip_aiding_default_frame_config(mip_interface* device, uint8_t frame_id); ///@} /// @@ -168,38 +189,50 @@ mip_cmd_result mip_aiding_default_frame_config(struct mip_interface* device, uin /// ///@{ -typedef uint8_t mip_aiding_aiding_echo_control_command_mode; -static const mip_aiding_aiding_echo_control_command_mode MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_SUPPRESS_ACK = 0; ///< Suppresses the usual command ack field for aiding messages. -static const mip_aiding_aiding_echo_control_command_mode MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_STANDARD = 1; ///< Normal ack/nack behavior. -static const mip_aiding_aiding_echo_control_command_mode MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_RESPONSE = 2; ///< Echo the data back as a response. +enum mip_aiding_aiding_echo_control_command_mode +{ + MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_SUPPRESS_ACK = 0, ///< Suppresses the usual command ack field for aiding messages. + MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_STANDARD = 1, ///< Normal ack/nack behavior. + MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_RESPONSE = 2, ///< Echo the data back as a response. +}; +typedef enum mip_aiding_aiding_echo_control_command_mode mip_aiding_aiding_echo_control_command_mode; + +inline void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_aiding_aiding_echo_control_command { mip_function_selector function; mip_aiding_aiding_echo_control_command_mode mode; ///< Controls data echoing. - }; typedef struct mip_aiding_aiding_echo_control_command mip_aiding_aiding_echo_control_command; + void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self); void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self); -void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self); -void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self); - struct mip_aiding_aiding_echo_control_response { mip_aiding_aiding_echo_control_command_mode mode; ///< Controls data echoing. - }; typedef struct mip_aiding_aiding_echo_control_response mip_aiding_aiding_echo_control_response; + void insert_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self); void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self); -mip_cmd_result mip_aiding_write_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode); -mip_cmd_result mip_aiding_read_aiding_echo_control(struct mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out); -mip_cmd_result mip_aiding_save_aiding_echo_control(struct mip_interface* device); -mip_cmd_result mip_aiding_load_aiding_echo_control(struct mip_interface* device); -mip_cmd_result mip_aiding_default_aiding_echo_control(struct mip_interface* device); +mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode); +mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out); +mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device); ///@} /// @@ -215,6 +248,17 @@ static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_aiding_ecef_pos_command { @@ -223,16 +267,13 @@ struct mip_aiding_ecef_pos_command mip_vector3d position; ///< ECEF position [m]. mip_vector3f uncertainty; ///< ECEF position uncertainty [m]. Cannot be 0 unless the corresponding valid flags are 0. mip_aiding_ecef_pos_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. - }; typedef struct mip_aiding_ecef_pos_command mip_aiding_ecef_pos_command; + void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self); void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self); -void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self); -void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self); - -mip_cmd_result mip_aiding_ecef_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags); ///@} /// @@ -249,6 +290,17 @@ static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_V static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_LONGITUDE = 0x0002; ///< static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_HEIGHT = 0x0004; ///< static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_aiding_llh_pos_command { @@ -259,16 +311,13 @@ struct mip_aiding_llh_pos_command double height; ///< [m] mip_vector3f uncertainty; ///< NED position uncertainty. Cannot be 0 unless the corresponding valid flags are 0. mip_aiding_llh_pos_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. - }; typedef struct mip_aiding_llh_pos_command mip_aiding_llh_pos_command; + void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self); void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self); -void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self); -void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self); - -mip_cmd_result mip_aiding_llh_pos(struct mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags); ///@} /// @@ -285,13 +334,13 @@ struct mip_aiding_height_command float height; ///< [m] float uncertainty; ///< [m] uint16_t valid_flags; - }; typedef struct mip_aiding_height_command mip_aiding_height_command; + void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self); void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self); -mip_cmd_result mip_aiding_height(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); +mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); ///@} /// @@ -307,6 +356,17 @@ static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_aiding_ecef_vel_command { @@ -315,16 +375,13 @@ struct mip_aiding_ecef_vel_command mip_vector3f velocity; ///< ECEF velocity [m/s]. mip_vector3f uncertainty; ///< ECEF velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. mip_aiding_ecef_vel_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. - }; typedef struct mip_aiding_ecef_vel_command mip_aiding_ecef_vel_command; + void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self); void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self); -void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self); -void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self); - -mip_cmd_result mip_aiding_ecef_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags); ///@} /// @@ -340,6 +397,17 @@ static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_V static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_aiding_ned_vel_command { @@ -348,16 +416,13 @@ struct mip_aiding_ned_vel_command mip_vector3f velocity; ///< NED velocity [m/s]. mip_vector3f uncertainty; ///< NED velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. mip_aiding_ned_vel_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. - }; typedef struct mip_aiding_ned_vel_command mip_aiding_ned_vel_command; + void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self); void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self); -void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self); -void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self); - -mip_cmd_result mip_aiding_ned_vel(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags); ///@} /// @@ -374,6 +439,17 @@ static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AID static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_aiding_vehicle_fixed_frame_velocity_command { @@ -382,16 +458,13 @@ struct mip_aiding_vehicle_fixed_frame_velocity_command mip_vector3f velocity; ///< [m/s] mip_vector3f uncertainty; ///< [m/s] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0. mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. - }; typedef struct mip_aiding_vehicle_fixed_frame_velocity_command mip_aiding_vehicle_fixed_frame_velocity_command; + void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self); void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self); -void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self); -void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self); - -mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags); ///@} /// @@ -407,13 +480,13 @@ struct mip_aiding_true_heading_command float heading; ///< Heading [radians]. Range +/- Pi. float uncertainty; ///< Cannot be 0 unless the valid flags are 0. uint16_t valid_flags; - }; typedef struct mip_aiding_true_heading_command mip_aiding_true_heading_command; + void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self); void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self); -mip_cmd_result mip_aiding_true_heading(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); +mip_cmd_result mip_aiding_true_heading(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); ///@} /// @@ -429,6 +502,17 @@ static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_F static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_FIELD_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_FIELD_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_FIELD_COMMAND_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_aiding_magnetic_field_command { @@ -437,16 +521,13 @@ struct mip_aiding_magnetic_field_command mip_vector3f magnetic_field; ///< [G] mip_vector3f uncertainty; ///< [G] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0. mip_aiding_magnetic_field_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. - }; typedef struct mip_aiding_magnetic_field_command mip_aiding_magnetic_field_command; + void insert_mip_aiding_magnetic_field_command(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command* self); void extract_mip_aiding_magnetic_field_command(microstrain_serializer* serializer, mip_aiding_magnetic_field_command* self); -void insert_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self); -void extract_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self); - -mip_cmd_result mip_aiding_magnetic_field(struct mip_interface* device, const mip_time* time, uint8_t frame_id, const float* magnetic_field, const float* uncertainty, mip_aiding_magnetic_field_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_magnetic_field(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* magnetic_field, const float* uncertainty, mip_aiding_magnetic_field_command_valid_flags valid_flags); ///@} /// @@ -463,13 +544,13 @@ struct mip_aiding_pressure_command float pressure; ///< [mbar] float uncertainty; ///< [mbar] 1-sigma uncertainty. Cannot be 0 unless the valid flags are 0. uint16_t valid_flags; - }; typedef struct mip_aiding_pressure_command mip_aiding_pressure_command; + void insert_mip_aiding_pressure_command(microstrain_serializer* serializer, const mip_aiding_pressure_command* self); void extract_mip_aiding_pressure_command(microstrain_serializer* serializer, mip_aiding_pressure_command* self); -mip_cmd_result mip_aiding_pressure(struct mip_interface* device, const mip_time* time, uint8_t frame_id, float pressure, float uncertainty, uint16_t valid_flags); +mip_cmd_result mip_aiding_pressure(mip_interface* device, const mip_time* time, uint8_t frame_id, float pressure, float uncertainty, uint16_t valid_flags); ///@} /// diff --git a/src/c/mip/definitions/commands_base.c b/src/c/mip/definitions/commands_base.c index 1f474e5b9..82b99f96a 100644 --- a/src/c/mip/definitions/commands_base.c +++ b/src/c/mip/definitions/commands_base.c @@ -11,11 +11,12 @@ namespace mip { namespace C { extern "C" { -#endif // __cplusplus; + +#endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions +// Mip Fields //////////////////////////////////////////////////////////////////////////////// void insert_mip_base_device_info(microstrain_serializer* serializer, const mip_base_device_info* self) @@ -59,42 +60,15 @@ void extract_mip_base_device_info(microstrain_serializer* serializer, mip_base_d } -void insert_mip_time_format(microstrain_serializer* serializer, const mip_time_format self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_time_format(microstrain_serializer* serializer, mip_time_format* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self) -{ - microstrain_insert_u32(serializer, (uint32_t) (self)); -} -void extract_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self) -{ - uint32_t tmp = 0; - microstrain_extract_u32(serializer, &tmp); - *self = tmp; -} - - -//////////////////////////////////////////////////////////////////////////////// -// Mip Fields -//////////////////////////////////////////////////////////////////////////////// - -mip_cmd_result mip_base_ping(struct mip_interface* device) +mip_cmd_result mip_base_ping(mip_interface* device) { return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_PING, NULL, 0); } -mip_cmd_result mip_base_set_idle(struct mip_interface* device) +mip_cmd_result mip_base_set_idle(mip_interface* device) { return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_SET_TO_IDLE, NULL, 0); } -mip_cmd_result mip_base_get_device_info(struct mip_interface* device, mip_base_device_info* device_info_out) +mip_cmd_result mip_base_get_device_info(mip_interface* device, mip_base_device_info* device_info_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -109,12 +83,12 @@ mip_cmd_result mip_base_get_device_info(struct mip_interface* device, mip_base_d assert(device_info_out); extract_mip_base_device_info(&deserializer, device_info_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_base_get_device_descriptors(struct mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count) +mip_cmd_result mip_base_get_device_descriptors(mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -126,16 +100,15 @@ mip_cmd_result mip_base_get_device_descriptors(struct mip_interface* device, uin microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && ( - microstrain_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) + for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && (microstrain_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) microstrain_extract_u16(&deserializer, &descriptors_out[*descriptors_out_count]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_base_built_in_test(struct mip_interface* device, uint32_t* result_out) +mip_cmd_result mip_base_built_in_test(mip_interface* device, uint32_t* result_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -150,16 +123,16 @@ mip_cmd_result mip_base_built_in_test(struct mip_interface* device, uint32_t* re assert(result_out); microstrain_extract_u32(&deserializer, result_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_base_resume(struct mip_interface* device) +mip_cmd_result mip_base_resume(mip_interface* device) { return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_RESUME, NULL, 0); } -mip_cmd_result mip_base_get_extended_descriptors(struct mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count) +mip_cmd_result mip_base_get_extended_descriptors(mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -171,16 +144,15 @@ mip_cmd_result mip_base_get_extended_descriptors(struct mip_interface* device, u microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && ( - microstrain_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) + for(*descriptors_out_count = 0; (*descriptors_out_count < descriptors_out_max) && (microstrain_serializer_remaining(&deserializer) > 0); (*descriptors_out_count)++) microstrain_extract_u16(&deserializer, &descriptors_out[*descriptors_out_count]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* result_out) +mip_cmd_result mip_base_continuous_bit(mip_interface* device, uint8_t* result_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -192,11 +164,11 @@ mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* re microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(result_out || (16 == 0)); + assert(result_out); for(unsigned int i=0; i < 16; i++) microstrain_extract_u8(&deserializer, &result_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -204,7 +176,7 @@ mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* re void insert_mip_base_comm_speed_command(microstrain_serializer* serializer, const mip_base_comm_speed_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->port); if( self->function == MIP_FUNCTION_WRITE ) @@ -216,7 +188,7 @@ void insert_mip_base_comm_speed_command(microstrain_serializer* serializer, cons void extract_mip_base_comm_speed_command(microstrain_serializer* serializer, mip_base_comm_speed_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->port); if( self->function == MIP_FUNCTION_WRITE ) @@ -226,113 +198,93 @@ void extract_mip_base_comm_speed_command(microstrain_serializer* serializer, mip } } -void insert_mip_base_comm_speed_response(microstrain_serializer* serializer, const mip_base_comm_speed_response* self) -{ - microstrain_insert_u8(serializer, self->port); - - microstrain_insert_u32(serializer, self->baud); - -} -void extract_mip_base_comm_speed_response(microstrain_serializer* serializer, mip_base_comm_speed_response* self) -{ - microstrain_extract_u8(serializer, &self->port); - - microstrain_extract_u32(serializer, &self->baud); - -} - -mip_cmd_result mip_base_write_comm_speed(struct mip_interface* device, uint8_t port, uint32_t baud) +mip_cmd_result mip_base_write_comm_speed(mip_interface* device, uint8_t port, uint32_t baud) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, port); - + microstrain_insert_u32(&serializer, baud); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_base_read_comm_speed(struct mip_interface* device, uint8_t port, uint32_t* baud_out) +mip_cmd_result mip_base_read_comm_speed(mip_interface* device, uint8_t port, uint32_t* baud_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, port); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_BASE_COMM_SPEED, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_BASE_COMM_SPEED, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &port); assert(baud_out); microstrain_extract_u32(&deserializer, baud_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_base_save_comm_speed(struct mip_interface* device, uint8_t port) +mip_cmd_result mip_base_save_comm_speed(mip_interface* device, uint8_t port) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, port); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_base_load_comm_speed(struct mip_interface* device, uint8_t port) +mip_cmd_result mip_base_load_comm_speed(mip_interface* device, uint8_t port) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, port); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_base_default_comm_speed(struct mip_interface* device, uint8_t port) +mip_cmd_result mip_base_default_comm_speed(mip_interface* device, uint8_t port) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, port); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_COMM_SPEED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_base_gps_time_update_command(microstrain_serializer* serializer, const mip_base_gps_time_update_command* self) { @@ -341,7 +293,7 @@ void insert_mip_base_gps_time_update_command(microstrain_serializer* serializer, if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_base_gps_time_update_command_field_id(serializer, self->field_id); - + microstrain_insert_u32(serializer, self->value); } @@ -353,24 +305,13 @@ void extract_mip_base_gps_time_update_command(microstrain_serializer* serializer if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_base_gps_time_update_command_field_id(serializer, &self->field_id); - + microstrain_extract_u32(serializer, &self->value); } } -void insert_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_base_write_gps_time_update(struct mip_interface* device, mip_base_gps_time_update_command_field_id field_id, uint32_t value) +mip_cmd_result mip_base_write_gps_time_update(mip_interface* device, mip_base_gps_time_update_command_field_id field_id, uint32_t value) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -379,15 +320,14 @@ mip_cmd_result mip_base_write_gps_time_update(struct mip_interface* device, mip_ insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_base_gps_time_update_command_field_id(&serializer, field_id); - + microstrain_insert_u32(&serializer, value); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_GPS_TIME_UPDATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_GPS_TIME_UPDATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_base_soft_reset(struct mip_interface* device) +mip_cmd_result mip_base_soft_reset(mip_interface* device) { return mip_interface_run_command(device, MIP_BASE_CMD_DESC_SET, MIP_CMD_DESC_BASE_SOFT_RESET, NULL, 0); } diff --git a/src/c/mip/definitions/commands_base.h b/src/c/mip/definitions/commands_base.h index d225677af..ab837b526 100644 --- a/src/c/mip/definitions/commands_base.h +++ b/src/c/mip/definitions/commands_base.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,9 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipCommands_c MIP Commands [C] @@ -67,17 +65,28 @@ struct mip_base_device_info char serial_number[16]; char lot_number[16]; char device_options[16]; - }; typedef struct mip_base_device_info mip_base_device_info; + void insert_mip_base_device_info(microstrain_serializer* serializer, const mip_base_device_info* self); void extract_mip_base_device_info(microstrain_serializer* serializer, mip_base_device_info* self); -typedef uint8_t mip_time_format; -static const mip_time_format MIP_TIME_FORMAT_GPS = 1; ///< GPS time, a = week number since 1980, b = time of week in milliseconds. +enum mip_time_format +{ + MIP_TIME_FORMAT_GPS = 1, ///< GPS time, a = week number since 1980, b = time of week in milliseconds. +}; +typedef enum mip_time_format mip_time_format; -void insert_mip_time_format(microstrain_serializer* serializer, const mip_time_format self); -void extract_mip_time_format(microstrain_serializer* serializer, mip_time_format* self); +inline void insert_mip_time_format(microstrain_serializer* serializer, const mip_time_format self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_time_format(microstrain_serializer* serializer, mip_time_format* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint32_t mip_commanded_test_bits_gq7; static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_NONE = 0x00000000; @@ -109,9 +118,16 @@ static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_RTK_FA static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_SOLUTION_FAULT = 0x40000000; ///< static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_GENERAL_FAULT = 0x80000000; ///< static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_ALL = 0xFFFFFFFF; - -void insert_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self); -void extract_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self); +inline void insert_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self) +{ + microstrain_insert_u32(serializer, (uint32_t)(self)); +} +inline void extract_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self) +{ + uint32_t tmp = 0; + microstrain_extract_u32(serializer, &tmp); + *self = tmp; +} //////////////////////////////////////////////////////////////////////////////// @@ -128,7 +144,7 @@ void extract_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, mip /// ///@{ -mip_cmd_result mip_base_ping(struct mip_interface* device); +mip_cmd_result mip_base_ping(mip_interface* device); ///@} /// @@ -142,7 +158,7 @@ mip_cmd_result mip_base_ping(struct mip_interface* device); /// ///@{ -mip_cmd_result mip_base_set_idle(struct mip_interface* device); +mip_cmd_result mip_base_set_idle(mip_interface* device); ///@} /// @@ -155,13 +171,13 @@ mip_cmd_result mip_base_set_idle(struct mip_interface* device); struct mip_base_get_device_info_response { mip_base_device_info device_info; - }; typedef struct mip_base_get_device_info_response mip_base_get_device_info_response; + void insert_mip_base_get_device_info_response(microstrain_serializer* serializer, const mip_base_get_device_info_response* self); void extract_mip_base_get_device_info_response(microstrain_serializer* serializer, mip_base_get_device_info_response* self); -mip_cmd_result mip_base_get_device_info(struct mip_interface* device, mip_base_device_info* device_info_out); +mip_cmd_result mip_base_get_device_info(mip_interface* device, mip_base_device_info* device_info_out); ///@} /// @@ -178,13 +194,13 @@ struct mip_base_get_device_descriptors_response { uint16_t descriptors[253]; uint8_t descriptors_count; - }; typedef struct mip_base_get_device_descriptors_response mip_base_get_device_descriptors_response; + void insert_mip_base_get_device_descriptors_response(microstrain_serializer* serializer, const mip_base_get_device_descriptors_response* self); void extract_mip_base_get_device_descriptors_response(microstrain_serializer* serializer, mip_base_get_device_descriptors_response* self); -mip_cmd_result mip_base_get_device_descriptors(struct mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count); +mip_cmd_result mip_base_get_device_descriptors(mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count); ///@} /// @@ -202,13 +218,13 @@ mip_cmd_result mip_base_get_device_descriptors(struct mip_interface* device, uin struct mip_base_built_in_test_response { uint32_t result; - }; typedef struct mip_base_built_in_test_response mip_base_built_in_test_response; + void insert_mip_base_built_in_test_response(microstrain_serializer* serializer, const mip_base_built_in_test_response* self); void extract_mip_base_built_in_test_response(microstrain_serializer* serializer, mip_base_built_in_test_response* self); -mip_cmd_result mip_base_built_in_test(struct mip_interface* device, uint32_t* result_out); +mip_cmd_result mip_base_built_in_test(mip_interface* device, uint32_t* result_out); ///@} /// @@ -220,7 +236,7 @@ mip_cmd_result mip_base_built_in_test(struct mip_interface* device, uint32_t* re /// ///@{ -mip_cmd_result mip_base_resume(struct mip_interface* device); +mip_cmd_result mip_base_resume(mip_interface* device); ///@} /// @@ -237,13 +253,13 @@ struct mip_base_get_extended_descriptors_response { uint16_t descriptors[253]; uint8_t descriptors_count; - }; typedef struct mip_base_get_extended_descriptors_response mip_base_get_extended_descriptors_response; + void insert_mip_base_get_extended_descriptors_response(microstrain_serializer* serializer, const mip_base_get_extended_descriptors_response* self); void extract_mip_base_get_extended_descriptors_response(microstrain_serializer* serializer, mip_base_get_extended_descriptors_response* self); -mip_cmd_result mip_base_get_extended_descriptors(struct mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count); +mip_cmd_result mip_base_get_extended_descriptors(mip_interface* device, uint16_t* descriptors_out, size_t descriptors_out_max, uint8_t* descriptors_out_count); ///@} /// @@ -258,13 +274,13 @@ mip_cmd_result mip_base_get_extended_descriptors(struct mip_interface* device, u struct mip_base_continuous_bit_response { uint8_t result[16]; ///< Device-specific bitfield (128 bits). See device user manual. Bits are least-significant-byte first. For example, bit 0 is located at bit 0 of result[0], bit 1 is located at bit 1 of result[0], bit 8 is located at bit 0 of result[1], and bit 127 is located at bit 7 of result[15]. - }; typedef struct mip_base_continuous_bit_response mip_base_continuous_bit_response; + void insert_mip_base_continuous_bit_response(microstrain_serializer* serializer, const mip_base_continuous_bit_response* self); void extract_mip_base_continuous_bit_response(microstrain_serializer* serializer, mip_base_continuous_bit_response* self); -mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* result_out); +mip_cmd_result mip_base_continuous_bit(mip_interface* device, uint8_t* result_out); ///@} /// @@ -288,14 +304,15 @@ mip_cmd_result mip_base_continuous_bit(struct mip_interface* device, uint8_t* re ///@{ enum { MIP_BASE_COMM_SPEED_COMMAND_ALL_PORTS = 0 }; + struct mip_base_comm_speed_command { mip_function_selector function; uint8_t port; ///< Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details. uint32_t baud; ///< Port baud rate. Must be a supported rate. - }; typedef struct mip_base_comm_speed_command mip_base_comm_speed_command; + void insert_mip_base_comm_speed_command(microstrain_serializer* serializer, const mip_base_comm_speed_command* self); void extract_mip_base_comm_speed_command(microstrain_serializer* serializer, mip_base_comm_speed_command* self); @@ -303,17 +320,17 @@ struct mip_base_comm_speed_response { uint8_t port; ///< Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details. uint32_t baud; ///< Port baud rate. Must be a supported rate. - }; typedef struct mip_base_comm_speed_response mip_base_comm_speed_response; + void insert_mip_base_comm_speed_response(microstrain_serializer* serializer, const mip_base_comm_speed_response* self); void extract_mip_base_comm_speed_response(microstrain_serializer* serializer, mip_base_comm_speed_response* self); -mip_cmd_result mip_base_write_comm_speed(struct mip_interface* device, uint8_t port, uint32_t baud); -mip_cmd_result mip_base_read_comm_speed(struct mip_interface* device, uint8_t port, uint32_t* baud_out); -mip_cmd_result mip_base_save_comm_speed(struct mip_interface* device, uint8_t port); -mip_cmd_result mip_base_load_comm_speed(struct mip_interface* device, uint8_t port); -mip_cmd_result mip_base_default_comm_speed(struct mip_interface* device, uint8_t port); +mip_cmd_result mip_base_write_comm_speed(mip_interface* device, uint8_t port, uint32_t baud); +mip_cmd_result mip_base_read_comm_speed(mip_interface* device, uint8_t port, uint32_t* baud_out); +mip_cmd_result mip_base_save_comm_speed(mip_interface* device, uint8_t port); +mip_cmd_result mip_base_load_comm_speed(mip_interface* device, uint8_t port); +mip_cmd_result mip_base_default_comm_speed(mip_interface* device, uint8_t port); ///@} /// @@ -326,25 +343,37 @@ mip_cmd_result mip_base_default_comm_speed(struct mip_interface* device, uint8_t /// ///@{ -typedef uint8_t mip_base_gps_time_update_command_field_id; -static const mip_base_gps_time_update_command_field_id MIP_BASE_GPS_TIME_UPDATE_COMMAND_FIELD_ID_WEEK_NUMBER = 1; ///< Week number. -static const mip_base_gps_time_update_command_field_id MIP_BASE_GPS_TIME_UPDATE_COMMAND_FIELD_ID_TIME_OF_WEEK = 2; ///< Time of week in seconds. +enum mip_base_gps_time_update_command_field_id +{ + MIP_BASE_GPS_TIME_UPDATE_COMMAND_FIELD_ID_WEEK_NUMBER = 1, ///< Week number. + MIP_BASE_GPS_TIME_UPDATE_COMMAND_FIELD_ID_TIME_OF_WEEK = 2, ///< Time of week in seconds. +}; +typedef enum mip_base_gps_time_update_command_field_id mip_base_gps_time_update_command_field_id; + +inline void insert_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_base_gps_time_update_command { mip_function_selector function; mip_base_gps_time_update_command_field_id field_id; ///< Determines how to interpret value. uint32_t value; ///< Week number or time of week, depending on the field_id. - }; typedef struct mip_base_gps_time_update_command mip_base_gps_time_update_command; + void insert_mip_base_gps_time_update_command(microstrain_serializer* serializer, const mip_base_gps_time_update_command* self); void extract_mip_base_gps_time_update_command(microstrain_serializer* serializer, mip_base_gps_time_update_command* self); -void insert_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self); -void extract_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self); - -mip_cmd_result mip_base_write_gps_time_update(struct mip_interface* device, mip_base_gps_time_update_command_field_id field_id, uint32_t value); +mip_cmd_result mip_base_write_gps_time_update(mip_interface* device, mip_base_gps_time_update_command_field_id field_id, uint32_t value); ///@} /// @@ -356,7 +385,7 @@ mip_cmd_result mip_base_write_gps_time_update(struct mip_interface* device, mip_ /// ///@{ -mip_cmd_result mip_base_soft_reset(struct mip_interface* device); +mip_cmd_result mip_base_soft_reset(mip_interface* device); ///@} /// diff --git a/src/c/mip/definitions/commands_filter.c b/src/c/mip/definitions/commands_filter.c index 2f783650c..8f42326d5 100644 --- a/src/c/mip/definitions/commands_filter.c +++ b/src/c/mip/definitions/commands_filter.c @@ -13,92 +13,50 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; - - -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - -void insert_mip_filter_reference_frame(microstrain_serializer* serializer, const mip_filter_reference_frame self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_reference_frame(microstrain_serializer* serializer, mip_filter_reference_frame* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_filter_mag_param_source(microstrain_serializer* serializer, const mip_filter_mag_param_source self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_mag_param_source(microstrain_serializer* serializer, mip_filter_mag_param_source* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_filter_adaptive_measurement(microstrain_serializer* serializer, const mip_filter_adaptive_measurement self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_adaptive_measurement(microstrain_serializer* serializer, mip_filter_adaptive_measurement* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -mip_cmd_result mip_filter_reset(struct mip_interface* device) +mip_cmd_result mip_filter_reset(mip_interface* device) { return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_RESET_FILTER, NULL, 0); } void insert_mip_filter_set_initial_attitude_command(microstrain_serializer* serializer, const mip_filter_set_initial_attitude_command* self) { microstrain_insert_float(serializer, self->roll); - + microstrain_insert_float(serializer, self->pitch); - + microstrain_insert_float(serializer, self->heading); } void extract_mip_filter_set_initial_attitude_command(microstrain_serializer* serializer, mip_filter_set_initial_attitude_command* self) { microstrain_extract_float(serializer, &self->roll); - + microstrain_extract_float(serializer, &self->pitch); - + microstrain_extract_float(serializer, &self->heading); } -mip_cmd_result mip_filter_set_initial_attitude(struct mip_interface* device, float roll, float pitch, float heading) +mip_cmd_result mip_filter_set_initial_attitude(mip_interface* device, float roll, float pitch, float heading) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_float(&serializer, roll); - + microstrain_insert_float(&serializer, pitch); - + microstrain_insert_float(&serializer, heading); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SET_INITIAL_ATTITUDE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SET_INITIAL_ATTITUDE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_estimation_control_command(microstrain_serializer* serializer, const mip_filter_estimation_control_command* self) { @@ -121,29 +79,7 @@ void extract_mip_filter_estimation_control_command(microstrain_serializer* seria } } -void insert_mip_filter_estimation_control_response(microstrain_serializer* serializer, const mip_filter_estimation_control_response* self) -{ - insert_mip_filter_estimation_control_command_enable_flags(serializer, self->enable); - -} -void extract_mip_filter_estimation_control_response(microstrain_serializer* serializer, mip_filter_estimation_control_response* self) -{ - extract_mip_filter_estimation_control_command_enable_flags(serializer, &self->enable); - -} - -void insert_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags enable) +mip_cmd_result mip_filter_write_estimation_control(mip_interface* device, mip_filter_estimation_control_command_enable_flags enable) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -155,10 +91,9 @@ mip_cmd_result mip_filter_write_estimation_control(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags* enable_out) +mip_cmd_result mip_filter_read_estimation_control(mip_interface* device, mip_filter_estimation_control_command_enable_flags* enable_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -169,8 +104,7 @@ mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -180,12 +114,12 @@ mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, assert(enable_out); extract_mip_filter_estimation_control_command_enable_flags(&deserializer, enable_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_estimation_control(struct mip_interface* device) +mip_cmd_result mip_filter_save_estimation_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -195,10 +129,9 @@ mip_cmd_result mip_filter_save_estimation_control(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_estimation_control(struct mip_interface* device) +mip_cmd_result mip_filter_load_estimation_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -208,10 +141,9 @@ mip_cmd_result mip_filter_load_estimation_control(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_estimation_control(struct mip_interface* device) +mip_cmd_result mip_filter_default_estimation_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -221,170 +153,160 @@ mip_cmd_result mip_filter_default_estimation_control(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_external_gnss_update_command(microstrain_serializer* serializer, const mip_filter_external_gnss_update_command* self) { microstrain_insert_double(serializer, self->gps_time); - + microstrain_insert_u16(serializer, self->gps_week); - + microstrain_insert_double(serializer, self->latitude); - + microstrain_insert_double(serializer, self->longitude); - + microstrain_insert_double(serializer, self->height); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->velocity[i]); + insert_mip_vector3f(serializer, self->velocity); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->pos_uncertainty[i]); + insert_mip_vector3f(serializer, self->pos_uncertainty); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->vel_uncertainty[i]); + insert_mip_vector3f(serializer, self->vel_uncertainty); } void extract_mip_filter_external_gnss_update_command(microstrain_serializer* serializer, mip_filter_external_gnss_update_command* self) { microstrain_extract_double(serializer, &self->gps_time); - + microstrain_extract_u16(serializer, &self->gps_week); - + microstrain_extract_double(serializer, &self->latitude); - + microstrain_extract_double(serializer, &self->longitude); - + microstrain_extract_double(serializer, &self->height); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->velocity[i]); + extract_mip_vector3f(serializer, self->velocity); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->pos_uncertainty[i]); + extract_mip_vector3f(serializer, self->pos_uncertainty); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->vel_uncertainty[i]); + extract_mip_vector3f(serializer, self->vel_uncertainty); } -mip_cmd_result mip_filter_external_gnss_update(struct mip_interface* device, double gps_time, uint16_t gps_week, double latitude, double longitude, double height, const float* velocity, const float* pos_uncertainty, const float* vel_uncertainty) +mip_cmd_result mip_filter_external_gnss_update(mip_interface* device, double gps_time, uint16_t gps_week, double latitude, double longitude, double height, const float* velocity, const float* pos_uncertainty, const float* vel_uncertainty) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_double(&serializer, gps_time); - + microstrain_insert_u16(&serializer, gps_week); - + microstrain_insert_double(&serializer, latitude); - + microstrain_insert_double(&serializer, longitude); - + microstrain_insert_double(&serializer, height); - assert(velocity || (3 == 0)); + assert(velocity); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, velocity[i]); - assert(pos_uncertainty || (3 == 0)); + assert(pos_uncertainty); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, pos_uncertainty[i]); - assert(vel_uncertainty || (3 == 0)); + assert(vel_uncertainty); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, vel_uncertainty[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_external_heading_update_command(microstrain_serializer* serializer, const mip_filter_external_heading_update_command* self) { microstrain_insert_float(serializer, self->heading); - + microstrain_insert_float(serializer, self->heading_uncertainty); - + microstrain_insert_u8(serializer, self->type); } void extract_mip_filter_external_heading_update_command(microstrain_serializer* serializer, mip_filter_external_heading_update_command* self) { microstrain_extract_float(serializer, &self->heading); - + microstrain_extract_float(serializer, &self->heading_uncertainty); - + microstrain_extract_u8(serializer, &self->type); } -mip_cmd_result mip_filter_external_heading_update(struct mip_interface* device, float heading, float heading_uncertainty, uint8_t type) +mip_cmd_result mip_filter_external_heading_update(mip_interface* device, float heading, float heading_uncertainty, uint8_t type) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_float(&serializer, heading); - + microstrain_insert_float(&serializer, heading_uncertainty); - + microstrain_insert_u8(&serializer, type); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_external_heading_update_with_time_command(microstrain_serializer* serializer, const mip_filter_external_heading_update_with_time_command* self) { microstrain_insert_double(serializer, self->gps_time); - + microstrain_insert_u16(serializer, self->gps_week); - + microstrain_insert_float(serializer, self->heading); - + microstrain_insert_float(serializer, self->heading_uncertainty); - + microstrain_insert_u8(serializer, self->type); } void extract_mip_filter_external_heading_update_with_time_command(microstrain_serializer* serializer, mip_filter_external_heading_update_with_time_command* self) { microstrain_extract_double(serializer, &self->gps_time); - + microstrain_extract_u16(serializer, &self->gps_week); - + microstrain_extract_float(serializer, &self->heading); - + microstrain_extract_float(serializer, &self->heading_uncertainty); - + microstrain_extract_u8(serializer, &self->type); } -mip_cmd_result mip_filter_external_heading_update_with_time(struct mip_interface* device, double gps_time, uint16_t gps_week, float heading, float heading_uncertainty, uint8_t type) +mip_cmd_result mip_filter_external_heading_update_with_time(mip_interface* device, double gps_time, uint16_t gps_week, float heading, float heading_uncertainty, uint8_t type) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_double(&serializer, gps_time); - + microstrain_insert_u16(&serializer, gps_week); - + microstrain_insert_float(&serializer, heading); - + microstrain_insert_float(&serializer, heading_uncertainty); - + microstrain_insert_u8(&serializer, type); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_tare_orientation_command(microstrain_serializer* serializer, const mip_filter_tare_orientation_command* self) { @@ -407,29 +329,7 @@ void extract_mip_filter_tare_orientation_command(microstrain_serializer* seriali } } -void insert_mip_filter_tare_orientation_response(microstrain_serializer* serializer, const mip_filter_tare_orientation_response* self) -{ - insert_mip_filter_tare_orientation_command_mip_tare_axes(serializer, self->axes); - -} -void extract_mip_filter_tare_orientation_response(microstrain_serializer* serializer, mip_filter_tare_orientation_response* self) -{ - extract_mip_filter_tare_orientation_command_mip_tare_axes(serializer, &self->axes); - -} - -void insert_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes axes) +mip_cmd_result mip_filter_write_tare_orientation(mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes axes) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -441,10 +341,9 @@ mip_cmd_result mip_filter_write_tare_orientation(struct mip_interface* device, m assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes* axes_out) +mip_cmd_result mip_filter_read_tare_orientation(mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes* axes_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -455,8 +354,7 @@ mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mi assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_TARE_ORIENTATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_TARE_ORIENTATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -466,12 +364,12 @@ mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mi assert(axes_out); extract_mip_filter_tare_orientation_command_mip_tare_axes(&deserializer, axes_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_tare_orientation(struct mip_interface* device) +mip_cmd_result mip_filter_save_tare_orientation(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -481,10 +379,9 @@ mip_cmd_result mip_filter_save_tare_orientation(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_tare_orientation(struct mip_interface* device) +mip_cmd_result mip_filter_load_tare_orientation(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -494,10 +391,9 @@ mip_cmd_result mip_filter_load_tare_orientation(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_tare_orientation(struct mip_interface* device) +mip_cmd_result mip_filter_default_tare_orientation(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -507,8 +403,7 @@ mip_cmd_result mip_filter_default_tare_orientation(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_TARE_ORIENTATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_vehicle_dynamics_mode_command(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self) { @@ -531,29 +426,7 @@ void extract_mip_filter_vehicle_dynamics_mode_command(microstrain_serializer* se } } -void insert_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_response* self) -{ - insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(serializer, self->mode); - -} -void extract_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_response* self) -{ - extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(serializer, &self->mode); - -} - -void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode) +mip_cmd_result mip_filter_write_vehicle_dynamics_mode(mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -565,10 +438,9 @@ mip_cmd_result mip_filter_write_vehicle_dynamics_mode(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* mode_out) +mip_cmd_result mip_filter_read_vehicle_dynamics_mode(mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* mode_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -579,8 +451,7 @@ mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -590,12 +461,12 @@ mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* devic assert(mode_out); extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(&deserializer, mode_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_vehicle_dynamics_mode(struct mip_interface* device) +mip_cmd_result mip_filter_save_vehicle_dynamics_mode(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -605,10 +476,9 @@ mip_cmd_result mip_filter_save_vehicle_dynamics_mode(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_vehicle_dynamics_mode(struct mip_interface* device) +mip_cmd_result mip_filter_load_vehicle_dynamics_mode(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -618,10 +488,9 @@ mip_cmd_result mip_filter_load_vehicle_dynamics_mode(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_vehicle_dynamics_mode(struct mip_interface* device) +mip_cmd_result mip_filter_default_vehicle_dynamics_mode(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -631,8 +500,7 @@ mip_cmd_result mip_filter_default_vehicle_dynamics_mode(struct mip_interface* de assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self) { @@ -641,9 +509,9 @@ void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_seri if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_float(serializer, self->roll); - + microstrain_insert_float(serializer, self->pitch); - + microstrain_insert_float(serializer, self->yaw); } @@ -655,53 +523,33 @@ void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_ser if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_float(serializer, &self->roll); - + microstrain_extract_float(serializer, &self->pitch); - + microstrain_extract_float(serializer, &self->yaw); } } -void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self) -{ - microstrain_insert_float(serializer, self->roll); - - microstrain_insert_float(serializer, self->pitch); - - microstrain_insert_float(serializer, self->yaw); - -} -void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self) -{ - microstrain_extract_float(serializer, &self->roll); - - microstrain_extract_float(serializer, &self->pitch); - - microstrain_extract_float(serializer, &self->yaw); - -} - -mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float roll, float pitch, float yaw) +mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(mip_interface* device, float roll, float pitch, float yaw) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_float(&serializer, roll); - + microstrain_insert_float(&serializer, pitch); - + microstrain_insert_float(&serializer, yaw); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out) +mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -712,8 +560,7 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_inter assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -729,12 +576,12 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_inter assert(yaw_out); microstrain_extract_float(&deserializer, yaw_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_euler(struct mip_interface* device) +mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_euler(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -744,10 +591,9 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_euler(struct mip_inter assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_euler(struct mip_interface* device) +mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_euler(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -757,10 +603,9 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_euler(struct mip_inter assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(struct mip_interface* device) +mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -770,8 +615,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(struct mip_in assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_command* self) { @@ -779,8 +623,7 @@ void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_serial if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->dcm[i]); + insert_mip_matrix3f(serializer, self->dcm); } } @@ -790,26 +633,12 @@ void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_seria if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->dcm[i]); + extract_mip_matrix3f(serializer, self->dcm); } } -void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self) -{ - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->dcm[i]); - -} -void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self) -{ - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->dcm[i]); - -} - -mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, const float* dcm) +mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(mip_interface* device, const float* dcm) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -817,16 +646,15 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(struct mip_interf insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(dcm || (9 == 0)); + assert(dcm); for(unsigned int i=0; i < 9; i++) microstrain_insert_float(&serializer, dcm[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, float* dcm_out) +mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(mip_interface* device, float* dcm_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -837,24 +665,23 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interfa assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(dcm_out || (9 == 0)); + assert(dcm_out); for(unsigned int i=0; i < 9; i++) microstrain_extract_float(&deserializer, &dcm_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_dcm(struct mip_interface* device) +mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_dcm(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -864,10 +691,9 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_dcm(struct mip_interfa assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_dcm(struct mip_interface* device) +mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_dcm(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -877,10 +703,9 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_dcm(struct mip_interfa assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(struct mip_interface* device) +mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -890,8 +715,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(struct mip_inte assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_command* self) { @@ -899,8 +723,7 @@ void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrain if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 4; i++) - microstrain_insert_float(serializer, self->quat[i]); + insert_mip_quatf(serializer, self->quat); } } @@ -910,26 +733,12 @@ void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrai if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 4; i++) - microstrain_extract_float(serializer, &self->quat[i]); + extract_mip_quatf(serializer, self->quat); } } -void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) -{ - for(unsigned int i=0; i < 4; i++) - microstrain_insert_float(serializer, self->quat[i]); - -} -void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) -{ - for(unsigned int i=0; i < 4; i++) - microstrain_extract_float(serializer, &self->quat[i]); - -} - -mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, const float* quat) +mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(mip_interface* device, const float* quat) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -937,16 +746,15 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(struct mip insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(quat || (4 == 0)); + assert(quat); for(unsigned int i=0; i < 4; i++) microstrain_insert_float(&serializer, quat[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, float* quat_out) +mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(mip_interface* device, float* quat_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -957,24 +765,23 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_ assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(quat_out || (4 == 0)); + assert(quat_out); for(unsigned int i=0; i < 4; i++) microstrain_extract_float(&deserializer, &quat_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device) +mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_quaternion(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -984,10 +791,9 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_quaternion(struct mip_ assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device) +mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_quaternion(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -997,10 +803,9 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_quaternion(struct mip_ assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device) +mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1010,8 +815,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(struct m assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_command* self) { @@ -1019,8 +823,7 @@ void insert_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset[i]); + insert_mip_vector3f(serializer, self->offset); } } @@ -1030,26 +833,12 @@ void extract_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset[i]); + extract_mip_vector3f(serializer, self->offset); } } -void insert_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset[i]); - -} -void extract_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset[i]); - -} - -mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(struct mip_interface* device, const float* offset) +mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(mip_interface* device, const float* offset) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1057,16 +846,15 @@ mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(struct mip_interface* d insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(offset || (3 == 0)); + assert(offset); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, offset[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* device, float* offset_out) +mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(mip_interface* device, float* offset_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1077,24 +865,23 @@ mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* de assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(offset_out || (3 == 0)); + assert(offset_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &offset_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_sensor_to_vehicle_offset(struct mip_interface* device) +mip_cmd_result mip_filter_save_sensor_to_vehicle_offset(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1104,10 +891,9 @@ mip_cmd_result mip_filter_save_sensor_to_vehicle_offset(struct mip_interface* de assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_sensor_to_vehicle_offset(struct mip_interface* device) +mip_cmd_result mip_filter_load_sensor_to_vehicle_offset(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1117,10 +903,9 @@ mip_cmd_result mip_filter_load_sensor_to_vehicle_offset(struct mip_interface* de assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(struct mip_interface* device) +mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1130,8 +915,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_antenna_offset_command(microstrain_serializer* serializer, const mip_filter_antenna_offset_command* self) { @@ -1139,8 +923,7 @@ void insert_mip_filter_antenna_offset_command(microstrain_serializer* serializer if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset[i]); + insert_mip_vector3f(serializer, self->offset); } } @@ -1150,26 +933,12 @@ void extract_mip_filter_antenna_offset_command(microstrain_serializer* serialize if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset[i]); + extract_mip_vector3f(serializer, self->offset); } } -void insert_mip_filter_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_antenna_offset_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset[i]); - -} -void extract_mip_filter_antenna_offset_response(microstrain_serializer* serializer, mip_filter_antenna_offset_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset[i]); - -} - -mip_cmd_result mip_filter_write_antenna_offset(struct mip_interface* device, const float* offset) +mip_cmd_result mip_filter_write_antenna_offset(mip_interface* device, const float* offset) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1177,16 +946,15 @@ mip_cmd_result mip_filter_write_antenna_offset(struct mip_interface* device, con insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(offset || (3 == 0)); + assert(offset); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, offset[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, float* offset_out) +mip_cmd_result mip_filter_read_antenna_offset(mip_interface* device, float* offset_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1197,24 +965,23 @@ mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, floa assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_ANTENNA_OFFSET, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(offset_out || (3 == 0)); + assert(offset_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &offset_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_antenna_offset(struct mip_interface* device) +mip_cmd_result mip_filter_save_antenna_offset(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1224,10 +991,9 @@ mip_cmd_result mip_filter_save_antenna_offset(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_antenna_offset(struct mip_interface* device) +mip_cmd_result mip_filter_load_antenna_offset(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1237,10 +1003,9 @@ mip_cmd_result mip_filter_load_antenna_offset(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_antenna_offset(struct mip_interface* device) +mip_cmd_result mip_filter_default_antenna_offset(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1250,8 +1015,7 @@ mip_cmd_result mip_filter_default_antenna_offset(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_gnss_source_command(microstrain_serializer* serializer, const mip_filter_gnss_source_command* self) { @@ -1274,29 +1038,7 @@ void extract_mip_filter_gnss_source_command(microstrain_serializer* serializer, } } -void insert_mip_filter_gnss_source_response(microstrain_serializer* serializer, const mip_filter_gnss_source_response* self) -{ - insert_mip_filter_gnss_source_command_source(serializer, self->source); - -} -void extract_mip_filter_gnss_source_response(microstrain_serializer* serializer, mip_filter_gnss_source_response* self) -{ - extract_mip_filter_gnss_source_command_source(serializer, &self->source); - -} - -void insert_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source source) +mip_cmd_result mip_filter_write_gnss_source(mip_interface* device, mip_filter_gnss_source_command_source source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1308,10 +1050,9 @@ mip_cmd_result mip_filter_write_gnss_source(struct mip_interface* device, mip_fi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source* source_out) +mip_cmd_result mip_filter_read_gnss_source(mip_interface* device, mip_filter_gnss_source_command_source* source_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1322,8 +1063,7 @@ mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_fil assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1333,12 +1073,12 @@ mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_fil assert(source_out); extract_mip_filter_gnss_source_command_source(&deserializer, source_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_gnss_source(struct mip_interface* device) +mip_cmd_result mip_filter_save_gnss_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1348,10 +1088,9 @@ mip_cmd_result mip_filter_save_gnss_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_gnss_source(struct mip_interface* device) +mip_cmd_result mip_filter_load_gnss_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1361,10 +1100,9 @@ mip_cmd_result mip_filter_load_gnss_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_gnss_source(struct mip_interface* device) +mip_cmd_result mip_filter_default_gnss_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1374,8 +1112,7 @@ mip_cmd_result mip_filter_default_gnss_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_heading_source_command(microstrain_serializer* serializer, const mip_filter_heading_source_command* self) { @@ -1398,29 +1135,7 @@ void extract_mip_filter_heading_source_command(microstrain_serializer* serialize } } -void insert_mip_filter_heading_source_response(microstrain_serializer* serializer, const mip_filter_heading_source_response* self) -{ - insert_mip_filter_heading_source_command_source(serializer, self->source); - -} -void extract_mip_filter_heading_source_response(microstrain_serializer* serializer, mip_filter_heading_source_response* self) -{ - extract_mip_filter_heading_source_command_source(serializer, &self->source); - -} - -void insert_mip_filter_heading_source_command_source(microstrain_serializer* serializer, const mip_filter_heading_source_command_source self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_heading_source_command_source(microstrain_serializer* serializer, mip_filter_heading_source_command_source* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source source) +mip_cmd_result mip_filter_write_heading_source(mip_interface* device, mip_filter_heading_source_command_source source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1432,10 +1147,9 @@ mip_cmd_result mip_filter_write_heading_source(struct mip_interface* device, mip assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source* source_out) +mip_cmd_result mip_filter_read_heading_source(mip_interface* device, mip_filter_heading_source_command_source* source_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1446,8 +1160,7 @@ mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_ assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1457,12 +1170,12 @@ mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_ assert(source_out); extract_mip_filter_heading_source_command_source(&deserializer, source_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_heading_source(struct mip_interface* device) +mip_cmd_result mip_filter_save_heading_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1472,10 +1185,9 @@ mip_cmd_result mip_filter_save_heading_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_heading_source(struct mip_interface* device) +mip_cmd_result mip_filter_load_heading_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1485,10 +1197,9 @@ mip_cmd_result mip_filter_load_heading_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_heading_source(struct mip_interface* device) +mip_cmd_result mip_filter_default_heading_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1498,8 +1209,7 @@ mip_cmd_result mip_filter_default_heading_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HEADING_UPDATE_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_auto_init_control_command(microstrain_serializer* serializer, const mip_filter_auto_init_control_command* self) { @@ -1522,33 +1232,21 @@ void extract_mip_filter_auto_init_control_command(microstrain_serializer* serial } } -void insert_mip_filter_auto_init_control_response(microstrain_serializer* serializer, const mip_filter_auto_init_control_response* self) -{ - microstrain_insert_u8(serializer, self->enable); - -} -void extract_mip_filter_auto_init_control_response(microstrain_serializer* serializer, mip_filter_auto_init_control_response* self) -{ - microstrain_extract_u8(serializer, &self->enable); - -} - -mip_cmd_result mip_filter_write_auto_init_control(struct mip_interface* device, uint8_t enable) +mip_cmd_result mip_filter_write_auto_init_control(mip_interface* device, uint8_t enable) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, enable); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, uint8_t* enable_out) +mip_cmd_result mip_filter_read_auto_init_control(mip_interface* device, uint8_t* enable_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1559,8 +1257,7 @@ mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, u assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_AUTOINIT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_AUTOINIT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1570,12 +1267,12 @@ mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, u assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_auto_init_control(struct mip_interface* device) +mip_cmd_result mip_filter_save_auto_init_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1585,10 +1282,9 @@ mip_cmd_result mip_filter_save_auto_init_control(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_auto_init_control(struct mip_interface* device) +mip_cmd_result mip_filter_load_auto_init_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1598,10 +1294,9 @@ mip_cmd_result mip_filter_load_auto_init_control(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_auto_init_control(struct mip_interface* device) +mip_cmd_result mip_filter_default_auto_init_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1611,8 +1306,7 @@ mip_cmd_result mip_filter_default_auto_init_control(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AUTOINIT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_accel_noise_command(microstrain_serializer* serializer, const mip_filter_accel_noise_command* self) { @@ -1620,8 +1314,7 @@ void insert_mip_filter_accel_noise_command(microstrain_serializer* serializer, c if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); + insert_mip_vector3f(serializer, self->noise); } } @@ -1631,43 +1324,28 @@ void extract_mip_filter_accel_noise_command(microstrain_serializer* serializer, if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); + extract_mip_vector3f(serializer, self->noise); } } -void insert_mip_filter_accel_noise_response(microstrain_serializer* serializer, const mip_filter_accel_noise_response* self) +mip_cmd_result mip_filter_write_accel_noise(mip_interface* device, const float* noise) { + microstrain_serializer serializer; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); + + insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); + + assert(noise); for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); - -} -void extract_mip_filter_accel_noise_response(microstrain_serializer* serializer, mip_filter_accel_noise_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); - -} - -mip_cmd_result mip_filter_write_accel_noise(struct mip_interface* device, const float* noise) -{ - microstrain_serializer serializer; - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - - insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - - assert(noise || (3 == 0)); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(&serializer, noise[i]); + microstrain_insert_float(&serializer, noise[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* noise_out) +mip_cmd_result mip_filter_read_accel_noise(mip_interface* device, float* noise_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1678,24 +1356,23 @@ mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_ACCEL_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ACCEL_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(noise_out || (3 == 0)); + assert(noise_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &noise_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_accel_noise(struct mip_interface* device) +mip_cmd_result mip_filter_save_accel_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1705,10 +1382,9 @@ mip_cmd_result mip_filter_save_accel_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_accel_noise(struct mip_interface* device) +mip_cmd_result mip_filter_load_accel_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1718,10 +1394,9 @@ mip_cmd_result mip_filter_load_accel_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_accel_noise(struct mip_interface* device) +mip_cmd_result mip_filter_default_accel_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1731,8 +1406,7 @@ mip_cmd_result mip_filter_default_accel_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_gyro_noise_command(microstrain_serializer* serializer, const mip_filter_gyro_noise_command* self) { @@ -1740,8 +1414,7 @@ void insert_mip_filter_gyro_noise_command(microstrain_serializer* serializer, co if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); + insert_mip_vector3f(serializer, self->noise); } } @@ -1751,26 +1424,12 @@ void extract_mip_filter_gyro_noise_command(microstrain_serializer* serializer, m if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); + extract_mip_vector3f(serializer, self->noise); } } -void insert_mip_filter_gyro_noise_response(microstrain_serializer* serializer, const mip_filter_gyro_noise_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); - -} -void extract_mip_filter_gyro_noise_response(microstrain_serializer* serializer, mip_filter_gyro_noise_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); - -} - -mip_cmd_result mip_filter_write_gyro_noise(struct mip_interface* device, const float* noise) +mip_cmd_result mip_filter_write_gyro_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1778,16 +1437,15 @@ mip_cmd_result mip_filter_write_gyro_noise(struct mip_interface* device, const f insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(noise || (3 == 0)); + assert(noise); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, noise[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* noise_out) +mip_cmd_result mip_filter_read_gyro_noise(mip_interface* device, float* noise_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1798,24 +1456,23 @@ mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* n assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_GYRO_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_GYRO_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(noise_out || (3 == 0)); + assert(noise_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &noise_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_gyro_noise(struct mip_interface* device) +mip_cmd_result mip_filter_save_gyro_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1825,10 +1482,9 @@ mip_cmd_result mip_filter_save_gyro_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_gyro_noise(struct mip_interface* device) +mip_cmd_result mip_filter_load_gyro_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1838,10 +1494,9 @@ mip_cmd_result mip_filter_load_gyro_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_gyro_noise(struct mip_interface* device) +mip_cmd_result mip_filter_default_gyro_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1851,8 +1506,7 @@ mip_cmd_result mip_filter_default_gyro_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_accel_bias_model_command(microstrain_serializer* serializer, const mip_filter_accel_bias_model_command* self) { @@ -1860,11 +1514,9 @@ void insert_mip_filter_accel_bias_model_command(microstrain_serializer* serializ if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->beta[i]); + insert_mip_vector3f(serializer, self->beta); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); + insert_mip_vector3f(serializer, self->noise); } } @@ -1874,35 +1526,14 @@ void extract_mip_filter_accel_bias_model_command(microstrain_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->beta[i]); + extract_mip_vector3f(serializer, self->beta); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); + extract_mip_vector3f(serializer, self->noise); } } -void insert_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, const mip_filter_accel_bias_model_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->beta[i]); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); - -} -void extract_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, mip_filter_accel_bias_model_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->beta[i]); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); - -} - -mip_cmd_result mip_filter_write_accel_bias_model(struct mip_interface* device, const float* beta, const float* noise) +mip_cmd_result mip_filter_write_accel_bias_model(mip_interface* device, const float* beta, const float* noise) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1910,20 +1541,19 @@ mip_cmd_result mip_filter_write_accel_bias_model(struct mip_interface* device, c insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(beta || (3 == 0)); + assert(beta); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, beta[i]); - assert(noise || (3 == 0)); + assert(noise); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, noise[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, float* beta_out, float* noise_out) +mip_cmd_result mip_filter_read_accel_bias_model(mip_interface* device, float* beta_out, float* noise_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1934,28 +1564,27 @@ mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, fl assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(beta_out || (3 == 0)); + assert(beta_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &beta_out[i]); - assert(noise_out || (3 == 0)); + assert(noise_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &noise_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_accel_bias_model(struct mip_interface* device) +mip_cmd_result mip_filter_save_accel_bias_model(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1965,10 +1594,9 @@ mip_cmd_result mip_filter_save_accel_bias_model(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_accel_bias_model(struct mip_interface* device) +mip_cmd_result mip_filter_load_accel_bias_model(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1978,10 +1606,9 @@ mip_cmd_result mip_filter_load_accel_bias_model(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_accel_bias_model(struct mip_interface* device) +mip_cmd_result mip_filter_default_accel_bias_model(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1991,8 +1618,7 @@ mip_cmd_result mip_filter_default_accel_bias_model(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_gyro_bias_model_command(microstrain_serializer* serializer, const mip_filter_gyro_bias_model_command* self) { @@ -2000,11 +1626,9 @@ void insert_mip_filter_gyro_bias_model_command(microstrain_serializer* serialize if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->beta[i]); + insert_mip_vector3f(serializer, self->beta); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); + insert_mip_vector3f(serializer, self->noise); } } @@ -2014,35 +1638,14 @@ void extract_mip_filter_gyro_bias_model_command(microstrain_serializer* serializ if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->beta[i]); + extract_mip_vector3f(serializer, self->beta); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); + extract_mip_vector3f(serializer, self->noise); } } -void insert_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, const mip_filter_gyro_bias_model_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->beta[i]); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); - -} -void extract_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, mip_filter_gyro_bias_model_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->beta[i]); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); - -} - -mip_cmd_result mip_filter_write_gyro_bias_model(struct mip_interface* device, const float* beta, const float* noise) +mip_cmd_result mip_filter_write_gyro_bias_model(mip_interface* device, const float* beta, const float* noise) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2050,20 +1653,19 @@ mip_cmd_result mip_filter_write_gyro_bias_model(struct mip_interface* device, co insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(beta || (3 == 0)); + assert(beta); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, beta[i]); - assert(noise || (3 == 0)); + assert(noise); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, noise[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, float* beta_out, float* noise_out) +mip_cmd_result mip_filter_read_gyro_bias_model(mip_interface* device, float* beta_out, float* noise_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2074,28 +1676,27 @@ mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, flo assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_GYRO_BIAS_MODEL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_GYRO_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(beta_out || (3 == 0)); + assert(beta_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &beta_out[i]); - assert(noise_out || (3 == 0)); + assert(noise_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &noise_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_gyro_bias_model(struct mip_interface* device) +mip_cmd_result mip_filter_save_gyro_bias_model(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2105,10 +1706,9 @@ mip_cmd_result mip_filter_save_gyro_bias_model(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_gyro_bias_model(struct mip_interface* device) +mip_cmd_result mip_filter_load_gyro_bias_model(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2118,10 +1718,9 @@ mip_cmd_result mip_filter_load_gyro_bias_model(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_gyro_bias_model(struct mip_interface* device) +mip_cmd_result mip_filter_default_gyro_bias_model(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2131,8 +1730,7 @@ mip_cmd_result mip_filter_default_gyro_bias_model(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GYRO_BIAS_MODEL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_altitude_aiding_command(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command* self) { @@ -2155,29 +1753,7 @@ void extract_mip_filter_altitude_aiding_command(microstrain_serializer* serializ } } -void insert_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, const mip_filter_altitude_aiding_response* self) -{ - insert_mip_filter_altitude_aiding_command_aiding_selector(serializer, self->selector); - -} -void extract_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, mip_filter_altitude_aiding_response* self) -{ - extract_mip_filter_altitude_aiding_command_aiding_selector(serializer, &self->selector); - -} - -void insert_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector selector) +mip_cmd_result mip_filter_write_altitude_aiding(mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector selector) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2189,10 +1765,9 @@ mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, mi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector* selector_out) +mip_cmd_result mip_filter_read_altitude_aiding(mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector* selector_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2203,8 +1778,7 @@ mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2214,12 +1788,12 @@ mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip assert(selector_out); extract_mip_filter_altitude_aiding_command_aiding_selector(&deserializer, selector_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_altitude_aiding(struct mip_interface* device) +mip_cmd_result mip_filter_save_altitude_aiding(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2229,10 +1803,9 @@ mip_cmd_result mip_filter_save_altitude_aiding(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device) +mip_cmd_result mip_filter_load_altitude_aiding(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2242,10 +1815,9 @@ mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device) +mip_cmd_result mip_filter_default_altitude_aiding(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2255,8 +1827,7 @@ mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_pitch_roll_aiding_command(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self) { @@ -2279,29 +1850,7 @@ void extract_mip_filter_pitch_roll_aiding_command(microstrain_serializer* serial } } -void insert_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_response* self) -{ - insert_mip_filter_pitch_roll_aiding_command_aiding_source(serializer, self->source); - -} -void extract_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_response* self) -{ - extract_mip_filter_pitch_roll_aiding_command_aiding_source(serializer, &self->source); - -} - -void insert_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source source) +mip_cmd_result mip_filter_write_pitch_roll_aiding(mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2313,10 +1862,9 @@ mip_cmd_result mip_filter_write_pitch_roll_aiding(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source* source_out) +mip_cmd_result mip_filter_read_pitch_roll_aiding(mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source* source_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2327,8 +1875,7 @@ mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, m assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2338,12 +1885,12 @@ mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, m assert(source_out); extract_mip_filter_pitch_roll_aiding_command_aiding_source(&deserializer, source_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_pitch_roll_aiding(struct mip_interface* device) +mip_cmd_result mip_filter_save_pitch_roll_aiding(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2353,10 +1900,9 @@ mip_cmd_result mip_filter_save_pitch_roll_aiding(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_pitch_roll_aiding(struct mip_interface* device) +mip_cmd_result mip_filter_load_pitch_roll_aiding(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2366,10 +1912,9 @@ mip_cmd_result mip_filter_load_pitch_roll_aiding(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_pitch_roll_aiding(struct mip_interface* device) +mip_cmd_result mip_filter_default_pitch_roll_aiding(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2379,8 +1924,7 @@ mip_cmd_result mip_filter_default_pitch_roll_aiding(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_auto_zupt_command(microstrain_serializer* serializer, const mip_filter_auto_zupt_command* self) { @@ -2389,7 +1933,7 @@ void insert_mip_filter_auto_zupt_command(microstrain_serializer* serializer, con if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_u8(serializer, self->enable); - + microstrain_insert_float(serializer, self->threshold); } @@ -2401,45 +1945,29 @@ void extract_mip_filter_auto_zupt_command(microstrain_serializer* serializer, mi if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_u8(serializer, &self->enable); - + microstrain_extract_float(serializer, &self->threshold); } } -void insert_mip_filter_auto_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_zupt_response* self) -{ - microstrain_insert_u8(serializer, self->enable); - - microstrain_insert_float(serializer, self->threshold); - -} -void extract_mip_filter_auto_zupt_response(microstrain_serializer* serializer, mip_filter_auto_zupt_response* self) -{ - microstrain_extract_u8(serializer, &self->enable); - - microstrain_extract_float(serializer, &self->threshold); - -} - -mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t enable, float threshold) +mip_cmd_result mip_filter_write_auto_zupt(mip_interface* device, uint8_t enable, float threshold) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, enable); - + microstrain_insert_float(&serializer, threshold); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out) +mip_cmd_result mip_filter_read_auto_zupt(mip_interface* device, uint8_t* enable_out, float* threshold_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2450,8 +1978,7 @@ mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_ZUPT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2464,12 +1991,12 @@ mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* assert(threshold_out); microstrain_extract_float(&deserializer, threshold_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_auto_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_save_auto_zupt(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2479,10 +2006,9 @@ mip_cmd_result mip_filter_save_auto_zupt(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_load_auto_zupt(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2492,10 +2018,9 @@ mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_default_auto_zupt(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2505,8 +2030,7 @@ mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_auto_angular_zupt_command(microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_command* self) { @@ -2515,7 +2039,7 @@ void insert_mip_filter_auto_angular_zupt_command(microstrain_serializer* seriali if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_u8(serializer, self->enable); - + microstrain_insert_float(serializer, self->threshold); } @@ -2527,45 +2051,29 @@ void extract_mip_filter_auto_angular_zupt_command(microstrain_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_u8(serializer, &self->enable); - + microstrain_extract_float(serializer, &self->threshold); } } -void insert_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_response* self) -{ - microstrain_insert_u8(serializer, self->enable); - - microstrain_insert_float(serializer, self->threshold); - -} -void extract_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, mip_filter_auto_angular_zupt_response* self) -{ - microstrain_extract_u8(serializer, &self->enable); - - microstrain_extract_float(serializer, &self->threshold); - -} - -mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, uint8_t enable, float threshold) +mip_cmd_result mip_filter_write_auto_angular_zupt(mip_interface* device, uint8_t enable, float threshold) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, enable); - + microstrain_insert_float(&serializer, threshold); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out) +mip_cmd_result mip_filter_read_auto_angular_zupt(mip_interface* device, uint8_t* enable_out, float* threshold_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2576,8 +2084,7 @@ mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, u assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2590,12 +2097,12 @@ mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, u assert(threshold_out); microstrain_extract_float(&deserializer, threshold_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_auto_angular_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_save_auto_angular_zupt(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2605,10 +2112,9 @@ mip_cmd_result mip_filter_save_auto_angular_zupt(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_load_auto_angular_zupt(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2618,10 +2124,9 @@ mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_default_auto_angular_zupt(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2631,14 +2136,13 @@ mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_commanded_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_commanded_zupt(mip_interface* device) { return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_COMMANDED_ZUPT, NULL, 0); } -mip_cmd_result mip_filter_commanded_angular_zupt(struct mip_interface* device) +mip_cmd_result mip_filter_commanded_angular_zupt(mip_interface* device) { return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_COMMANDED_ANGULAR_ZUPT, NULL, 0); } @@ -2653,7 +2157,7 @@ void extract_mip_filter_mag_capture_auto_cal_command(microstrain_serializer* ser } -mip_cmd_result mip_filter_write_mag_capture_auto_cal(struct mip_interface* device) +mip_cmd_result mip_filter_write_mag_capture_auto_cal(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2663,10 +2167,9 @@ mip_cmd_result mip_filter_write_mag_capture_auto_cal(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device) +mip_cmd_result mip_filter_save_mag_capture_auto_cal(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2676,8 +2179,7 @@ mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_gravity_noise_command(microstrain_serializer* serializer, const mip_filter_gravity_noise_command* self) { @@ -2685,8 +2187,7 @@ void insert_mip_filter_gravity_noise_command(microstrain_serializer* serializer, if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); + insert_mip_vector3f(serializer, self->noise); } } @@ -2696,26 +2197,12 @@ void extract_mip_filter_gravity_noise_command(microstrain_serializer* serializer if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); + extract_mip_vector3f(serializer, self->noise); } } -void insert_mip_filter_gravity_noise_response(microstrain_serializer* serializer, const mip_filter_gravity_noise_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); - -} -void extract_mip_filter_gravity_noise_response(microstrain_serializer* serializer, mip_filter_gravity_noise_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); - -} - -mip_cmd_result mip_filter_write_gravity_noise(struct mip_interface* device, const float* noise) +mip_cmd_result mip_filter_write_gravity_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2723,16 +2210,15 @@ mip_cmd_result mip_filter_write_gravity_noise(struct mip_interface* device, cons insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(noise || (3 == 0)); + assert(noise); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, noise[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float* noise_out) +mip_cmd_result mip_filter_read_gravity_noise(mip_interface* device, float* noise_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2743,24 +2229,23 @@ mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_GRAVITY_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_GRAVITY_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(noise_out || (3 == 0)); + assert(noise_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &noise_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_gravity_noise(struct mip_interface* device) +mip_cmd_result mip_filter_save_gravity_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2770,10 +2255,9 @@ mip_cmd_result mip_filter_save_gravity_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_gravity_noise(struct mip_interface* device) +mip_cmd_result mip_filter_load_gravity_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2783,10 +2267,9 @@ mip_cmd_result mip_filter_load_gravity_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_gravity_noise(struct mip_interface* device) +mip_cmd_result mip_filter_default_gravity_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2796,8 +2279,7 @@ mip_cmd_result mip_filter_default_gravity_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GRAVITY_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_pressure_altitude_noise_command(microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self) { @@ -2820,33 +2302,21 @@ void extract_mip_filter_pressure_altitude_noise_command(microstrain_serializer* } } -void insert_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self) -{ - microstrain_insert_float(serializer, self->noise); - -} -void extract_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_response* self) -{ - microstrain_extract_float(serializer, &self->noise); - -} - -mip_cmd_result mip_filter_write_pressure_altitude_noise(struct mip_interface* device, float noise) +mip_cmd_result mip_filter_write_pressure_altitude_noise(mip_interface* device, float noise) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_float(&serializer, noise); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* device, float* noise_out) +mip_cmd_result mip_filter_read_pressure_altitude_noise(mip_interface* device, float* noise_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2857,8 +2327,7 @@ mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* dev assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_PRESSURE_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_PRESSURE_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2868,12 +2337,12 @@ mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* dev assert(noise_out); microstrain_extract_float(&deserializer, noise_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_pressure_altitude_noise(struct mip_interface* device) +mip_cmd_result mip_filter_save_pressure_altitude_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2883,10 +2352,9 @@ mip_cmd_result mip_filter_save_pressure_altitude_noise(struct mip_interface* dev assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_pressure_altitude_noise(struct mip_interface* device) +mip_cmd_result mip_filter_load_pressure_altitude_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2896,10 +2364,9 @@ mip_cmd_result mip_filter_load_pressure_altitude_noise(struct mip_interface* dev assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_pressure_altitude_noise(struct mip_interface* device) +mip_cmd_result mip_filter_default_pressure_altitude_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2909,8 +2376,7 @@ mip_cmd_result mip_filter_default_pressure_altitude_noise(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_PRESSURE_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self) { @@ -2918,8 +2384,7 @@ void insert_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* se if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); + insert_mip_vector3f(serializer, self->noise); } } @@ -2929,26 +2394,12 @@ void extract_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* s if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); + extract_mip_vector3f(serializer, self->noise); } } -void insert_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); - -} -void extract_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); - -} - -mip_cmd_result mip_filter_write_hard_iron_offset_noise(struct mip_interface* device, const float* noise) +mip_cmd_result mip_filter_write_hard_iron_offset_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2956,16 +2407,15 @@ mip_cmd_result mip_filter_write_hard_iron_offset_noise(struct mip_interface* dev insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(noise || (3 == 0)); + assert(noise); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, noise[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* device, float* noise_out) +mip_cmd_result mip_filter_read_hard_iron_offset_noise(mip_interface* device, float* noise_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2976,24 +2426,23 @@ mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(noise_out || (3 == 0)); + assert(noise_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &noise_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_hard_iron_offset_noise(struct mip_interface* device) +mip_cmd_result mip_filter_save_hard_iron_offset_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3003,10 +2452,9 @@ mip_cmd_result mip_filter_save_hard_iron_offset_noise(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_hard_iron_offset_noise(struct mip_interface* device) +mip_cmd_result mip_filter_load_hard_iron_offset_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3016,10 +2464,9 @@ mip_cmd_result mip_filter_load_hard_iron_offset_noise(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_hard_iron_offset_noise(struct mip_interface* device) +mip_cmd_result mip_filter_default_hard_iron_offset_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3029,8 +2476,7 @@ mip_cmd_result mip_filter_default_hard_iron_offset_noise(struct mip_interface* d assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self) { @@ -3038,8 +2484,7 @@ void insert_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* se if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->noise[i]); + insert_mip_matrix3f(serializer, self->noise); } } @@ -3049,26 +2494,12 @@ void extract_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* s if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->noise[i]); + extract_mip_matrix3f(serializer, self->noise); } } -void insert_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self) -{ - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->noise[i]); - -} -void extract_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self) -{ - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->noise[i]); - -} - -mip_cmd_result mip_filter_write_soft_iron_matrix_noise(struct mip_interface* device, const float* noise) +mip_cmd_result mip_filter_write_soft_iron_matrix_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3076,16 +2507,15 @@ mip_cmd_result mip_filter_write_soft_iron_matrix_noise(struct mip_interface* dev insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(noise || (9 == 0)); + assert(noise); for(unsigned int i=0; i < 9; i++) microstrain_insert_float(&serializer, noise[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* device, float* noise_out) +mip_cmd_result mip_filter_read_soft_iron_matrix_noise(mip_interface* device, float* noise_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3096,24 +2526,23 @@ mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(noise_out || (9 == 0)); + assert(noise_out); for(unsigned int i=0; i < 9; i++) microstrain_extract_float(&deserializer, &noise_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_soft_iron_matrix_noise(struct mip_interface* device) +mip_cmd_result mip_filter_save_soft_iron_matrix_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3123,10 +2552,9 @@ mip_cmd_result mip_filter_save_soft_iron_matrix_noise(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_soft_iron_matrix_noise(struct mip_interface* device) +mip_cmd_result mip_filter_load_soft_iron_matrix_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3136,10 +2564,9 @@ mip_cmd_result mip_filter_load_soft_iron_matrix_noise(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_soft_iron_matrix_noise(struct mip_interface* device) +mip_cmd_result mip_filter_default_soft_iron_matrix_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3149,8 +2576,7 @@ mip_cmd_result mip_filter_default_soft_iron_matrix_noise(struct mip_interface* d assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_mag_noise_command(microstrain_serializer* serializer, const mip_filter_mag_noise_command* self) { @@ -3158,8 +2584,7 @@ void insert_mip_filter_mag_noise_command(microstrain_serializer* serializer, con if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); + insert_mip_vector3f(serializer, self->noise); } } @@ -3169,26 +2594,12 @@ void extract_mip_filter_mag_noise_command(microstrain_serializer* serializer, mi if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); + extract_mip_vector3f(serializer, self->noise); } } -void insert_mip_filter_mag_noise_response(microstrain_serializer* serializer, const mip_filter_mag_noise_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->noise[i]); - -} -void extract_mip_filter_mag_noise_response(microstrain_serializer* serializer, mip_filter_mag_noise_response* self) -{ - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->noise[i]); - -} - -mip_cmd_result mip_filter_write_mag_noise(struct mip_interface* device, const float* noise) +mip_cmd_result mip_filter_write_mag_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3196,16 +2607,15 @@ mip_cmd_result mip_filter_write_mag_noise(struct mip_interface* device, const fl insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - assert(noise || (3 == 0)); + assert(noise); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, noise[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* noise_out) +mip_cmd_result mip_filter_read_mag_noise(mip_interface* device, float* noise_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3216,24 +2626,23 @@ mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* no assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_MAG_NOISE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MAG_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(noise_out || (3 == 0)); + assert(noise_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &noise_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_mag_noise(struct mip_interface* device) +mip_cmd_result mip_filter_save_mag_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3243,10 +2652,9 @@ mip_cmd_result mip_filter_save_mag_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_mag_noise(struct mip_interface* device) +mip_cmd_result mip_filter_load_mag_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3256,10 +2664,9 @@ mip_cmd_result mip_filter_load_mag_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_mag_noise(struct mip_interface* device) +mip_cmd_result mip_filter_default_mag_noise(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3269,8 +2676,7 @@ mip_cmd_result mip_filter_default_mag_noise(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_NOISE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_inclination_source_command(microstrain_serializer* serializer, const mip_filter_inclination_source_command* self) { @@ -3279,7 +2685,7 @@ void insert_mip_filter_inclination_source_command(microstrain_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_mag_param_source(serializer, self->source); - + microstrain_insert_float(serializer, self->inclination); } @@ -3291,28 +2697,13 @@ void extract_mip_filter_inclination_source_command(microstrain_serializer* seria if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_mag_param_source(serializer, &self->source); - + microstrain_extract_float(serializer, &self->inclination); } } -void insert_mip_filter_inclination_source_response(microstrain_serializer* serializer, const mip_filter_inclination_source_response* self) -{ - insert_mip_filter_mag_param_source(serializer, self->source); - - microstrain_insert_float(serializer, self->inclination); - -} -void extract_mip_filter_inclination_source_response(microstrain_serializer* serializer, mip_filter_inclination_source_response* self) -{ - extract_mip_filter_mag_param_source(serializer, &self->source); - - microstrain_extract_float(serializer, &self->inclination); - -} - -mip_cmd_result mip_filter_write_inclination_source(struct mip_interface* device, mip_filter_mag_param_source source, float inclination) +mip_cmd_result mip_filter_write_inclination_source(mip_interface* device, mip_filter_mag_param_source source, float inclination) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3321,15 +2712,14 @@ mip_cmd_result mip_filter_write_inclination_source(struct mip_interface* device, insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_mag_param_source(&serializer, source); - + microstrain_insert_float(&serializer, inclination); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* inclination_out) +mip_cmd_result mip_filter_read_inclination_source(mip_interface* device, mip_filter_mag_param_source* source_out, float* inclination_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3340,8 +2730,7 @@ mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_INCLINATION_SOURCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_INCLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3354,12 +2743,12 @@ mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, assert(inclination_out); microstrain_extract_float(&deserializer, inclination_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_inclination_source(struct mip_interface* device) +mip_cmd_result mip_filter_save_inclination_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3369,10 +2758,9 @@ mip_cmd_result mip_filter_save_inclination_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_inclination_source(struct mip_interface* device) +mip_cmd_result mip_filter_load_inclination_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3382,10 +2770,9 @@ mip_cmd_result mip_filter_load_inclination_source(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_inclination_source(struct mip_interface* device) +mip_cmd_result mip_filter_default_inclination_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3395,8 +2782,7 @@ mip_cmd_result mip_filter_default_inclination_source(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INCLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_magnetic_declination_source_command(microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_command* self) { @@ -3405,7 +2791,7 @@ void insert_mip_filter_magnetic_declination_source_command(microstrain_serialize if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_mag_param_source(serializer, self->source); - + microstrain_insert_float(serializer, self->declination); } @@ -3417,28 +2803,13 @@ void extract_mip_filter_magnetic_declination_source_command(microstrain_serializ if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_mag_param_source(serializer, &self->source); - + microstrain_extract_float(serializer, &self->declination); } } -void insert_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_response* self) -{ - insert_mip_filter_mag_param_source(serializer, self->source); - - microstrain_insert_float(serializer, self->declination); - -} -void extract_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, mip_filter_magnetic_declination_source_response* self) -{ - extract_mip_filter_mag_param_source(serializer, &self->source); - - microstrain_extract_float(serializer, &self->declination); - -} - -mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source source, float declination) +mip_cmd_result mip_filter_write_magnetic_declination_source(mip_interface* device, mip_filter_mag_param_source source, float declination) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3447,15 +2818,14 @@ mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_mag_param_source(&serializer, source); - + microstrain_insert_float(&serializer, declination); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* declination_out) +mip_cmd_result mip_filter_read_magnetic_declination_source(mip_interface* device, mip_filter_mag_param_source* source_out, float* declination_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3466,8 +2836,7 @@ mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_DECLINATION_SOURCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_DECLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3480,12 +2849,12 @@ mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* assert(declination_out); microstrain_extract_float(&deserializer, declination_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_magnetic_declination_source(struct mip_interface* device) +mip_cmd_result mip_filter_save_magnetic_declination_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3495,10 +2864,9 @@ mip_cmd_result mip_filter_save_magnetic_declination_source(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_magnetic_declination_source(struct mip_interface* device) +mip_cmd_result mip_filter_load_magnetic_declination_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3508,10 +2876,9 @@ mip_cmd_result mip_filter_load_magnetic_declination_source(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_magnetic_declination_source(struct mip_interface* device) +mip_cmd_result mip_filter_default_magnetic_declination_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3521,8 +2888,7 @@ mip_cmd_result mip_filter_default_magnetic_declination_source(struct mip_interfa assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_DECLINATION_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_mag_field_magnitude_source_command(microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self) { @@ -3531,7 +2897,7 @@ void insert_mip_filter_mag_field_magnitude_source_command(microstrain_serializer if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_mag_param_source(serializer, self->source); - + microstrain_insert_float(serializer, self->magnitude); } @@ -3543,28 +2909,13 @@ void extract_mip_filter_mag_field_magnitude_source_command(microstrain_serialize if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_mag_param_source(serializer, &self->source); - + microstrain_extract_float(serializer, &self->magnitude); } } -void insert_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self) -{ - insert_mip_filter_mag_param_source(serializer, self->source); - - microstrain_insert_float(serializer, self->magnitude); - -} -void extract_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self) -{ - extract_mip_filter_mag_param_source(serializer, &self->source); - - microstrain_extract_float(serializer, &self->magnitude); - -} - -mip_cmd_result mip_filter_write_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source source, float magnitude) +mip_cmd_result mip_filter_write_mag_field_magnitude_source(mip_interface* device, mip_filter_mag_param_source source, float magnitude) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3573,15 +2924,14 @@ mip_cmd_result mip_filter_write_mag_field_magnitude_source(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_mag_param_source(&serializer, source); - + microstrain_insert_float(&serializer, magnitude); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* magnitude_out) +mip_cmd_result mip_filter_read_mag_field_magnitude_source(mip_interface* device, mip_filter_mag_param_source* source_out, float* magnitude_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3592,8 +2942,7 @@ mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3606,12 +2955,12 @@ mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* assert(magnitude_out); microstrain_extract_float(&deserializer, magnitude_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_mag_field_magnitude_source(struct mip_interface* device) +mip_cmd_result mip_filter_save_mag_field_magnitude_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3621,10 +2970,9 @@ mip_cmd_result mip_filter_save_mag_field_magnitude_source(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_mag_field_magnitude_source(struct mip_interface* device) +mip_cmd_result mip_filter_load_mag_field_magnitude_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3634,10 +2982,9 @@ mip_cmd_result mip_filter_load_mag_field_magnitude_source(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_mag_field_magnitude_source(struct mip_interface* device) +mip_cmd_result mip_filter_default_mag_field_magnitude_source(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3647,8 +2994,7 @@ mip_cmd_result mip_filter_default_mag_field_magnitude_source(struct mip_interfac assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_reference_position_command(microstrain_serializer* serializer, const mip_filter_reference_position_command* self) { @@ -3657,11 +3003,11 @@ void insert_mip_filter_reference_position_command(microstrain_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_bool(serializer, self->enable); - + microstrain_insert_double(serializer, self->latitude); - + microstrain_insert_double(serializer, self->longitude); - + microstrain_insert_double(serializer, self->altitude); } @@ -3673,61 +3019,37 @@ void extract_mip_filter_reference_position_command(microstrain_serializer* seria if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_bool(serializer, &self->enable); - + microstrain_extract_double(serializer, &self->latitude); - + microstrain_extract_double(serializer, &self->longitude); - + microstrain_extract_double(serializer, &self->altitude); } } -void insert_mip_filter_reference_position_response(microstrain_serializer* serializer, const mip_filter_reference_position_response* self) -{ - microstrain_insert_bool(serializer, self->enable); - - microstrain_insert_double(serializer, self->latitude); - - microstrain_insert_double(serializer, self->longitude); - - microstrain_insert_double(serializer, self->altitude); - -} -void extract_mip_filter_reference_position_response(microstrain_serializer* serializer, mip_filter_reference_position_response* self) -{ - microstrain_extract_bool(serializer, &self->enable); - - microstrain_extract_double(serializer, &self->latitude); - - microstrain_extract_double(serializer, &self->longitude); - - microstrain_extract_double(serializer, &self->altitude); - -} - -mip_cmd_result mip_filter_write_reference_position(struct mip_interface* device, bool enable, double latitude, double longitude, double altitude) +mip_cmd_result mip_filter_write_reference_position(mip_interface* device, bool enable, double latitude, double longitude, double altitude) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_bool(&serializer, enable); - + microstrain_insert_double(&serializer, latitude); - + microstrain_insert_double(&serializer, longitude); - + microstrain_insert_double(&serializer, altitude); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, bool* enable_out, double* latitude_out, double* longitude_out, double* altitude_out) +mip_cmd_result mip_filter_read_reference_position(mip_interface* device, bool* enable_out, double* latitude_out, double* longitude_out, double* altitude_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3738,8 +3060,7 @@ mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_REFERENCE_POSITION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_REFERENCE_POSITION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3758,12 +3079,12 @@ mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, assert(altitude_out); microstrain_extract_double(&deserializer, altitude_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_reference_position(struct mip_interface* device) +mip_cmd_result mip_filter_save_reference_position(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3773,10 +3094,9 @@ mip_cmd_result mip_filter_save_reference_position(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_reference_position(struct mip_interface* device) +mip_cmd_result mip_filter_load_reference_position(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3786,10 +3106,9 @@ mip_cmd_result mip_filter_load_reference_position(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_reference_position(struct mip_interface* device) +mip_cmd_result mip_filter_default_reference_position(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3799,8 +3118,7 @@ mip_cmd_result mip_filter_default_reference_position(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REFERENCE_POSITION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self) { @@ -3809,17 +3127,17 @@ void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(micros if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - + microstrain_insert_float(serializer, self->frequency); - + microstrain_insert_float(serializer, self->low_limit); - + microstrain_insert_float(serializer, self->high_limit); - + microstrain_insert_float(serializer, self->low_limit_uncertainty); - + microstrain_insert_float(serializer, self->high_limit_uncertainty); - + microstrain_insert_float(serializer, self->minimum_uncertainty); } @@ -3831,58 +3149,23 @@ void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(micro if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - + microstrain_extract_float(serializer, &self->frequency); - + microstrain_extract_float(serializer, &self->low_limit); - + microstrain_extract_float(serializer, &self->high_limit); - + microstrain_extract_float(serializer, &self->low_limit_uncertainty); - + microstrain_extract_float(serializer, &self->high_limit_uncertainty); - + microstrain_extract_float(serializer, &self->minimum_uncertainty); } } -void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self) -{ - insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - - microstrain_insert_float(serializer, self->frequency); - - microstrain_insert_float(serializer, self->low_limit); - - microstrain_insert_float(serializer, self->high_limit); - - microstrain_insert_float(serializer, self->low_limit_uncertainty); - - microstrain_insert_float(serializer, self->high_limit_uncertainty); - - microstrain_insert_float(serializer, self->minimum_uncertainty); - -} -void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self) -{ - extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - - microstrain_extract_float(serializer, &self->frequency); - - microstrain_extract_float(serializer, &self->low_limit); - - microstrain_extract_float(serializer, &self->high_limit); - - microstrain_extract_float(serializer, &self->low_limit_uncertainty); - - microstrain_extract_float(serializer, &self->high_limit_uncertainty); - - microstrain_extract_float(serializer, &self->minimum_uncertainty); - -} - -mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty) +mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3891,25 +3174,24 @@ mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(struc insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_adaptive_measurement(&serializer, adaptive_measurement); - + microstrain_insert_float(&serializer, frequency); - + microstrain_insert_float(&serializer, low_limit); - + microstrain_insert_float(&serializer, high_limit); - + microstrain_insert_float(&serializer, low_limit_uncertainty); - + microstrain_insert_float(&serializer, high_limit_uncertainty); - + microstrain_insert_float(&serializer, minimum_uncertainty); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) +mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3920,8 +3202,7 @@ mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3949,12 +3230,12 @@ mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct assert(minimum_uncertainty_out); microstrain_extract_float(&deserializer, minimum_uncertainty_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) +mip_cmd_result mip_filter_save_accel_magnitude_error_adaptive_measurement(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3964,10 +3245,9 @@ mip_cmd_result mip_filter_save_accel_magnitude_error_adaptive_measurement(struct assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) +mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3977,10 +3257,9 @@ mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(struct assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(struct mip_interface* device) +mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3990,8 +3269,7 @@ mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(str assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self) { @@ -4000,17 +3278,17 @@ void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(microstr if( self->function == MIP_FUNCTION_WRITE ) { insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - + microstrain_insert_float(serializer, self->frequency); - + microstrain_insert_float(serializer, self->low_limit); - + microstrain_insert_float(serializer, self->high_limit); - + microstrain_insert_float(serializer, self->low_limit_uncertainty); - + microstrain_insert_float(serializer, self->high_limit_uncertainty); - + microstrain_insert_float(serializer, self->minimum_uncertainty); } @@ -4022,58 +3300,23 @@ void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(microst if( self->function == MIP_FUNCTION_WRITE ) { extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - + microstrain_extract_float(serializer, &self->frequency); - + microstrain_extract_float(serializer, &self->low_limit); - + microstrain_extract_float(serializer, &self->high_limit); - + microstrain_extract_float(serializer, &self->low_limit_uncertainty); - + microstrain_extract_float(serializer, &self->high_limit_uncertainty); - + microstrain_extract_float(serializer, &self->minimum_uncertainty); } } -void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self) -{ - insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); - - microstrain_insert_float(serializer, self->frequency); - - microstrain_insert_float(serializer, self->low_limit); - - microstrain_insert_float(serializer, self->high_limit); - - microstrain_insert_float(serializer, self->low_limit_uncertainty); - - microstrain_insert_float(serializer, self->high_limit_uncertainty); - - microstrain_insert_float(serializer, self->minimum_uncertainty); - -} -void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self) -{ - extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); - - microstrain_extract_float(serializer, &self->frequency); - - microstrain_extract_float(serializer, &self->low_limit); - - microstrain_extract_float(serializer, &self->high_limit); - - microstrain_extract_float(serializer, &self->low_limit_uncertainty); - - microstrain_extract_float(serializer, &self->high_limit_uncertainty); - - microstrain_extract_float(serializer, &self->minimum_uncertainty); - -} - -mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty) +mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4082,25 +3325,24 @@ mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(struct insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_adaptive_measurement(&serializer, adaptive_measurement); - + microstrain_insert_float(&serializer, frequency); - + microstrain_insert_float(&serializer, low_limit); - + microstrain_insert_float(&serializer, high_limit); - + microstrain_insert_float(&serializer, low_limit_uncertainty); - + microstrain_insert_float(&serializer, high_limit_uncertainty); - + microstrain_insert_float(&serializer, minimum_uncertainty); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) +mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4111,8 +3353,7 @@ mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct m assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4140,12 +3381,12 @@ mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct m assert(minimum_uncertainty_out); microstrain_extract_float(&deserializer, minimum_uncertainty_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) +mip_cmd_result mip_filter_save_mag_magnitude_error_adaptive_measurement(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4155,10 +3396,9 @@ mip_cmd_result mip_filter_save_mag_magnitude_error_adaptive_measurement(struct m assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) +mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4168,10 +3408,9 @@ mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(struct m assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(struct mip_interface* device) +mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4181,8 +3420,7 @@ mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(struc assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self) { @@ -4191,13 +3429,13 @@ void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microstr if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_bool(serializer, self->enable); - + microstrain_insert_float(serializer, self->frequency); - + microstrain_insert_float(serializer, self->high_limit); - + microstrain_insert_float(serializer, self->high_limit_uncertainty); - + microstrain_insert_float(serializer, self->minimum_uncertainty); } @@ -4209,69 +3447,41 @@ void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microst if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_bool(serializer, &self->enable); - + microstrain_extract_float(serializer, &self->frequency); - + microstrain_extract_float(serializer, &self->high_limit); - + microstrain_extract_float(serializer, &self->high_limit_uncertainty); - + microstrain_extract_float(serializer, &self->minimum_uncertainty); } } -void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) -{ - microstrain_insert_bool(serializer, self->enable); - - microstrain_insert_float(serializer, self->frequency); - - microstrain_insert_float(serializer, self->high_limit); - - microstrain_insert_float(serializer, self->high_limit_uncertainty); - - microstrain_insert_float(serializer, self->minimum_uncertainty); - -} -void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) -{ - microstrain_extract_bool(serializer, &self->enable); - - microstrain_extract_float(serializer, &self->frequency); - - microstrain_extract_float(serializer, &self->high_limit); - - microstrain_extract_float(serializer, &self->high_limit_uncertainty); - - microstrain_extract_float(serializer, &self->minimum_uncertainty); - -} - -mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool enable, float frequency, float high_limit, float high_limit_uncertainty, float minimum_uncertainty) +mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(mip_interface* device, bool enable, float frequency, float high_limit, float high_limit_uncertainty, float minimum_uncertainty) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_bool(&serializer, enable); - + microstrain_insert_float(&serializer, frequency); - + microstrain_insert_float(&serializer, high_limit); - + microstrain_insert_float(&serializer, high_limit_uncertainty); - + microstrain_insert_float(&serializer, minimum_uncertainty); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool* enable_out, float* frequency_out, float* high_limit_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) +mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(mip_interface* device, bool* enable_out, float* frequency_out, float* high_limit_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4282,8 +3492,7 @@ mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct m assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4305,12 +3514,12 @@ mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct m assert(minimum_uncertainty_out); microstrain_extract_float(&deserializer, minimum_uncertainty_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) +mip_cmd_result mip_filter_save_mag_dip_angle_error_adaptive_measurement(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4320,10 +3529,9 @@ mip_cmd_result mip_filter_save_mag_dip_angle_error_adaptive_measurement(struct m assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) +mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4333,10 +3541,9 @@ mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(struct m assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device) +mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4346,8 +3553,7 @@ mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(struc assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_aiding_measurement_enable_command(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self) { @@ -4374,33 +3580,7 @@ void extract_mip_filter_aiding_measurement_enable_command(microstrain_serializer } } -void insert_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self) -{ - insert_mip_filter_aiding_measurement_enable_command_aiding_source(serializer, self->aiding_source); - - microstrain_insert_bool(serializer, self->enable); - -} -void extract_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_response* self) -{ - extract_mip_filter_aiding_measurement_enable_command_aiding_source(serializer, &self->aiding_source); - - microstrain_extract_bool(serializer, &self->enable); - -} - -void insert_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool enable) +mip_cmd_result mip_filter_write_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool enable) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4409,15 +3589,14 @@ mip_cmd_result mip_filter_write_aiding_measurement_enable(struct mip_interface* insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); insert_mip_filter_aiding_measurement_enable_command_aiding_source(&serializer, aiding_source); - + microstrain_insert_bool(&serializer, enable); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool* enable_out) +mip_cmd_result mip_filter_read_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool* enable_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4430,8 +3609,7 @@ mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* d assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4443,12 +3621,12 @@ mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* d assert(enable_out); microstrain_extract_bool(&deserializer, enable_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) +mip_cmd_result mip_filter_save_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4460,10 +3638,9 @@ mip_cmd_result mip_filter_save_aiding_measurement_enable(struct mip_interface* d assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) +mip_cmd_result mip_filter_load_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4475,10 +3652,9 @@ mip_cmd_result mip_filter_load_aiding_measurement_enable(struct mip_interface* d assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) +mip_cmd_result mip_filter_default_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4490,10 +3666,9 @@ mip_cmd_result mip_filter_default_aiding_measurement_enable(struct mip_interface assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_run(struct mip_interface* device) +mip_cmd_result mip_filter_run(mip_interface* device) { return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_RUN, NULL, 0); } @@ -4504,9 +3679,9 @@ void insert_mip_filter_kinematic_constraint_command(microstrain_serializer* seri if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_u8(serializer, self->acceleration_constraint_selection); - + microstrain_insert_u8(serializer, self->velocity_constraint_selection); - + microstrain_insert_u8(serializer, self->angular_constraint_selection); } @@ -4518,53 +3693,33 @@ void extract_mip_filter_kinematic_constraint_command(microstrain_serializer* ser if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_u8(serializer, &self->acceleration_constraint_selection); - + microstrain_extract_u8(serializer, &self->velocity_constraint_selection); - + microstrain_extract_u8(serializer, &self->angular_constraint_selection); } } -void insert_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, const mip_filter_kinematic_constraint_response* self) -{ - microstrain_insert_u8(serializer, self->acceleration_constraint_selection); - - microstrain_insert_u8(serializer, self->velocity_constraint_selection); - - microstrain_insert_u8(serializer, self->angular_constraint_selection); - -} -void extract_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, mip_filter_kinematic_constraint_response* self) -{ - microstrain_extract_u8(serializer, &self->acceleration_constraint_selection); - - microstrain_extract_u8(serializer, &self->velocity_constraint_selection); - - microstrain_extract_u8(serializer, &self->angular_constraint_selection); - -} - -mip_cmd_result mip_filter_write_kinematic_constraint(struct mip_interface* device, uint8_t acceleration_constraint_selection, uint8_t velocity_constraint_selection, uint8_t angular_constraint_selection) +mip_cmd_result mip_filter_write_kinematic_constraint(mip_interface* device, uint8_t acceleration_constraint_selection, uint8_t velocity_constraint_selection, uint8_t angular_constraint_selection) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, acceleration_constraint_selection); - + microstrain_insert_u8(&serializer, velocity_constraint_selection); - + microstrain_insert_u8(&serializer, angular_constraint_selection); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device, uint8_t* acceleration_constraint_selection_out, uint8_t* velocity_constraint_selection_out, uint8_t* angular_constraint_selection_out) +mip_cmd_result mip_filter_read_kinematic_constraint(mip_interface* device, uint8_t* acceleration_constraint_selection_out, uint8_t* velocity_constraint_selection_out, uint8_t* angular_constraint_selection_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4575,8 +3730,7 @@ mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4592,12 +3746,12 @@ mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device assert(angular_constraint_selection_out); microstrain_extract_u8(&deserializer, angular_constraint_selection_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_kinematic_constraint(struct mip_interface* device) +mip_cmd_result mip_filter_save_kinematic_constraint(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4607,10 +3761,9 @@ mip_cmd_result mip_filter_save_kinematic_constraint(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_kinematic_constraint(struct mip_interface* device) +mip_cmd_result mip_filter_load_kinematic_constraint(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4620,10 +3773,9 @@ mip_cmd_result mip_filter_load_kinematic_constraint(struct mip_interface* device assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_kinematic_constraint(struct mip_interface* device) +mip_cmd_result mip_filter_default_kinematic_constraint(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4633,8 +3785,7 @@ mip_cmd_result mip_filter_default_kinematic_constraint(struct mip_interface* dev assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_KINEMATIC_CONSTRAINT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_initialization_configuration_command(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command* self) { @@ -4647,18 +3798,16 @@ void insert_mip_filter_initialization_configuration_command(microstrain_serializ insert_mip_filter_initialization_configuration_command_initial_condition_source(serializer, self->initial_cond_src); insert_mip_filter_initialization_configuration_command_alignment_selector(serializer, self->auto_heading_alignment_selector); - + microstrain_insert_float(serializer, self->initial_heading); - + microstrain_insert_float(serializer, self->initial_pitch); - + microstrain_insert_float(serializer, self->initial_roll); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->initial_position[i]); + insert_mip_vector3f(serializer, self->initial_position); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->initial_velocity[i]); + insert_mip_vector3f(serializer, self->initial_velocity); insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); @@ -4675,118 +3824,47 @@ void extract_mip_filter_initialization_configuration_command(microstrain_seriali extract_mip_filter_initialization_configuration_command_initial_condition_source(serializer, &self->initial_cond_src); extract_mip_filter_initialization_configuration_command_alignment_selector(serializer, &self->auto_heading_alignment_selector); - + microstrain_extract_float(serializer, &self->initial_heading); - + microstrain_extract_float(serializer, &self->initial_pitch); - + microstrain_extract_float(serializer, &self->initial_roll); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->initial_position[i]); + extract_mip_vector3f(serializer, self->initial_position); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->initial_velocity[i]); + extract_mip_vector3f(serializer, self->initial_velocity); extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); } } -void insert_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, const mip_filter_initialization_configuration_response* self) -{ - microstrain_insert_u8(serializer, self->wait_for_run_command); - - insert_mip_filter_initialization_configuration_command_initial_condition_source(serializer, self->initial_cond_src); - - insert_mip_filter_initialization_configuration_command_alignment_selector(serializer, self->auto_heading_alignment_selector); - - microstrain_insert_float(serializer, self->initial_heading); - - microstrain_insert_float(serializer, self->initial_pitch); - - microstrain_insert_float(serializer, self->initial_roll); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->initial_position[i]); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->initial_velocity[i]); - - insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); - -} -void extract_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, mip_filter_initialization_configuration_response* self) -{ - microstrain_extract_u8(serializer, &self->wait_for_run_command); - - extract_mip_filter_initialization_configuration_command_initial_condition_source(serializer, &self->initial_cond_src); - - extract_mip_filter_initialization_configuration_command_alignment_selector(serializer, &self->auto_heading_alignment_selector); - - microstrain_extract_float(serializer, &self->initial_heading); - - microstrain_extract_float(serializer, &self->initial_pitch); - - microstrain_extract_float(serializer, &self->initial_roll); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->initial_position[i]); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->initial_velocity[i]); - - extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); - -} - -void insert_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_initialization_configuration(struct mip_interface* device, uint8_t wait_for_run_command, mip_filter_initialization_configuration_command_initial_condition_source initial_cond_src, mip_filter_initialization_configuration_command_alignment_selector auto_heading_alignment_selector, float initial_heading, float initial_pitch, float initial_roll, const float* initial_position, const float* initial_velocity, mip_filter_reference_frame reference_frame_selector) +mip_cmd_result mip_filter_write_initialization_configuration(mip_interface* device, uint8_t wait_for_run_command, mip_filter_initialization_configuration_command_initial_condition_source initial_cond_src, mip_filter_initialization_configuration_command_alignment_selector auto_heading_alignment_selector, float initial_heading, float initial_pitch, float initial_roll, const float* initial_position, const float* initial_velocity, mip_filter_reference_frame reference_frame_selector) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, wait_for_run_command); insert_mip_filter_initialization_configuration_command_initial_condition_source(&serializer, initial_cond_src); insert_mip_filter_initialization_configuration_command_alignment_selector(&serializer, auto_heading_alignment_selector); - + microstrain_insert_float(&serializer, initial_heading); - + microstrain_insert_float(&serializer, initial_pitch); - + microstrain_insert_float(&serializer, initial_roll); - assert(initial_position || (3 == 0)); + assert(initial_position); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, initial_position[i]); - assert(initial_velocity || (3 == 0)); + assert(initial_velocity); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, initial_velocity[i]); @@ -4794,10 +3872,9 @@ mip_cmd_result mip_filter_write_initialization_configuration(struct mip_interfac assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface* device, uint8_t* wait_for_run_command_out, mip_filter_initialization_configuration_command_initial_condition_source* initial_cond_src_out, mip_filter_initialization_configuration_command_alignment_selector* auto_heading_alignment_selector_out, float* initial_heading_out, float* initial_pitch_out, float* initial_roll_out, float* initial_position_out, float* initial_velocity_out, mip_filter_reference_frame* reference_frame_selector_out) +mip_cmd_result mip_filter_read_initialization_configuration(mip_interface* device, uint8_t* wait_for_run_command_out, mip_filter_initialization_configuration_command_initial_condition_source* initial_cond_src_out, mip_filter_initialization_configuration_command_alignment_selector* auto_heading_alignment_selector_out, float* initial_heading_out, float* initial_pitch_out, float* initial_roll_out, float* initial_position_out, float* initial_velocity_out, mip_filter_reference_frame* reference_frame_selector_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4808,8 +3885,7 @@ mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4834,23 +3910,23 @@ mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface assert(initial_roll_out); microstrain_extract_float(&deserializer, initial_roll_out); - assert(initial_position_out || (3 == 0)); + assert(initial_position_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &initial_position_out[i]); - assert(initial_velocity_out || (3 == 0)); + assert(initial_velocity_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &initial_velocity_out[i]); assert(reference_frame_selector_out); extract_mip_filter_reference_frame(&deserializer, reference_frame_selector_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_initialization_configuration(struct mip_interface* device) +mip_cmd_result mip_filter_save_initialization_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4860,10 +3936,9 @@ mip_cmd_result mip_filter_save_initialization_configuration(struct mip_interface assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_initialization_configuration(struct mip_interface* device) +mip_cmd_result mip_filter_load_initialization_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4873,10 +3948,9 @@ mip_cmd_result mip_filter_load_initialization_configuration(struct mip_interface assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_initialization_configuration(struct mip_interface* device) +mip_cmd_result mip_filter_default_initialization_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4886,8 +3960,7 @@ mip_cmd_result mip_filter_default_initialization_configuration(struct mip_interf assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_adaptive_filter_options_command(microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_command* self) { @@ -4896,7 +3969,7 @@ void insert_mip_filter_adaptive_filter_options_command(microstrain_serializer* s if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_u8(serializer, self->level); - + microstrain_insert_u16(serializer, self->time_limit); } @@ -4908,45 +3981,29 @@ void extract_mip_filter_adaptive_filter_options_command(microstrain_serializer* if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_u8(serializer, &self->level); - + microstrain_extract_u16(serializer, &self->time_limit); } } -void insert_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_response* self) -{ - microstrain_insert_u8(serializer, self->level); - - microstrain_insert_u16(serializer, self->time_limit); - -} -void extract_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, mip_filter_adaptive_filter_options_response* self) -{ - microstrain_extract_u8(serializer, &self->level); - - microstrain_extract_u16(serializer, &self->time_limit); - -} - -mip_cmd_result mip_filter_write_adaptive_filter_options(struct mip_interface* device, uint8_t level, uint16_t time_limit) +mip_cmd_result mip_filter_write_adaptive_filter_options(mip_interface* device, uint8_t level, uint16_t time_limit) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, level); - + microstrain_insert_u16(&serializer, time_limit); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* device, uint8_t* level_out, uint16_t* time_limit_out) +mip_cmd_result mip_filter_read_adaptive_filter_options(mip_interface* device, uint8_t* level_out, uint16_t* time_limit_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4957,8 +4014,7 @@ mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* dev assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4971,12 +4027,12 @@ mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* dev assert(time_limit_out); microstrain_extract_u16(&deserializer, time_limit_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_adaptive_filter_options(struct mip_interface* device) +mip_cmd_result mip_filter_save_adaptive_filter_options(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4986,10 +4042,9 @@ mip_cmd_result mip_filter_save_adaptive_filter_options(struct mip_interface* dev assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_adaptive_filter_options(struct mip_interface* device) +mip_cmd_result mip_filter_load_adaptive_filter_options(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4999,10 +4054,9 @@ mip_cmd_result mip_filter_load_adaptive_filter_options(struct mip_interface* dev assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_adaptive_filter_options(struct mip_interface* device) +mip_cmd_result mip_filter_default_adaptive_filter_options(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5012,148 +4066,123 @@ mip_cmd_result mip_filter_default_adaptive_filter_options(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_multi_antenna_offset_command(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->receiver_id); if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->antenna_offset[i]); + insert_mip_vector3f(serializer, self->antenna_offset); } } void extract_mip_filter_multi_antenna_offset_command(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->receiver_id); if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->antenna_offset[i]); + extract_mip_vector3f(serializer, self->antenna_offset); } } -void insert_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_response* self) -{ - microstrain_insert_u8(serializer, self->receiver_id); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->antenna_offset[i]); - -} -void extract_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_response* self) -{ - microstrain_extract_u8(serializer, &self->receiver_id); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->antenna_offset[i]); - -} - -mip_cmd_result mip_filter_write_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, const float* antenna_offset) +mip_cmd_result mip_filter_write_multi_antenna_offset(mip_interface* device, uint8_t receiver_id, const float* antenna_offset) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, receiver_id); - assert(antenna_offset || (3 == 0)); + assert(antenna_offset); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, antenna_offset[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, float* antenna_offset_out) +mip_cmd_result mip_filter_read_multi_antenna_offset(mip_interface* device, uint8_t receiver_id, float* antenna_offset_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, receiver_id); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &receiver_id); - assert(antenna_offset_out || (3 == 0)); + assert(antenna_offset_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &antenna_offset_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id) +mip_cmd_result mip_filter_save_multi_antenna_offset(mip_interface* device, uint8_t receiver_id) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, receiver_id); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id) +mip_cmd_result mip_filter_load_multi_antenna_offset(mip_interface* device, uint8_t receiver_id) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, receiver_id); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id) +mip_cmd_result mip_filter_default_multi_antenna_offset(mip_interface* device, uint8_t receiver_id) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, receiver_id); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_rel_pos_configuration_command(microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_command* self) { @@ -5165,8 +4194,7 @@ void insert_mip_filter_rel_pos_configuration_command(microstrain_serializer* ser insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_double(serializer, self->reference_coordinates[i]); + insert_mip_vector3d(serializer, self->reference_coordinates); } } @@ -5180,55 +4208,32 @@ void extract_mip_filter_rel_pos_configuration_command(microstrain_serializer* se extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_double(serializer, &self->reference_coordinates[i]); + extract_mip_vector3d(serializer, self->reference_coordinates); } } -void insert_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_response* self) -{ - microstrain_insert_u8(serializer, self->source); - - insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_double(serializer, self->reference_coordinates[i]); - -} -void extract_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, mip_filter_rel_pos_configuration_response* self) -{ - microstrain_extract_u8(serializer, &self->source); - - extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_double(serializer, &self->reference_coordinates[i]); - -} - -mip_cmd_result mip_filter_write_rel_pos_configuration(struct mip_interface* device, uint8_t source, mip_filter_reference_frame reference_frame_selector, const double* reference_coordinates) +mip_cmd_result mip_filter_write_rel_pos_configuration(mip_interface* device, uint8_t source, mip_filter_reference_frame reference_frame_selector, const double* reference_coordinates) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, source); insert_mip_filter_reference_frame(&serializer, reference_frame_selector); - assert(reference_coordinates || (3 == 0)); + assert(reference_coordinates); for(unsigned int i=0; i < 3; i++) microstrain_insert_double(&serializer, reference_coordinates[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* device, uint8_t* source_out, mip_filter_reference_frame* reference_frame_selector_out, double* reference_coordinates_out) +mip_cmd_result mip_filter_read_rel_pos_configuration(mip_interface* device, uint8_t* source_out, mip_filter_reference_frame* reference_frame_selector_out, double* reference_coordinates_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5239,8 +4244,7 @@ mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_REL_POS_CONFIGURATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_REL_POS_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5253,16 +4257,16 @@ mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* devic assert(reference_frame_selector_out); extract_mip_filter_reference_frame(&deserializer, reference_frame_selector_out); - assert(reference_coordinates_out || (3 == 0)); + assert(reference_coordinates_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_double(&deserializer, &reference_coordinates_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_rel_pos_configuration(struct mip_interface* device) +mip_cmd_result mip_filter_save_rel_pos_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5272,10 +4276,9 @@ mip_cmd_result mip_filter_save_rel_pos_configuration(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_rel_pos_configuration(struct mip_interface* device) +mip_cmd_result mip_filter_load_rel_pos_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5285,10 +4288,9 @@ mip_cmd_result mip_filter_load_rel_pos_configuration(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_rel_pos_configuration(struct mip_interface* device) +mip_cmd_result mip_filter_default_rel_pos_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5298,8 +4300,7 @@ mip_cmd_result mip_filter_default_rel_pos_configuration(struct mip_interface* de assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REL_POS_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_ref_point_lever_arm_command(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command* self) { @@ -5309,8 +4310,7 @@ void insert_mip_filter_ref_point_lever_arm_command(microstrain_serializer* seria { insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, self->ref_point_sel); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->lever_arm_offset[i]); + insert_mip_vector3f(serializer, self->lever_arm_offset); } } @@ -5322,41 +4322,12 @@ void extract_mip_filter_ref_point_lever_arm_command(microstrain_serializer* seri { extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, &self->ref_point_sel); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->lever_arm_offset[i]); + extract_mip_vector3f(serializer, self->lever_arm_offset); } } -void insert_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_response* self) -{ - insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, self->ref_point_sel); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->lever_arm_offset[i]); - -} -void extract_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_response* self) -{ - extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, &self->ref_point_sel); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->lever_arm_offset[i]); - -} - -void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_filter_write_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel, const float* lever_arm_offset) +mip_cmd_result mip_filter_write_ref_point_lever_arm(mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel, const float* lever_arm_offset) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5366,16 +4337,15 @@ mip_cmd_result mip_filter_write_ref_point_lever_arm(struct mip_interface* device insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(&serializer, ref_point_sel); - assert(lever_arm_offset || (3 == 0)); + assert(lever_arm_offset); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, lever_arm_offset[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector* ref_point_sel_out, float* lever_arm_offset_out) +mip_cmd_result mip_filter_read_ref_point_lever_arm(mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector* ref_point_sel_out, float* lever_arm_offset_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5386,8 +4356,7 @@ mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5397,16 +4366,16 @@ mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, assert(ref_point_sel_out); extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(&deserializer, ref_point_sel_out); - assert(lever_arm_offset_out || (3 == 0)); + assert(lever_arm_offset_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &lever_arm_offset_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_ref_point_lever_arm(struct mip_interface* device) +mip_cmd_result mip_filter_save_ref_point_lever_arm(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5416,10 +4385,9 @@ mip_cmd_result mip_filter_save_ref_point_lever_arm(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_ref_point_lever_arm(struct mip_interface* device) +mip_cmd_result mip_filter_load_ref_point_lever_arm(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5429,10 +4397,9 @@ mip_cmd_result mip_filter_load_ref_point_lever_arm(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_ref_point_lever_arm(struct mip_interface* device) +mip_cmd_result mip_filter_default_ref_point_lever_arm(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5442,190 +4409,164 @@ mip_cmd_result mip_filter_default_ref_point_lever_arm(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_REF_POINT_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_speed_measurement_command(microstrain_serializer* serializer, const mip_filter_speed_measurement_command* self) { microstrain_insert_u8(serializer, self->source); - + microstrain_insert_float(serializer, self->time_of_week); - + microstrain_insert_float(serializer, self->speed); - + microstrain_insert_float(serializer, self->speed_uncertainty); } void extract_mip_filter_speed_measurement_command(microstrain_serializer* serializer, mip_filter_speed_measurement_command* self) { microstrain_extract_u8(serializer, &self->source); - + microstrain_extract_float(serializer, &self->time_of_week); - + microstrain_extract_float(serializer, &self->speed); - + microstrain_extract_float(serializer, &self->speed_uncertainty); } -mip_cmd_result mip_filter_speed_measurement(struct mip_interface* device, uint8_t source, float time_of_week, float speed, float speed_uncertainty) +mip_cmd_result mip_filter_speed_measurement(mip_interface* device, uint8_t source, float time_of_week, float speed, float speed_uncertainty) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_u8(&serializer, source); - + microstrain_insert_float(&serializer, time_of_week); - + microstrain_insert_float(&serializer, speed); - + microstrain_insert_float(&serializer, speed_uncertainty); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_MEASUREMENT, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_MEASUREMENT, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_speed_lever_arm_command(microstrain_serializer* serializer, const mip_filter_speed_lever_arm_command* self) { insert_mip_function_selector(serializer, self->function); - + microstrain_insert_u8(serializer, self->source); if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->lever_arm_offset[i]); + insert_mip_vector3f(serializer, self->lever_arm_offset); } } void extract_mip_filter_speed_lever_arm_command(microstrain_serializer* serializer, mip_filter_speed_lever_arm_command* self) { extract_mip_function_selector(serializer, &self->function); - + microstrain_extract_u8(serializer, &self->source); if( self->function == MIP_FUNCTION_WRITE ) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->lever_arm_offset[i]); + extract_mip_vector3f(serializer, self->lever_arm_offset); } } -void insert_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, const mip_filter_speed_lever_arm_response* self) -{ - microstrain_insert_u8(serializer, self->source); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->lever_arm_offset[i]); - -} -void extract_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, mip_filter_speed_lever_arm_response* self) -{ - microstrain_extract_u8(serializer, &self->source); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->lever_arm_offset[i]); - -} - -mip_cmd_result mip_filter_write_speed_lever_arm(struct mip_interface* device, uint8_t source, const float* lever_arm_offset) +mip_cmd_result mip_filter_write_speed_lever_arm(mip_interface* device, uint8_t source, const float* lever_arm_offset) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, source); - assert(lever_arm_offset || (3 == 0)); + assert(lever_arm_offset); for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, lever_arm_offset[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_speed_lever_arm(struct mip_interface* device, uint8_t source, float* lever_arm_offset_out) +mip_cmd_result mip_filter_read_speed_lever_arm(mip_interface* device, uint8_t source, float* lever_arm_offset_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_READ); - + microstrain_insert_u8(&serializer, source); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_FILTER_SPEED_LEVER_ARM, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_FILTER_SPEED_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - + microstrain_extract_u8(&deserializer, &source); - assert(lever_arm_offset_out || (3 == 0)); + assert(lever_arm_offset_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_float(&deserializer, &lever_arm_offset_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_speed_lever_arm(struct mip_interface* device, uint8_t source) +mip_cmd_result mip_filter_save_speed_lever_arm(mip_interface* device, uint8_t source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_SAVE); - + microstrain_insert_u8(&serializer, source); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_speed_lever_arm(struct mip_interface* device, uint8_t source) +mip_cmd_result mip_filter_load_speed_lever_arm(mip_interface* device, uint8_t source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_LOAD); - + microstrain_insert_u8(&serializer, source); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_speed_lever_arm(struct mip_interface* device, uint8_t source) +mip_cmd_result mip_filter_default_speed_lever_arm(mip_interface* device, uint8_t source) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_RESET); - + microstrain_insert_u8(&serializer, source); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SPEED_LEVER_ARM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_wheeled_vehicle_constraint_control_command(microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_command* self) { @@ -5648,33 +4589,21 @@ void extract_mip_filter_wheeled_vehicle_constraint_control_command(microstrain_s } } -void insert_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self) -{ - microstrain_insert_u8(serializer, self->enable); - -} -void extract_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self) -{ - microstrain_extract_u8(serializer, &self->enable); - -} - -mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t enable) +mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(mip_interface* device, uint8_t enable) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, enable); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t* enable_out) +mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(mip_interface* device, uint8_t* enable_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5685,8 +4614,7 @@ mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_int assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5696,12 +4624,12 @@ mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_int assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_wheeled_vehicle_constraint_control(struct mip_interface* device) +mip_cmd_result mip_filter_save_wheeled_vehicle_constraint_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5711,10 +4639,9 @@ mip_cmd_result mip_filter_save_wheeled_vehicle_constraint_control(struct mip_int assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_wheeled_vehicle_constraint_control(struct mip_interface* device) +mip_cmd_result mip_filter_load_wheeled_vehicle_constraint_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5724,10 +4651,9 @@ mip_cmd_result mip_filter_load_wheeled_vehicle_constraint_control(struct mip_int assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(struct mip_interface* device) +mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5737,8 +4663,7 @@ mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(struct mip_ assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_WHEELED_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_vertical_gyro_constraint_control_command(microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_command* self) { @@ -5761,33 +4686,21 @@ void extract_mip_filter_vertical_gyro_constraint_control_command(microstrain_ser } } -void insert_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self) -{ - microstrain_insert_u8(serializer, self->enable); - -} -void extract_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self) -{ - microstrain_extract_u8(serializer, &self->enable); - -} - -mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t enable) +mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(mip_interface* device, uint8_t enable) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, enable); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t* enable_out) +mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(mip_interface* device, uint8_t* enable_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5798,8 +4711,7 @@ mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_inter assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5809,12 +4721,12 @@ mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_inter assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_vertical_gyro_constraint_control(struct mip_interface* device) +mip_cmd_result mip_filter_save_vertical_gyro_constraint_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5824,10 +4736,9 @@ mip_cmd_result mip_filter_save_vertical_gyro_constraint_control(struct mip_inter assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_vertical_gyro_constraint_control(struct mip_interface* device) +mip_cmd_result mip_filter_load_vertical_gyro_constraint_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5837,10 +4748,9 @@ mip_cmd_result mip_filter_load_vertical_gyro_constraint_control(struct mip_inter assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(struct mip_interface* device) +mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5850,8 +4760,7 @@ mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(struct mip_in assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_VERTICAL_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_command* self) { @@ -5860,7 +4769,7 @@ void insert_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_u8(serializer, self->enable); - + microstrain_insert_float(serializer, self->max_offset); } @@ -5872,45 +4781,29 @@ void extract_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_u8(serializer, &self->enable); - + microstrain_extract_float(serializer, &self->max_offset); } } -void insert_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self) -{ - microstrain_insert_u8(serializer, self->enable); - - microstrain_insert_float(serializer, self->max_offset); - -} -void extract_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self) -{ - microstrain_extract_u8(serializer, &self->enable); - - microstrain_extract_float(serializer, &self->max_offset); - -} - -mip_cmd_result mip_filter_write_gnss_antenna_cal_control(struct mip_interface* device, uint8_t enable, float max_offset) +mip_cmd_result mip_filter_write_gnss_antenna_cal_control(mip_interface* device, uint8_t enable, float max_offset) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, enable); - + microstrain_insert_float(&serializer, max_offset); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* device, uint8_t* enable_out, float* max_offset_out) +mip_cmd_result mip_filter_read_gnss_antenna_cal_control(mip_interface* device, uint8_t* enable_out, float* max_offset_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5921,8 +4814,7 @@ mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* de assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5935,12 +4827,12 @@ mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* de assert(max_offset_out); microstrain_extract_float(&deserializer, max_offset_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_filter_save_gnss_antenna_cal_control(struct mip_interface* device) +mip_cmd_result mip_filter_save_gnss_antenna_cal_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5950,10 +4842,9 @@ mip_cmd_result mip_filter_save_gnss_antenna_cal_control(struct mip_interface* de assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_load_gnss_antenna_cal_control(struct mip_interface* device) +mip_cmd_result mip_filter_load_gnss_antenna_cal_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5963,10 +4854,9 @@ mip_cmd_result mip_filter_load_gnss_antenna_cal_control(struct mip_interface* de assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_filter_default_gnss_antenna_cal_control(struct mip_interface* device) +mip_cmd_result mip_filter_default_gnss_antenna_cal_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -5976,8 +4866,7 @@ mip_cmd_result mip_filter_default_gnss_antenna_cal_control(struct mip_interface* assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_GNSS_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_filter_set_initial_heading_command(microstrain_serializer* serializer, const mip_filter_set_initial_heading_command* self) { @@ -5990,18 +4879,17 @@ void extract_mip_filter_set_initial_heading_command(microstrain_serializer* seri } -mip_cmd_result mip_filter_set_initial_heading(struct mip_interface* device, float heading) +mip_cmd_result mip_filter_set_initial_heading(mip_interface* device, float heading) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_float(&serializer, heading); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SET_INITIAL_HEADING, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_SET_INITIAL_HEADING, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } #ifdef __cplusplus diff --git a/src/c/mip/definitions/commands_filter.h b/src/c/mip/definitions/commands_filter.h index 6b98182d1..9718f4329 100644 --- a/src/c/mip/definitions/commands_filter.h +++ b/src/c/mip/definitions/commands_filter.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,8 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipCommands_c MIP Commands [C] @@ -155,28 +154,61 @@ enum // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -typedef uint8_t mip_filter_reference_frame; -static const mip_filter_reference_frame MIP_FILTER_REFERENCE_FRAME_ECEF = 1; ///< WGS84 Earth-fixed, earth centered coordinates -static const mip_filter_reference_frame MIP_FILTER_REFERENCE_FRAME_LLH = 2; ///< WGS84 Latitude, longitude, and height above ellipsoid +enum mip_filter_reference_frame +{ + MIP_FILTER_REFERENCE_FRAME_ECEF = 1, ///< WGS84 Earth-fixed, earth centered coordinates + MIP_FILTER_REFERENCE_FRAME_LLH = 2, ///< WGS84 Latitude, longitude, and height above ellipsoid +}; +typedef enum mip_filter_reference_frame mip_filter_reference_frame; -void insert_mip_filter_reference_frame(microstrain_serializer* serializer, const mip_filter_reference_frame self); -void extract_mip_filter_reference_frame(microstrain_serializer* serializer, mip_filter_reference_frame* self); +inline void insert_mip_filter_reference_frame(microstrain_serializer* serializer, const mip_filter_reference_frame self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_reference_frame(microstrain_serializer* serializer, mip_filter_reference_frame* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} -typedef uint8_t mip_filter_mag_param_source; -static const mip_filter_mag_param_source MIP_FILTER_MAG_PARAM_SOURCE_NONE = 1; ///< No source. See command documentation for default behavior -static const mip_filter_mag_param_source MIP_FILTER_MAG_PARAM_SOURCE_WMM = 2; ///< Magnetic field is assumed to conform to the World Magnetic Model, calculated using current location estimate as an input to the model. -static const mip_filter_mag_param_source MIP_FILTER_MAG_PARAM_SOURCE_MANUAL = 3; ///< Magnetic field is assumed to have the parameter specified by the user. +enum mip_filter_mag_param_source +{ + MIP_FILTER_MAG_PARAM_SOURCE_NONE = 1, ///< No source. See command documentation for default behavior + MIP_FILTER_MAG_PARAM_SOURCE_WMM = 2, ///< Magnetic field is assumed to conform to the World Magnetic Model, calculated using current location estimate as an input to the model. + MIP_FILTER_MAG_PARAM_SOURCE_MANUAL = 3, ///< Magnetic field is assumed to have the parameter specified by the user. +}; +typedef enum mip_filter_mag_param_source mip_filter_mag_param_source; -void insert_mip_filter_mag_param_source(microstrain_serializer* serializer, const mip_filter_mag_param_source self); -void extract_mip_filter_mag_param_source(microstrain_serializer* serializer, mip_filter_mag_param_source* self); +inline void insert_mip_filter_mag_param_source(microstrain_serializer* serializer, const mip_filter_mag_param_source self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_mag_param_source(microstrain_serializer* serializer, mip_filter_mag_param_source* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} -typedef uint8_t mip_filter_adaptive_measurement; -static const mip_filter_adaptive_measurement MIP_FILTER_ADAPTIVE_MEASUREMENT_DISABLED = 0; ///< No adaptive measurement -static const mip_filter_adaptive_measurement MIP_FILTER_ADAPTIVE_MEASUREMENT_FIXED = 1; ///< Enable fixed adaptive measurement (use specified limits) -static const mip_filter_adaptive_measurement MIP_FILTER_ADAPTIVE_MEASUREMENT_AUTO = 2; ///< Enable auto adaptive measurement +enum mip_filter_adaptive_measurement +{ + MIP_FILTER_ADAPTIVE_MEASUREMENT_DISABLED = 0, ///< No adaptive measurement + MIP_FILTER_ADAPTIVE_MEASUREMENT_FIXED = 1, ///< Enable fixed adaptive measurement (use specified limits) + MIP_FILTER_ADAPTIVE_MEASUREMENT_AUTO = 2, ///< Enable auto adaptive measurement +}; +typedef enum mip_filter_adaptive_measurement mip_filter_adaptive_measurement; -void insert_mip_filter_adaptive_measurement(microstrain_serializer* serializer, const mip_filter_adaptive_measurement self); -void extract_mip_filter_adaptive_measurement(microstrain_serializer* serializer, mip_filter_adaptive_measurement* self); +inline void insert_mip_filter_adaptive_measurement(microstrain_serializer* serializer, const mip_filter_adaptive_measurement self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_adaptive_measurement(microstrain_serializer* serializer, mip_filter_adaptive_measurement* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} //////////////////////////////////////////////////////////////////////////////// @@ -192,7 +224,7 @@ void extract_mip_filter_adaptive_measurement(microstrain_serializer* serializer, /// ///@{ -mip_cmd_result mip_filter_reset(struct mip_interface* device); +mip_cmd_result mip_filter_reset(mip_interface* device); ///@} /// @@ -218,13 +250,13 @@ struct mip_filter_set_initial_attitude_command float roll; ///< [radians] float pitch; ///< [radians] float heading; ///< [radians] - }; typedef struct mip_filter_set_initial_attitude_command mip_filter_set_initial_attitude_command; + void insert_mip_filter_set_initial_attitude_command(microstrain_serializer* serializer, const mip_filter_set_initial_attitude_command* self); void extract_mip_filter_set_initial_attitude_command(microstrain_serializer* serializer, mip_filter_set_initial_attitude_command* self); -mip_cmd_result mip_filter_set_initial_attitude(struct mip_interface* device, float roll, float pitch, float heading); +mip_cmd_result mip_filter_set_initial_attitude(mip_interface* device, float roll, float pitch, float heading); ///@} /// @@ -254,34 +286,42 @@ static const mip_filter_estimation_control_command_enable_flags MIP_FILTER_ESTIM static const mip_filter_estimation_control_command_enable_flags MIP_FILTER_ESTIMATION_CONTROL_COMMAND_ENABLE_FLAGS_AUTO_MAG_HARD_IRON = 0x0020; ///< static const mip_filter_estimation_control_command_enable_flags MIP_FILTER_ESTIMATION_CONTROL_COMMAND_ENABLE_FLAGS_AUTO_MAG_SOFT_IRON = 0x0040; ///< static const mip_filter_estimation_control_command_enable_flags MIP_FILTER_ESTIMATION_CONTROL_COMMAND_ENABLE_FLAGS_ALL = 0x007F; +inline void insert_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_filter_estimation_control_command { mip_function_selector function; mip_filter_estimation_control_command_enable_flags enable; ///< See above - }; typedef struct mip_filter_estimation_control_command mip_filter_estimation_control_command; + void insert_mip_filter_estimation_control_command(microstrain_serializer* serializer, const mip_filter_estimation_control_command* self); void extract_mip_filter_estimation_control_command(microstrain_serializer* serializer, mip_filter_estimation_control_command* self); -void insert_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self); -void extract_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self); - struct mip_filter_estimation_control_response { mip_filter_estimation_control_command_enable_flags enable; ///< See above - }; typedef struct mip_filter_estimation_control_response mip_filter_estimation_control_response; + void insert_mip_filter_estimation_control_response(microstrain_serializer* serializer, const mip_filter_estimation_control_response* self); void extract_mip_filter_estimation_control_response(microstrain_serializer* serializer, mip_filter_estimation_control_response* self); -mip_cmd_result mip_filter_write_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags enable); -mip_cmd_result mip_filter_read_estimation_control(struct mip_interface* device, mip_filter_estimation_control_command_enable_flags* enable_out); -mip_cmd_result mip_filter_save_estimation_control(struct mip_interface* device); -mip_cmd_result mip_filter_load_estimation_control(struct mip_interface* device); -mip_cmd_result mip_filter_default_estimation_control(struct mip_interface* device); +mip_cmd_result mip_filter_write_estimation_control(mip_interface* device, mip_filter_estimation_control_command_enable_flags enable); +mip_cmd_result mip_filter_read_estimation_control(mip_interface* device, mip_filter_estimation_control_command_enable_flags* enable_out); +mip_cmd_result mip_filter_save_estimation_control(mip_interface* device); +mip_cmd_result mip_filter_load_estimation_control(mip_interface* device); +mip_cmd_result mip_filter_default_estimation_control(mip_interface* device); ///@} /// @@ -305,13 +345,13 @@ struct mip_filter_external_gnss_update_command mip_vector3f velocity; ///< NED Frame [meters/second] mip_vector3f pos_uncertainty; ///< NED Frame, 1-sigma [meters] mip_vector3f vel_uncertainty; ///< NED Frame, 1-sigma [meters/second] - }; typedef struct mip_filter_external_gnss_update_command mip_filter_external_gnss_update_command; + void insert_mip_filter_external_gnss_update_command(microstrain_serializer* serializer, const mip_filter_external_gnss_update_command* self); void extract_mip_filter_external_gnss_update_command(microstrain_serializer* serializer, mip_filter_external_gnss_update_command* self); -mip_cmd_result mip_filter_external_gnss_update(struct mip_interface* device, double gps_time, uint16_t gps_week, double latitude, double longitude, double height, const float* velocity, const float* pos_uncertainty, const float* vel_uncertainty); +mip_cmd_result mip_filter_external_gnss_update(mip_interface* device, double gps_time, uint16_t gps_week, double latitude, double longitude, double height, const float* velocity, const float* pos_uncertainty, const float* vel_uncertainty); ///@} /// @@ -338,13 +378,13 @@ struct mip_filter_external_heading_update_command float heading; ///< Bounded by +-PI [radians] float heading_uncertainty; ///< 1-sigma [radians] uint8_t type; ///< 1 - True, 2 - Magnetic - }; typedef struct mip_filter_external_heading_update_command mip_filter_external_heading_update_command; + void insert_mip_filter_external_heading_update_command(microstrain_serializer* serializer, const mip_filter_external_heading_update_command* self); void extract_mip_filter_external_heading_update_command(microstrain_serializer* serializer, mip_filter_external_heading_update_command* self); -mip_cmd_result mip_filter_external_heading_update(struct mip_interface* device, float heading, float heading_uncertainty, uint8_t type); +mip_cmd_result mip_filter_external_heading_update(mip_interface* device, float heading, float heading_uncertainty, uint8_t type); ///@} /// @@ -377,13 +417,13 @@ struct mip_filter_external_heading_update_with_time_command float heading; ///< Relative to true north, bounded by +-PI [radians] float heading_uncertainty; ///< 1-sigma [radians] uint8_t type; ///< 1 - True, 2 - Magnetic - }; typedef struct mip_filter_external_heading_update_with_time_command mip_filter_external_heading_update_with_time_command; + void insert_mip_filter_external_heading_update_with_time_command(microstrain_serializer* serializer, const mip_filter_external_heading_update_with_time_command* self); void extract_mip_filter_external_heading_update_with_time_command(microstrain_serializer* serializer, mip_filter_external_heading_update_with_time_command* self); -mip_cmd_result mip_filter_external_heading_update_with_time(struct mip_interface* device, double gps_time, uint16_t gps_week, float heading, float heading_uncertainty, uint8_t type); +mip_cmd_result mip_filter_external_heading_update_with_time(mip_interface* device, double gps_time, uint16_t gps_week, float heading, float heading_uncertainty, uint8_t type); ///@} /// @@ -403,34 +443,42 @@ static const mip_filter_tare_orientation_command_mip_tare_axes MIP_FILTER_TARE_O static const mip_filter_tare_orientation_command_mip_tare_axes MIP_FILTER_TARE_ORIENTATION_COMMAND_MIP_TARE_AXES_PITCH = 0x2; ///< static const mip_filter_tare_orientation_command_mip_tare_axes MIP_FILTER_TARE_ORIENTATION_COMMAND_MIP_TARE_AXES_YAW = 0x4; ///< static const mip_filter_tare_orientation_command_mip_tare_axes MIP_FILTER_TARE_ORIENTATION_COMMAND_MIP_TARE_AXES_ALL = 0x7; +inline void insert_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_filter_tare_orientation_command { mip_function_selector function; mip_filter_tare_orientation_command_mip_tare_axes axes; ///< Axes to tare - }; typedef struct mip_filter_tare_orientation_command mip_filter_tare_orientation_command; + void insert_mip_filter_tare_orientation_command(microstrain_serializer* serializer, const mip_filter_tare_orientation_command* self); void extract_mip_filter_tare_orientation_command(microstrain_serializer* serializer, mip_filter_tare_orientation_command* self); -void insert_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self); -void extract_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self); - struct mip_filter_tare_orientation_response { mip_filter_tare_orientation_command_mip_tare_axes axes; ///< Axes to tare - }; typedef struct mip_filter_tare_orientation_response mip_filter_tare_orientation_response; + void insert_mip_filter_tare_orientation_response(microstrain_serializer* serializer, const mip_filter_tare_orientation_response* self); void extract_mip_filter_tare_orientation_response(microstrain_serializer* serializer, mip_filter_tare_orientation_response* self); -mip_cmd_result mip_filter_write_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes axes); -mip_cmd_result mip_filter_read_tare_orientation(struct mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes* axes_out); -mip_cmd_result mip_filter_save_tare_orientation(struct mip_interface* device); -mip_cmd_result mip_filter_load_tare_orientation(struct mip_interface* device); -mip_cmd_result mip_filter_default_tare_orientation(struct mip_interface* device); +mip_cmd_result mip_filter_write_tare_orientation(mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes axes); +mip_cmd_result mip_filter_read_tare_orientation(mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes* axes_out); +mip_cmd_result mip_filter_save_tare_orientation(mip_interface* device); +mip_cmd_result mip_filter_load_tare_orientation(mip_interface* device); +mip_cmd_result mip_filter_default_tare_orientation(mip_interface* device); ///@} /// @@ -440,39 +488,51 @@ mip_cmd_result mip_filter_default_tare_orientation(struct mip_interface* device) /// ///@{ -typedef uint8_t mip_filter_vehicle_dynamics_mode_command_dynamics_mode; -static const mip_filter_vehicle_dynamics_mode_command_dynamics_mode MIP_FILTER_VEHICLE_DYNAMICS_MODE_COMMAND_DYNAMICS_MODE_PORTABLE = 1; ///< -static const mip_filter_vehicle_dynamics_mode_command_dynamics_mode MIP_FILTER_VEHICLE_DYNAMICS_MODE_COMMAND_DYNAMICS_MODE_AUTOMOTIVE = 2; ///< -static const mip_filter_vehicle_dynamics_mode_command_dynamics_mode MIP_FILTER_VEHICLE_DYNAMICS_MODE_COMMAND_DYNAMICS_MODE_AIRBORNE = 3; ///< -static const mip_filter_vehicle_dynamics_mode_command_dynamics_mode MIP_FILTER_VEHICLE_DYNAMICS_MODE_COMMAND_DYNAMICS_MODE_AIRBORNE_HIGH_G = 4; ///< +enum mip_filter_vehicle_dynamics_mode_command_dynamics_mode +{ + MIP_FILTER_VEHICLE_DYNAMICS_MODE_COMMAND_DYNAMICS_MODE_PORTABLE = 1, ///< + MIP_FILTER_VEHICLE_DYNAMICS_MODE_COMMAND_DYNAMICS_MODE_AUTOMOTIVE = 2, ///< + MIP_FILTER_VEHICLE_DYNAMICS_MODE_COMMAND_DYNAMICS_MODE_AIRBORNE = 3, ///< + MIP_FILTER_VEHICLE_DYNAMICS_MODE_COMMAND_DYNAMICS_MODE_AIRBORNE_HIGH_G = 4, ///< +}; +typedef enum mip_filter_vehicle_dynamics_mode_command_dynamics_mode mip_filter_vehicle_dynamics_mode_command_dynamics_mode; + +inline void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_filter_vehicle_dynamics_mode_command { mip_function_selector function; mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode; - }; typedef struct mip_filter_vehicle_dynamics_mode_command mip_filter_vehicle_dynamics_mode_command; + void insert_mip_filter_vehicle_dynamics_mode_command(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command* self); void extract_mip_filter_vehicle_dynamics_mode_command(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command* self); -void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self); -void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self); - struct mip_filter_vehicle_dynamics_mode_response { mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode; - }; typedef struct mip_filter_vehicle_dynamics_mode_response mip_filter_vehicle_dynamics_mode_response; + void insert_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_response* self); void extract_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_response* self); -mip_cmd_result mip_filter_write_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode); -mip_cmd_result mip_filter_read_vehicle_dynamics_mode(struct mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* mode_out); -mip_cmd_result mip_filter_save_vehicle_dynamics_mode(struct mip_interface* device); -mip_cmd_result mip_filter_load_vehicle_dynamics_mode(struct mip_interface* device); -mip_cmd_result mip_filter_default_vehicle_dynamics_mode(struct mip_interface* device); +mip_cmd_result mip_filter_write_vehicle_dynamics_mode(mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode); +mip_cmd_result mip_filter_read_vehicle_dynamics_mode(mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* mode_out); +mip_cmd_result mip_filter_save_vehicle_dynamics_mode(mip_interface* device); +mip_cmd_result mip_filter_load_vehicle_dynamics_mode(mip_interface* device); +mip_cmd_result mip_filter_default_vehicle_dynamics_mode(mip_interface* device); ///@} /// @@ -510,9 +570,9 @@ struct mip_filter_sensor_to_vehicle_rotation_euler_command float roll; ///< [radians] float pitch; ///< [radians] float yaw; ///< [radians] - }; typedef struct mip_filter_sensor_to_vehicle_rotation_euler_command mip_filter_sensor_to_vehicle_rotation_euler_command; + void insert_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_command* self); void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_command* self); @@ -521,17 +581,17 @@ struct mip_filter_sensor_to_vehicle_rotation_euler_response float roll; ///< [radians] float pitch; ///< [radians] float yaw; ///< [radians] - }; typedef struct mip_filter_sensor_to_vehicle_rotation_euler_response mip_filter_sensor_to_vehicle_rotation_euler_response; + void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self); void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self); -mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float roll, float pitch, float yaw); -mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(struct mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out); -mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_euler(struct mip_interface* device); -mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_euler(struct mip_interface* device); -mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(struct mip_interface* device); +mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(mip_interface* device, float roll, float pitch, float yaw); +mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_euler(mip_interface* device, float* roll_out, float* pitch_out, float* yaw_out); +mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_euler(mip_interface* device); +mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_euler(mip_interface* device); +mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(mip_interface* device); ///@} /// @@ -573,26 +633,26 @@ struct mip_filter_sensor_to_vehicle_rotation_dcm_command { mip_function_selector function; mip_matrix3f dcm; - }; typedef struct mip_filter_sensor_to_vehicle_rotation_dcm_command mip_filter_sensor_to_vehicle_rotation_dcm_command; + void insert_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_command* self); void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_command* self); struct mip_filter_sensor_to_vehicle_rotation_dcm_response { mip_matrix3f dcm; - }; typedef struct mip_filter_sensor_to_vehicle_rotation_dcm_response mip_filter_sensor_to_vehicle_rotation_dcm_response; + void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self); void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self); -mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, const float* dcm); -mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(struct mip_interface* device, float* dcm_out); -mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_dcm(struct mip_interface* device); -mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_dcm(struct mip_interface* device); -mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(struct mip_interface* device); +mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(mip_interface* device, const float* dcm); +mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_dcm(mip_interface* device, float* dcm_out); +mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_dcm(mip_interface* device); +mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_dcm(mip_interface* device); +mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(mip_interface* device); ///@} /// @@ -633,26 +693,26 @@ struct mip_filter_sensor_to_vehicle_rotation_quaternion_command { mip_function_selector function; mip_quatf quat; - }; typedef struct mip_filter_sensor_to_vehicle_rotation_quaternion_command mip_filter_sensor_to_vehicle_rotation_quaternion_command; + void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_command* self); struct mip_filter_sensor_to_vehicle_rotation_quaternion_response { mip_quatf quat; - }; typedef struct mip_filter_sensor_to_vehicle_rotation_quaternion_response mip_filter_sensor_to_vehicle_rotation_quaternion_response; + void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self); -mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, const float* quat); -mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device, float* quat_out); -mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device); -mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device); -mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(struct mip_interface* device); +mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(mip_interface* device, const float* quat); +mip_cmd_result mip_filter_read_sensor_to_vehicle_rotation_quaternion(mip_interface* device, float* quat_out); +mip_cmd_result mip_filter_save_sensor_to_vehicle_rotation_quaternion(mip_interface* device); +mip_cmd_result mip_filter_load_sensor_to_vehicle_rotation_quaternion(mip_interface* device); +mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(mip_interface* device); ///@} /// @@ -674,26 +734,26 @@ struct mip_filter_sensor_to_vehicle_offset_command { mip_function_selector function; mip_vector3f offset; ///< [meters] - }; typedef struct mip_filter_sensor_to_vehicle_offset_command mip_filter_sensor_to_vehicle_offset_command; + void insert_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_command* self); void extract_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_command* self); struct mip_filter_sensor_to_vehicle_offset_response { mip_vector3f offset; ///< [meters] - }; typedef struct mip_filter_sensor_to_vehicle_offset_response mip_filter_sensor_to_vehicle_offset_response; + void insert_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self); void extract_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self); -mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(struct mip_interface* device, const float* offset); -mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(struct mip_interface* device, float* offset_out); -mip_cmd_result mip_filter_save_sensor_to_vehicle_offset(struct mip_interface* device); -mip_cmd_result mip_filter_load_sensor_to_vehicle_offset(struct mip_interface* device); -mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(struct mip_interface* device); +mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(mip_interface* device, const float* offset); +mip_cmd_result mip_filter_read_sensor_to_vehicle_offset(mip_interface* device, float* offset_out); +mip_cmd_result mip_filter_save_sensor_to_vehicle_offset(mip_interface* device); +mip_cmd_result mip_filter_load_sensor_to_vehicle_offset(mip_interface* device); +mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(mip_interface* device); ///@} /// @@ -712,26 +772,26 @@ struct mip_filter_antenna_offset_command { mip_function_selector function; mip_vector3f offset; ///< [meters] - }; typedef struct mip_filter_antenna_offset_command mip_filter_antenna_offset_command; + void insert_mip_filter_antenna_offset_command(microstrain_serializer* serializer, const mip_filter_antenna_offset_command* self); void extract_mip_filter_antenna_offset_command(microstrain_serializer* serializer, mip_filter_antenna_offset_command* self); struct mip_filter_antenna_offset_response { mip_vector3f offset; ///< [meters] - }; typedef struct mip_filter_antenna_offset_response mip_filter_antenna_offset_response; + void insert_mip_filter_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_antenna_offset_response* self); void extract_mip_filter_antenna_offset_response(microstrain_serializer* serializer, mip_filter_antenna_offset_response* self); -mip_cmd_result mip_filter_write_antenna_offset(struct mip_interface* device, const float* offset); -mip_cmd_result mip_filter_read_antenna_offset(struct mip_interface* device, float* offset_out); -mip_cmd_result mip_filter_save_antenna_offset(struct mip_interface* device); -mip_cmd_result mip_filter_load_antenna_offset(struct mip_interface* device); -mip_cmd_result mip_filter_default_antenna_offset(struct mip_interface* device); +mip_cmd_result mip_filter_write_antenna_offset(mip_interface* device, const float* offset); +mip_cmd_result mip_filter_read_antenna_offset(mip_interface* device, float* offset_out); +mip_cmd_result mip_filter_save_antenna_offset(mip_interface* device); +mip_cmd_result mip_filter_load_antenna_offset(mip_interface* device); +mip_cmd_result mip_filter_default_antenna_offset(mip_interface* device); ///@} /// @@ -745,39 +805,51 @@ mip_cmd_result mip_filter_default_antenna_offset(struct mip_interface* device); /// ///@{ -typedef uint8_t mip_filter_gnss_source_command_source; -static const mip_filter_gnss_source_command_source MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_ALL_INT = 1; ///< All internal receivers -static const mip_filter_gnss_source_command_source MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_EXT = 2; ///< External GNSS messages provided by user -static const mip_filter_gnss_source_command_source MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_INT_1 = 3; ///< Internal GNSS Receiver 1 only -static const mip_filter_gnss_source_command_source MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_INT_2 = 4; ///< Internal GNSS Receiver 2 only +enum mip_filter_gnss_source_command_source +{ + MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_ALL_INT = 1, ///< All internal receivers + MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_EXT = 2, ///< External GNSS messages provided by user + MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_INT_1 = 3, ///< Internal GNSS Receiver 1 only + MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_INT_2 = 4, ///< Internal GNSS Receiver 2 only +}; +typedef enum mip_filter_gnss_source_command_source mip_filter_gnss_source_command_source; + +inline void insert_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_filter_gnss_source_command { mip_function_selector function; mip_filter_gnss_source_command_source source; - }; typedef struct mip_filter_gnss_source_command mip_filter_gnss_source_command; + void insert_mip_filter_gnss_source_command(microstrain_serializer* serializer, const mip_filter_gnss_source_command* self); void extract_mip_filter_gnss_source_command(microstrain_serializer* serializer, mip_filter_gnss_source_command* self); -void insert_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self); -void extract_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self); - struct mip_filter_gnss_source_response { mip_filter_gnss_source_command_source source; - }; typedef struct mip_filter_gnss_source_response mip_filter_gnss_source_response; + void insert_mip_filter_gnss_source_response(microstrain_serializer* serializer, const mip_filter_gnss_source_response* self); void extract_mip_filter_gnss_source_response(microstrain_serializer* serializer, mip_filter_gnss_source_response* self); -mip_cmd_result mip_filter_write_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source source); -mip_cmd_result mip_filter_read_gnss_source(struct mip_interface* device, mip_filter_gnss_source_command_source* source_out); -mip_cmd_result mip_filter_save_gnss_source(struct mip_interface* device); -mip_cmd_result mip_filter_load_gnss_source(struct mip_interface* device); -mip_cmd_result mip_filter_default_gnss_source(struct mip_interface* device); +mip_cmd_result mip_filter_write_gnss_source(mip_interface* device, mip_filter_gnss_source_command_source source); +mip_cmd_result mip_filter_read_gnss_source(mip_interface* device, mip_filter_gnss_source_command_source* source_out); +mip_cmd_result mip_filter_save_gnss_source(mip_interface* device); +mip_cmd_result mip_filter_load_gnss_source(mip_interface* device); +mip_cmd_result mip_filter_default_gnss_source(mip_interface* device); ///@} /// @@ -798,43 +870,55 @@ mip_cmd_result mip_filter_default_gnss_source(struct mip_interface* device); /// ///@{ -typedef uint8_t mip_filter_heading_source_command_source; -static const mip_filter_heading_source_command_source MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_NONE = 0; ///< See note 3 -static const mip_filter_heading_source_command_source MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_MAG = 1; ///< -static const mip_filter_heading_source_command_source MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_GNSS_VEL = 2; ///< See notes 1,2 -static const mip_filter_heading_source_command_source MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_EXTERNAL = 3; ///< -static const mip_filter_heading_source_command_source MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_GNSS_VEL_AND_MAG = 4; ///< -static const mip_filter_heading_source_command_source MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_GNSS_VEL_AND_EXTERNAL = 5; ///< -static const mip_filter_heading_source_command_source MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_MAG_AND_EXTERNAL = 6; ///< -static const mip_filter_heading_source_command_source MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_GNSS_VEL_AND_MAG_AND_EXTERNAL = 7; ///< +enum mip_filter_heading_source_command_source +{ + MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_NONE = 0, ///< See note 3 + MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_MAG = 1, ///< + MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_GNSS_VEL = 2, ///< See notes 1,2 + MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_EXTERNAL = 3, ///< + MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_GNSS_VEL_AND_MAG = 4, ///< + MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_GNSS_VEL_AND_EXTERNAL = 5, ///< + MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_MAG_AND_EXTERNAL = 6, ///< + MIP_FILTER_HEADING_SOURCE_COMMAND_SOURCE_GNSS_VEL_AND_MAG_AND_EXTERNAL = 7, ///< +}; +typedef enum mip_filter_heading_source_command_source mip_filter_heading_source_command_source; + +inline void insert_mip_filter_heading_source_command_source(microstrain_serializer* serializer, const mip_filter_heading_source_command_source self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_heading_source_command_source(microstrain_serializer* serializer, mip_filter_heading_source_command_source* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_filter_heading_source_command { mip_function_selector function; mip_filter_heading_source_command_source source; - }; typedef struct mip_filter_heading_source_command mip_filter_heading_source_command; + void insert_mip_filter_heading_source_command(microstrain_serializer* serializer, const mip_filter_heading_source_command* self); void extract_mip_filter_heading_source_command(microstrain_serializer* serializer, mip_filter_heading_source_command* self); -void insert_mip_filter_heading_source_command_source(microstrain_serializer* serializer, const mip_filter_heading_source_command_source self); -void extract_mip_filter_heading_source_command_source(microstrain_serializer* serializer, mip_filter_heading_source_command_source* self); - struct mip_filter_heading_source_response { mip_filter_heading_source_command_source source; - }; typedef struct mip_filter_heading_source_response mip_filter_heading_source_response; + void insert_mip_filter_heading_source_response(microstrain_serializer* serializer, const mip_filter_heading_source_response* self); void extract_mip_filter_heading_source_response(microstrain_serializer* serializer, mip_filter_heading_source_response* self); -mip_cmd_result mip_filter_write_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source source); -mip_cmd_result mip_filter_read_heading_source(struct mip_interface* device, mip_filter_heading_source_command_source* source_out); -mip_cmd_result mip_filter_save_heading_source(struct mip_interface* device); -mip_cmd_result mip_filter_load_heading_source(struct mip_interface* device); -mip_cmd_result mip_filter_default_heading_source(struct mip_interface* device); +mip_cmd_result mip_filter_write_heading_source(mip_interface* device, mip_filter_heading_source_command_source source); +mip_cmd_result mip_filter_read_heading_source(mip_interface* device, mip_filter_heading_source_command_source* source_out); +mip_cmd_result mip_filter_save_heading_source(mip_interface* device); +mip_cmd_result mip_filter_load_heading_source(mip_interface* device); +mip_cmd_result mip_filter_default_heading_source(mip_interface* device); ///@} /// @@ -856,26 +940,26 @@ struct mip_filter_auto_init_control_command { mip_function_selector function; uint8_t enable; ///< See above - }; typedef struct mip_filter_auto_init_control_command mip_filter_auto_init_control_command; + void insert_mip_filter_auto_init_control_command(microstrain_serializer* serializer, const mip_filter_auto_init_control_command* self); void extract_mip_filter_auto_init_control_command(microstrain_serializer* serializer, mip_filter_auto_init_control_command* self); struct mip_filter_auto_init_control_response { uint8_t enable; ///< See above - }; typedef struct mip_filter_auto_init_control_response mip_filter_auto_init_control_response; + void insert_mip_filter_auto_init_control_response(microstrain_serializer* serializer, const mip_filter_auto_init_control_response* self); void extract_mip_filter_auto_init_control_response(microstrain_serializer* serializer, mip_filter_auto_init_control_response* self); -mip_cmd_result mip_filter_write_auto_init_control(struct mip_interface* device, uint8_t enable); -mip_cmd_result mip_filter_read_auto_init_control(struct mip_interface* device, uint8_t* enable_out); -mip_cmd_result mip_filter_save_auto_init_control(struct mip_interface* device); -mip_cmd_result mip_filter_load_auto_init_control(struct mip_interface* device); -mip_cmd_result mip_filter_default_auto_init_control(struct mip_interface* device); +mip_cmd_result mip_filter_write_auto_init_control(mip_interface* device, uint8_t enable); +mip_cmd_result mip_filter_read_auto_init_control(mip_interface* device, uint8_t* enable_out); +mip_cmd_result mip_filter_save_auto_init_control(mip_interface* device); +mip_cmd_result mip_filter_load_auto_init_control(mip_interface* device); +mip_cmd_result mip_filter_default_auto_init_control(mip_interface* device); ///@} /// @@ -895,26 +979,26 @@ struct mip_filter_accel_noise_command { mip_function_selector function; mip_vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] - }; typedef struct mip_filter_accel_noise_command mip_filter_accel_noise_command; + void insert_mip_filter_accel_noise_command(microstrain_serializer* serializer, const mip_filter_accel_noise_command* self); void extract_mip_filter_accel_noise_command(microstrain_serializer* serializer, mip_filter_accel_noise_command* self); struct mip_filter_accel_noise_response { mip_vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] - }; typedef struct mip_filter_accel_noise_response mip_filter_accel_noise_response; + void insert_mip_filter_accel_noise_response(microstrain_serializer* serializer, const mip_filter_accel_noise_response* self); void extract_mip_filter_accel_noise_response(microstrain_serializer* serializer, mip_filter_accel_noise_response* self); -mip_cmd_result mip_filter_write_accel_noise(struct mip_interface* device, const float* noise); -mip_cmd_result mip_filter_read_accel_noise(struct mip_interface* device, float* noise_out); -mip_cmd_result mip_filter_save_accel_noise(struct mip_interface* device); -mip_cmd_result mip_filter_load_accel_noise(struct mip_interface* device); -mip_cmd_result mip_filter_default_accel_noise(struct mip_interface* device); +mip_cmd_result mip_filter_write_accel_noise(mip_interface* device, const float* noise); +mip_cmd_result mip_filter_read_accel_noise(mip_interface* device, float* noise_out); +mip_cmd_result mip_filter_save_accel_noise(mip_interface* device); +mip_cmd_result mip_filter_load_accel_noise(mip_interface* device); +mip_cmd_result mip_filter_default_accel_noise(mip_interface* device); ///@} /// @@ -934,26 +1018,26 @@ struct mip_filter_gyro_noise_command { mip_function_selector function; mip_vector3f noise; ///< Gyro Noise 1-sigma [rad/second] - }; typedef struct mip_filter_gyro_noise_command mip_filter_gyro_noise_command; + void insert_mip_filter_gyro_noise_command(microstrain_serializer* serializer, const mip_filter_gyro_noise_command* self); void extract_mip_filter_gyro_noise_command(microstrain_serializer* serializer, mip_filter_gyro_noise_command* self); struct mip_filter_gyro_noise_response { mip_vector3f noise; ///< Gyro Noise 1-sigma [rad/second] - }; typedef struct mip_filter_gyro_noise_response mip_filter_gyro_noise_response; + void insert_mip_filter_gyro_noise_response(microstrain_serializer* serializer, const mip_filter_gyro_noise_response* self); void extract_mip_filter_gyro_noise_response(microstrain_serializer* serializer, mip_filter_gyro_noise_response* self); -mip_cmd_result mip_filter_write_gyro_noise(struct mip_interface* device, const float* noise); -mip_cmd_result mip_filter_read_gyro_noise(struct mip_interface* device, float* noise_out); -mip_cmd_result mip_filter_save_gyro_noise(struct mip_interface* device); -mip_cmd_result mip_filter_load_gyro_noise(struct mip_interface* device); -mip_cmd_result mip_filter_default_gyro_noise(struct mip_interface* device); +mip_cmd_result mip_filter_write_gyro_noise(mip_interface* device, const float* noise); +mip_cmd_result mip_filter_read_gyro_noise(mip_interface* device, float* noise_out); +mip_cmd_result mip_filter_save_gyro_noise(mip_interface* device); +mip_cmd_result mip_filter_load_gyro_noise(mip_interface* device); +mip_cmd_result mip_filter_default_gyro_noise(mip_interface* device); ///@} /// @@ -971,9 +1055,9 @@ struct mip_filter_accel_bias_model_command mip_function_selector function; mip_vector3f beta; ///< Accel Bias Beta [1/second] mip_vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] - }; typedef struct mip_filter_accel_bias_model_command mip_filter_accel_bias_model_command; + void insert_mip_filter_accel_bias_model_command(microstrain_serializer* serializer, const mip_filter_accel_bias_model_command* self); void extract_mip_filter_accel_bias_model_command(microstrain_serializer* serializer, mip_filter_accel_bias_model_command* self); @@ -981,17 +1065,17 @@ struct mip_filter_accel_bias_model_response { mip_vector3f beta; ///< Accel Bias Beta [1/second] mip_vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] - }; typedef struct mip_filter_accel_bias_model_response mip_filter_accel_bias_model_response; + void insert_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, const mip_filter_accel_bias_model_response* self); void extract_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, mip_filter_accel_bias_model_response* self); -mip_cmd_result mip_filter_write_accel_bias_model(struct mip_interface* device, const float* beta, const float* noise); -mip_cmd_result mip_filter_read_accel_bias_model(struct mip_interface* device, float* beta_out, float* noise_out); -mip_cmd_result mip_filter_save_accel_bias_model(struct mip_interface* device); -mip_cmd_result mip_filter_load_accel_bias_model(struct mip_interface* device); -mip_cmd_result mip_filter_default_accel_bias_model(struct mip_interface* device); +mip_cmd_result mip_filter_write_accel_bias_model(mip_interface* device, const float* beta, const float* noise); +mip_cmd_result mip_filter_read_accel_bias_model(mip_interface* device, float* beta_out, float* noise_out); +mip_cmd_result mip_filter_save_accel_bias_model(mip_interface* device); +mip_cmd_result mip_filter_load_accel_bias_model(mip_interface* device); +mip_cmd_result mip_filter_default_accel_bias_model(mip_interface* device); ///@} /// @@ -1009,9 +1093,9 @@ struct mip_filter_gyro_bias_model_command mip_function_selector function; mip_vector3f beta; ///< Gyro Bias Beta [1/second] mip_vector3f noise; ///< Gyro Noise 1-sigma [rad/second] - }; typedef struct mip_filter_gyro_bias_model_command mip_filter_gyro_bias_model_command; + void insert_mip_filter_gyro_bias_model_command(microstrain_serializer* serializer, const mip_filter_gyro_bias_model_command* self); void extract_mip_filter_gyro_bias_model_command(microstrain_serializer* serializer, mip_filter_gyro_bias_model_command* self); @@ -1019,17 +1103,17 @@ struct mip_filter_gyro_bias_model_response { mip_vector3f beta; ///< Gyro Bias Beta [1/second] mip_vector3f noise; ///< Gyro Noise 1-sigma [rad/second] - }; typedef struct mip_filter_gyro_bias_model_response mip_filter_gyro_bias_model_response; + void insert_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, const mip_filter_gyro_bias_model_response* self); void extract_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, mip_filter_gyro_bias_model_response* self); -mip_cmd_result mip_filter_write_gyro_bias_model(struct mip_interface* device, const float* beta, const float* noise); -mip_cmd_result mip_filter_read_gyro_bias_model(struct mip_interface* device, float* beta_out, float* noise_out); -mip_cmd_result mip_filter_save_gyro_bias_model(struct mip_interface* device); -mip_cmd_result mip_filter_load_gyro_bias_model(struct mip_interface* device); -mip_cmd_result mip_filter_default_gyro_bias_model(struct mip_interface* device); +mip_cmd_result mip_filter_write_gyro_bias_model(mip_interface* device, const float* beta, const float* noise); +mip_cmd_result mip_filter_read_gyro_bias_model(mip_interface* device, float* beta_out, float* noise_out); +mip_cmd_result mip_filter_save_gyro_bias_model(mip_interface* device); +mip_cmd_result mip_filter_load_gyro_bias_model(mip_interface* device); +mip_cmd_result mip_filter_default_gyro_bias_model(mip_interface* device); ///@} /// @@ -1043,37 +1127,49 @@ mip_cmd_result mip_filter_default_gyro_bias_model(struct mip_interface* device); /// ///@{ -typedef uint8_t mip_filter_altitude_aiding_command_aiding_selector; -static const mip_filter_altitude_aiding_command_aiding_selector MIP_FILTER_ALTITUDE_AIDING_COMMAND_AIDING_SELECTOR_NONE = 0; ///< No altitude aiding -static const mip_filter_altitude_aiding_command_aiding_selector MIP_FILTER_ALTITUDE_AIDING_COMMAND_AIDING_SELECTOR_PRESURE = 1; ///< Enable pressure sensor aiding +enum mip_filter_altitude_aiding_command_aiding_selector +{ + MIP_FILTER_ALTITUDE_AIDING_COMMAND_AIDING_SELECTOR_NONE = 0, ///< No altitude aiding + MIP_FILTER_ALTITUDE_AIDING_COMMAND_AIDING_SELECTOR_PRESURE = 1, ///< Enable pressure sensor aiding +}; +typedef enum mip_filter_altitude_aiding_command_aiding_selector mip_filter_altitude_aiding_command_aiding_selector; + +inline void insert_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_filter_altitude_aiding_command { mip_function_selector function; mip_filter_altitude_aiding_command_aiding_selector selector; ///< See above - }; typedef struct mip_filter_altitude_aiding_command mip_filter_altitude_aiding_command; + void insert_mip_filter_altitude_aiding_command(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command* self); void extract_mip_filter_altitude_aiding_command(microstrain_serializer* serializer, mip_filter_altitude_aiding_command* self); -void insert_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self); -void extract_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self); - struct mip_filter_altitude_aiding_response { mip_filter_altitude_aiding_command_aiding_selector selector; ///< See above - }; typedef struct mip_filter_altitude_aiding_response mip_filter_altitude_aiding_response; + void insert_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, const mip_filter_altitude_aiding_response* self); void extract_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, mip_filter_altitude_aiding_response* self); -mip_cmd_result mip_filter_write_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector selector); -mip_cmd_result mip_filter_read_altitude_aiding(struct mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector* selector_out); -mip_cmd_result mip_filter_save_altitude_aiding(struct mip_interface* device); -mip_cmd_result mip_filter_load_altitude_aiding(struct mip_interface* device); -mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device); +mip_cmd_result mip_filter_write_altitude_aiding(mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector selector); +mip_cmd_result mip_filter_read_altitude_aiding(mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector* selector_out); +mip_cmd_result mip_filter_save_altitude_aiding(mip_interface* device); +mip_cmd_result mip_filter_load_altitude_aiding(mip_interface* device); +mip_cmd_result mip_filter_default_altitude_aiding(mip_interface* device); ///@} /// @@ -1084,37 +1180,49 @@ mip_cmd_result mip_filter_default_altitude_aiding(struct mip_interface* device); /// ///@{ -typedef uint8_t mip_filter_pitch_roll_aiding_command_aiding_source; -static const mip_filter_pitch_roll_aiding_command_aiding_source MIP_FILTER_PITCH_ROLL_AIDING_COMMAND_AIDING_SOURCE_NONE = 0; ///< No pitch/roll aiding -static const mip_filter_pitch_roll_aiding_command_aiding_source MIP_FILTER_PITCH_ROLL_AIDING_COMMAND_AIDING_SOURCE_GRAVITY_VEC = 1; ///< Enable gravity vector aiding +enum mip_filter_pitch_roll_aiding_command_aiding_source +{ + MIP_FILTER_PITCH_ROLL_AIDING_COMMAND_AIDING_SOURCE_NONE = 0, ///< No pitch/roll aiding + MIP_FILTER_PITCH_ROLL_AIDING_COMMAND_AIDING_SOURCE_GRAVITY_VEC = 1, ///< Enable gravity vector aiding +}; +typedef enum mip_filter_pitch_roll_aiding_command_aiding_source mip_filter_pitch_roll_aiding_command_aiding_source; + +inline void insert_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_filter_pitch_roll_aiding_command { mip_function_selector function; mip_filter_pitch_roll_aiding_command_aiding_source source; ///< Controls the aiding source - }; typedef struct mip_filter_pitch_roll_aiding_command mip_filter_pitch_roll_aiding_command; + void insert_mip_filter_pitch_roll_aiding_command(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command* self); void extract_mip_filter_pitch_roll_aiding_command(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command* self); -void insert_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self); -void extract_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self); - struct mip_filter_pitch_roll_aiding_response { mip_filter_pitch_roll_aiding_command_aiding_source source; ///< Controls the aiding source - }; typedef struct mip_filter_pitch_roll_aiding_response mip_filter_pitch_roll_aiding_response; + void insert_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_response* self); void extract_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_response* self); -mip_cmd_result mip_filter_write_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source source); -mip_cmd_result mip_filter_read_pitch_roll_aiding(struct mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source* source_out); -mip_cmd_result mip_filter_save_pitch_roll_aiding(struct mip_interface* device); -mip_cmd_result mip_filter_load_pitch_roll_aiding(struct mip_interface* device); -mip_cmd_result mip_filter_default_pitch_roll_aiding(struct mip_interface* device); +mip_cmd_result mip_filter_write_pitch_roll_aiding(mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source source); +mip_cmd_result mip_filter_read_pitch_roll_aiding(mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source* source_out); +mip_cmd_result mip_filter_save_pitch_roll_aiding(mip_interface* device); +mip_cmd_result mip_filter_load_pitch_roll_aiding(mip_interface* device); +mip_cmd_result mip_filter_default_pitch_roll_aiding(mip_interface* device); ///@} /// @@ -1130,9 +1238,9 @@ struct mip_filter_auto_zupt_command mip_function_selector function; uint8_t enable; ///< 0 - Disable, 1 - Enable float threshold; ///< [meters/second] - }; typedef struct mip_filter_auto_zupt_command mip_filter_auto_zupt_command; + void insert_mip_filter_auto_zupt_command(microstrain_serializer* serializer, const mip_filter_auto_zupt_command* self); void extract_mip_filter_auto_zupt_command(microstrain_serializer* serializer, mip_filter_auto_zupt_command* self); @@ -1140,17 +1248,17 @@ struct mip_filter_auto_zupt_response { uint8_t enable; ///< 0 - Disable, 1 - Enable float threshold; ///< [meters/second] - }; typedef struct mip_filter_auto_zupt_response mip_filter_auto_zupt_response; + void insert_mip_filter_auto_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_zupt_response* self); void extract_mip_filter_auto_zupt_response(microstrain_serializer* serializer, mip_filter_auto_zupt_response* self); -mip_cmd_result mip_filter_write_auto_zupt(struct mip_interface* device, uint8_t enable, float threshold); -mip_cmd_result mip_filter_read_auto_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out); -mip_cmd_result mip_filter_save_auto_zupt(struct mip_interface* device); -mip_cmd_result mip_filter_load_auto_zupt(struct mip_interface* device); -mip_cmd_result mip_filter_default_auto_zupt(struct mip_interface* device); +mip_cmd_result mip_filter_write_auto_zupt(mip_interface* device, uint8_t enable, float threshold); +mip_cmd_result mip_filter_read_auto_zupt(mip_interface* device, uint8_t* enable_out, float* threshold_out); +mip_cmd_result mip_filter_save_auto_zupt(mip_interface* device); +mip_cmd_result mip_filter_load_auto_zupt(mip_interface* device); +mip_cmd_result mip_filter_default_auto_zupt(mip_interface* device); ///@} /// @@ -1167,9 +1275,9 @@ struct mip_filter_auto_angular_zupt_command mip_function_selector function; uint8_t enable; ///< 0 - Disable, 1 - Enable float threshold; ///< [radians/second] - }; typedef struct mip_filter_auto_angular_zupt_command mip_filter_auto_angular_zupt_command; + void insert_mip_filter_auto_angular_zupt_command(microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_command* self); void extract_mip_filter_auto_angular_zupt_command(microstrain_serializer* serializer, mip_filter_auto_angular_zupt_command* self); @@ -1177,17 +1285,17 @@ struct mip_filter_auto_angular_zupt_response { uint8_t enable; ///< 0 - Disable, 1 - Enable float threshold; ///< [radians/second] - }; typedef struct mip_filter_auto_angular_zupt_response mip_filter_auto_angular_zupt_response; + void insert_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_response* self); void extract_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, mip_filter_auto_angular_zupt_response* self); -mip_cmd_result mip_filter_write_auto_angular_zupt(struct mip_interface* device, uint8_t enable, float threshold); -mip_cmd_result mip_filter_read_auto_angular_zupt(struct mip_interface* device, uint8_t* enable_out, float* threshold_out); -mip_cmd_result mip_filter_save_auto_angular_zupt(struct mip_interface* device); -mip_cmd_result mip_filter_load_auto_angular_zupt(struct mip_interface* device); -mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device); +mip_cmd_result mip_filter_write_auto_angular_zupt(mip_interface* device, uint8_t enable, float threshold); +mip_cmd_result mip_filter_read_auto_angular_zupt(mip_interface* device, uint8_t* enable_out, float* threshold_out); +mip_cmd_result mip_filter_save_auto_angular_zupt(mip_interface* device); +mip_cmd_result mip_filter_load_auto_angular_zupt(mip_interface* device); +mip_cmd_result mip_filter_default_auto_angular_zupt(mip_interface* device); ///@} /// @@ -1197,7 +1305,7 @@ mip_cmd_result mip_filter_default_auto_angular_zupt(struct mip_interface* device /// ///@{ -mip_cmd_result mip_filter_commanded_zupt(struct mip_interface* device); +mip_cmd_result mip_filter_commanded_zupt(mip_interface* device); ///@} /// @@ -1207,7 +1315,7 @@ mip_cmd_result mip_filter_commanded_zupt(struct mip_interface* device); /// ///@{ -mip_cmd_result mip_filter_commanded_angular_zupt(struct mip_interface* device); +mip_cmd_result mip_filter_commanded_angular_zupt(mip_interface* device); ///@} /// @@ -1222,14 +1330,14 @@ mip_cmd_result mip_filter_commanded_angular_zupt(struct mip_interface* device); struct mip_filter_mag_capture_auto_cal_command { mip_function_selector function; - }; typedef struct mip_filter_mag_capture_auto_cal_command mip_filter_mag_capture_auto_cal_command; + void insert_mip_filter_mag_capture_auto_cal_command(microstrain_serializer* serializer, const mip_filter_mag_capture_auto_cal_command* self); void extract_mip_filter_mag_capture_auto_cal_command(microstrain_serializer* serializer, mip_filter_mag_capture_auto_cal_command* self); -mip_cmd_result mip_filter_write_mag_capture_auto_cal(struct mip_interface* device); -mip_cmd_result mip_filter_save_mag_capture_auto_cal(struct mip_interface* device); +mip_cmd_result mip_filter_write_mag_capture_auto_cal(mip_interface* device); +mip_cmd_result mip_filter_save_mag_capture_auto_cal(mip_interface* device); ///@} /// @@ -1248,26 +1356,26 @@ struct mip_filter_gravity_noise_command { mip_function_selector function; mip_vector3f noise; ///< Gravity Noise 1-sigma [gauss] - }; typedef struct mip_filter_gravity_noise_command mip_filter_gravity_noise_command; + void insert_mip_filter_gravity_noise_command(microstrain_serializer* serializer, const mip_filter_gravity_noise_command* self); void extract_mip_filter_gravity_noise_command(microstrain_serializer* serializer, mip_filter_gravity_noise_command* self); struct mip_filter_gravity_noise_response { mip_vector3f noise; ///< Gravity Noise 1-sigma [gauss] - }; typedef struct mip_filter_gravity_noise_response mip_filter_gravity_noise_response; + void insert_mip_filter_gravity_noise_response(microstrain_serializer* serializer, const mip_filter_gravity_noise_response* self); void extract_mip_filter_gravity_noise_response(microstrain_serializer* serializer, mip_filter_gravity_noise_response* self); -mip_cmd_result mip_filter_write_gravity_noise(struct mip_interface* device, const float* noise); -mip_cmd_result mip_filter_read_gravity_noise(struct mip_interface* device, float* noise_out); -mip_cmd_result mip_filter_save_gravity_noise(struct mip_interface* device); -mip_cmd_result mip_filter_load_gravity_noise(struct mip_interface* device); -mip_cmd_result mip_filter_default_gravity_noise(struct mip_interface* device); +mip_cmd_result mip_filter_write_gravity_noise(mip_interface* device, const float* noise); +mip_cmd_result mip_filter_read_gravity_noise(mip_interface* device, float* noise_out); +mip_cmd_result mip_filter_save_gravity_noise(mip_interface* device); +mip_cmd_result mip_filter_load_gravity_noise(mip_interface* device); +mip_cmd_result mip_filter_default_gravity_noise(mip_interface* device); ///@} /// @@ -1286,26 +1394,26 @@ struct mip_filter_pressure_altitude_noise_command { mip_function_selector function; float noise; ///< Pressure Altitude Noise 1-sigma [m] - }; typedef struct mip_filter_pressure_altitude_noise_command mip_filter_pressure_altitude_noise_command; + void insert_mip_filter_pressure_altitude_noise_command(microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_command* self); void extract_mip_filter_pressure_altitude_noise_command(microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_command* self); struct mip_filter_pressure_altitude_noise_response { float noise; ///< Pressure Altitude Noise 1-sigma [m] - }; typedef struct mip_filter_pressure_altitude_noise_response mip_filter_pressure_altitude_noise_response; + void insert_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self); void extract_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_response* self); -mip_cmd_result mip_filter_write_pressure_altitude_noise(struct mip_interface* device, float noise); -mip_cmd_result mip_filter_read_pressure_altitude_noise(struct mip_interface* device, float* noise_out); -mip_cmd_result mip_filter_save_pressure_altitude_noise(struct mip_interface* device); -mip_cmd_result mip_filter_load_pressure_altitude_noise(struct mip_interface* device); -mip_cmd_result mip_filter_default_pressure_altitude_noise(struct mip_interface* device); +mip_cmd_result mip_filter_write_pressure_altitude_noise(mip_interface* device, float noise); +mip_cmd_result mip_filter_read_pressure_altitude_noise(mip_interface* device, float* noise_out); +mip_cmd_result mip_filter_save_pressure_altitude_noise(mip_interface* device); +mip_cmd_result mip_filter_load_pressure_altitude_noise(mip_interface* device); +mip_cmd_result mip_filter_default_pressure_altitude_noise(mip_interface* device); ///@} /// @@ -1326,26 +1434,26 @@ struct mip_filter_hard_iron_offset_noise_command { mip_function_selector function; mip_vector3f noise; ///< Hard Iron Offset Noise 1-sigma [gauss] - }; typedef struct mip_filter_hard_iron_offset_noise_command mip_filter_hard_iron_offset_noise_command; + void insert_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_command* self); void extract_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_command* self); struct mip_filter_hard_iron_offset_noise_response { mip_vector3f noise; ///< Hard Iron Offset Noise 1-sigma [gauss] - }; typedef struct mip_filter_hard_iron_offset_noise_response mip_filter_hard_iron_offset_noise_response; + void insert_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self); void extract_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self); -mip_cmd_result mip_filter_write_hard_iron_offset_noise(struct mip_interface* device, const float* noise); -mip_cmd_result mip_filter_read_hard_iron_offset_noise(struct mip_interface* device, float* noise_out); -mip_cmd_result mip_filter_save_hard_iron_offset_noise(struct mip_interface* device); -mip_cmd_result mip_filter_load_hard_iron_offset_noise(struct mip_interface* device); -mip_cmd_result mip_filter_default_hard_iron_offset_noise(struct mip_interface* device); +mip_cmd_result mip_filter_write_hard_iron_offset_noise(mip_interface* device, const float* noise); +mip_cmd_result mip_filter_read_hard_iron_offset_noise(mip_interface* device, float* noise_out); +mip_cmd_result mip_filter_save_hard_iron_offset_noise(mip_interface* device); +mip_cmd_result mip_filter_load_hard_iron_offset_noise(mip_interface* device); +mip_cmd_result mip_filter_default_hard_iron_offset_noise(mip_interface* device); ///@} /// @@ -1365,26 +1473,26 @@ struct mip_filter_soft_iron_matrix_noise_command { mip_function_selector function; mip_matrix3f noise; ///< Soft Iron Matrix Noise 1-sigma [dimensionless] - }; typedef struct mip_filter_soft_iron_matrix_noise_command mip_filter_soft_iron_matrix_noise_command; + void insert_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_command* self); void extract_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_command* self); struct mip_filter_soft_iron_matrix_noise_response { mip_matrix3f noise; ///< Soft Iron Matrix Noise 1-sigma [dimensionless] - }; typedef struct mip_filter_soft_iron_matrix_noise_response mip_filter_soft_iron_matrix_noise_response; + void insert_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self); void extract_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self); -mip_cmd_result mip_filter_write_soft_iron_matrix_noise(struct mip_interface* device, const float* noise); -mip_cmd_result mip_filter_read_soft_iron_matrix_noise(struct mip_interface* device, float* noise_out); -mip_cmd_result mip_filter_save_soft_iron_matrix_noise(struct mip_interface* device); -mip_cmd_result mip_filter_load_soft_iron_matrix_noise(struct mip_interface* device); -mip_cmd_result mip_filter_default_soft_iron_matrix_noise(struct mip_interface* device); +mip_cmd_result mip_filter_write_soft_iron_matrix_noise(mip_interface* device, const float* noise); +mip_cmd_result mip_filter_read_soft_iron_matrix_noise(mip_interface* device, float* noise_out); +mip_cmd_result mip_filter_save_soft_iron_matrix_noise(mip_interface* device); +mip_cmd_result mip_filter_load_soft_iron_matrix_noise(mip_interface* device); +mip_cmd_result mip_filter_default_soft_iron_matrix_noise(mip_interface* device); ///@} /// @@ -1404,26 +1512,26 @@ struct mip_filter_mag_noise_command { mip_function_selector function; mip_vector3f noise; ///< Mag Noise 1-sigma [gauss] - }; typedef struct mip_filter_mag_noise_command mip_filter_mag_noise_command; + void insert_mip_filter_mag_noise_command(microstrain_serializer* serializer, const mip_filter_mag_noise_command* self); void extract_mip_filter_mag_noise_command(microstrain_serializer* serializer, mip_filter_mag_noise_command* self); struct mip_filter_mag_noise_response { mip_vector3f noise; ///< Mag Noise 1-sigma [gauss] - }; typedef struct mip_filter_mag_noise_response mip_filter_mag_noise_response; + void insert_mip_filter_mag_noise_response(microstrain_serializer* serializer, const mip_filter_mag_noise_response* self); void extract_mip_filter_mag_noise_response(microstrain_serializer* serializer, mip_filter_mag_noise_response* self); -mip_cmd_result mip_filter_write_mag_noise(struct mip_interface* device, const float* noise); -mip_cmd_result mip_filter_read_mag_noise(struct mip_interface* device, float* noise_out); -mip_cmd_result mip_filter_save_mag_noise(struct mip_interface* device); -mip_cmd_result mip_filter_load_mag_noise(struct mip_interface* device); -mip_cmd_result mip_filter_default_mag_noise(struct mip_interface* device); +mip_cmd_result mip_filter_write_mag_noise(mip_interface* device, const float* noise); +mip_cmd_result mip_filter_read_mag_noise(mip_interface* device, float* noise_out); +mip_cmd_result mip_filter_save_mag_noise(mip_interface* device); +mip_cmd_result mip_filter_load_mag_noise(mip_interface* device); +mip_cmd_result mip_filter_default_mag_noise(mip_interface* device); ///@} /// @@ -1442,9 +1550,9 @@ struct mip_filter_inclination_source_command mip_function_selector function; mip_filter_mag_param_source source; ///< Inclination Source float inclination; ///< Inclination angle [radians] (only required if source = MANUAL) - }; typedef struct mip_filter_inclination_source_command mip_filter_inclination_source_command; + void insert_mip_filter_inclination_source_command(microstrain_serializer* serializer, const mip_filter_inclination_source_command* self); void extract_mip_filter_inclination_source_command(microstrain_serializer* serializer, mip_filter_inclination_source_command* self); @@ -1452,17 +1560,17 @@ struct mip_filter_inclination_source_response { mip_filter_mag_param_source source; ///< Inclination Source float inclination; ///< Inclination angle [radians] (only required if source = MANUAL) - }; typedef struct mip_filter_inclination_source_response mip_filter_inclination_source_response; + void insert_mip_filter_inclination_source_response(microstrain_serializer* serializer, const mip_filter_inclination_source_response* self); void extract_mip_filter_inclination_source_response(microstrain_serializer* serializer, mip_filter_inclination_source_response* self); -mip_cmd_result mip_filter_write_inclination_source(struct mip_interface* device, mip_filter_mag_param_source source, float inclination); -mip_cmd_result mip_filter_read_inclination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* inclination_out); -mip_cmd_result mip_filter_save_inclination_source(struct mip_interface* device); -mip_cmd_result mip_filter_load_inclination_source(struct mip_interface* device); -mip_cmd_result mip_filter_default_inclination_source(struct mip_interface* device); +mip_cmd_result mip_filter_write_inclination_source(mip_interface* device, mip_filter_mag_param_source source, float inclination); +mip_cmd_result mip_filter_read_inclination_source(mip_interface* device, mip_filter_mag_param_source* source_out, float* inclination_out); +mip_cmd_result mip_filter_save_inclination_source(mip_interface* device); +mip_cmd_result mip_filter_load_inclination_source(mip_interface* device); +mip_cmd_result mip_filter_default_inclination_source(mip_interface* device); ///@} /// @@ -1481,9 +1589,9 @@ struct mip_filter_magnetic_declination_source_command mip_function_selector function; mip_filter_mag_param_source source; ///< Magnetic field declination angle source float declination; ///< Declination angle [radians] (only required if source = MANUAL) - }; typedef struct mip_filter_magnetic_declination_source_command mip_filter_magnetic_declination_source_command; + void insert_mip_filter_magnetic_declination_source_command(microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_command* self); void extract_mip_filter_magnetic_declination_source_command(microstrain_serializer* serializer, mip_filter_magnetic_declination_source_command* self); @@ -1491,17 +1599,17 @@ struct mip_filter_magnetic_declination_source_response { mip_filter_mag_param_source source; ///< Magnetic field declination angle source float declination; ///< Declination angle [radians] (only required if source = MANUAL) - }; typedef struct mip_filter_magnetic_declination_source_response mip_filter_magnetic_declination_source_response; + void insert_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_response* self); void extract_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, mip_filter_magnetic_declination_source_response* self); -mip_cmd_result mip_filter_write_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source source, float declination); -mip_cmd_result mip_filter_read_magnetic_declination_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* declination_out); -mip_cmd_result mip_filter_save_magnetic_declination_source(struct mip_interface* device); -mip_cmd_result mip_filter_load_magnetic_declination_source(struct mip_interface* device); -mip_cmd_result mip_filter_default_magnetic_declination_source(struct mip_interface* device); +mip_cmd_result mip_filter_write_magnetic_declination_source(mip_interface* device, mip_filter_mag_param_source source, float declination); +mip_cmd_result mip_filter_read_magnetic_declination_source(mip_interface* device, mip_filter_mag_param_source* source_out, float* declination_out); +mip_cmd_result mip_filter_save_magnetic_declination_source(mip_interface* device); +mip_cmd_result mip_filter_load_magnetic_declination_source(mip_interface* device); +mip_cmd_result mip_filter_default_magnetic_declination_source(mip_interface* device); ///@} /// @@ -1519,9 +1627,9 @@ struct mip_filter_mag_field_magnitude_source_command mip_function_selector function; mip_filter_mag_param_source source; ///< Magnetic Field Magnitude Source float magnitude; ///< Magnitude [gauss] (only required if source = MANUAL) - }; typedef struct mip_filter_mag_field_magnitude_source_command mip_filter_mag_field_magnitude_source_command; + void insert_mip_filter_mag_field_magnitude_source_command(microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_command* self); void extract_mip_filter_mag_field_magnitude_source_command(microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_command* self); @@ -1529,17 +1637,17 @@ struct mip_filter_mag_field_magnitude_source_response { mip_filter_mag_param_source source; ///< Magnetic Field Magnitude Source float magnitude; ///< Magnitude [gauss] (only required if source = MANUAL) - }; typedef struct mip_filter_mag_field_magnitude_source_response mip_filter_mag_field_magnitude_source_response; + void insert_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self); void extract_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self); -mip_cmd_result mip_filter_write_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source source, float magnitude); -mip_cmd_result mip_filter_read_mag_field_magnitude_source(struct mip_interface* device, mip_filter_mag_param_source* source_out, float* magnitude_out); -mip_cmd_result mip_filter_save_mag_field_magnitude_source(struct mip_interface* device); -mip_cmd_result mip_filter_load_mag_field_magnitude_source(struct mip_interface* device); -mip_cmd_result mip_filter_default_mag_field_magnitude_source(struct mip_interface* device); +mip_cmd_result mip_filter_write_mag_field_magnitude_source(mip_interface* device, mip_filter_mag_param_source source, float magnitude); +mip_cmd_result mip_filter_read_mag_field_magnitude_source(mip_interface* device, mip_filter_mag_param_source* source_out, float* magnitude_out); +mip_cmd_result mip_filter_save_mag_field_magnitude_source(mip_interface* device); +mip_cmd_result mip_filter_load_mag_field_magnitude_source(mip_interface* device); +mip_cmd_result mip_filter_default_mag_field_magnitude_source(mip_interface* device); ///@} /// @@ -1559,9 +1667,9 @@ struct mip_filter_reference_position_command double latitude; ///< [degrees] double longitude; ///< [degrees] double altitude; ///< [meters] - }; typedef struct mip_filter_reference_position_command mip_filter_reference_position_command; + void insert_mip_filter_reference_position_command(microstrain_serializer* serializer, const mip_filter_reference_position_command* self); void extract_mip_filter_reference_position_command(microstrain_serializer* serializer, mip_filter_reference_position_command* self); @@ -1571,17 +1679,17 @@ struct mip_filter_reference_position_response double latitude; ///< [degrees] double longitude; ///< [degrees] double altitude; ///< [meters] - }; typedef struct mip_filter_reference_position_response mip_filter_reference_position_response; + void insert_mip_filter_reference_position_response(microstrain_serializer* serializer, const mip_filter_reference_position_response* self); void extract_mip_filter_reference_position_response(microstrain_serializer* serializer, mip_filter_reference_position_response* self); -mip_cmd_result mip_filter_write_reference_position(struct mip_interface* device, bool enable, double latitude, double longitude, double altitude); -mip_cmd_result mip_filter_read_reference_position(struct mip_interface* device, bool* enable_out, double* latitude_out, double* longitude_out, double* altitude_out); -mip_cmd_result mip_filter_save_reference_position(struct mip_interface* device); -mip_cmd_result mip_filter_load_reference_position(struct mip_interface* device); -mip_cmd_result mip_filter_default_reference_position(struct mip_interface* device); +mip_cmd_result mip_filter_write_reference_position(mip_interface* device, bool enable, double latitude, double longitude, double altitude); +mip_cmd_result mip_filter_read_reference_position(mip_interface* device, bool* enable_out, double* latitude_out, double* longitude_out, double* altitude_out); +mip_cmd_result mip_filter_save_reference_position(mip_interface* device); +mip_cmd_result mip_filter_load_reference_position(mip_interface* device); +mip_cmd_result mip_filter_default_reference_position(mip_interface* device); ///@} /// @@ -1614,9 +1722,9 @@ struct mip_filter_accel_magnitude_error_adaptive_measurement_command float low_limit_uncertainty; ///< 1-Sigma [meters/second^2] float high_limit_uncertainty; ///< 1-Sigma [meters/second^2] float minimum_uncertainty; ///< 1-Sigma [meters/second^2] - }; typedef struct mip_filter_accel_magnitude_error_adaptive_measurement_command mip_filter_accel_magnitude_error_adaptive_measurement_command; + void insert_mip_filter_accel_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_command* self); void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_command* self); @@ -1629,17 +1737,17 @@ struct mip_filter_accel_magnitude_error_adaptive_measurement_response float low_limit_uncertainty; ///< 1-Sigma [meters/second^2] float high_limit_uncertainty; ///< 1-Sigma [meters/second^2] float minimum_uncertainty; ///< 1-Sigma [meters/second^2] - }; typedef struct mip_filter_accel_magnitude_error_adaptive_measurement_response mip_filter_accel_magnitude_error_adaptive_measurement_response; + void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self); void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self); -mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty); -mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); -mip_cmd_result mip_filter_save_accel_magnitude_error_adaptive_measurement(struct mip_interface* device); -mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(struct mip_interface* device); -mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(struct mip_interface* device); +mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty); +mip_cmd_result mip_filter_read_accel_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); +mip_cmd_result mip_filter_save_accel_magnitude_error_adaptive_measurement(mip_interface* device); +mip_cmd_result mip_filter_load_accel_magnitude_error_adaptive_measurement(mip_interface* device); +mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(mip_interface* device); ///@} /// @@ -1667,9 +1775,9 @@ struct mip_filter_mag_magnitude_error_adaptive_measurement_command float low_limit_uncertainty; ///< 1-Sigma [meters/second^2] float high_limit_uncertainty; ///< 1-Sigma [meters/second^2] float minimum_uncertainty; ///< 1-Sigma [meters/second^2] - }; typedef struct mip_filter_mag_magnitude_error_adaptive_measurement_command mip_filter_mag_magnitude_error_adaptive_measurement_command; + void insert_mip_filter_mag_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_command* self); void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_command* self); @@ -1682,17 +1790,17 @@ struct mip_filter_mag_magnitude_error_adaptive_measurement_response float low_limit_uncertainty; ///< 1-Sigma [meters/second^2] float high_limit_uncertainty; ///< 1-Sigma [meters/second^2] float minimum_uncertainty; ///< 1-Sigma [meters/second^2] - }; typedef struct mip_filter_mag_magnitude_error_adaptive_measurement_response mip_filter_mag_magnitude_error_adaptive_measurement_response; + void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self); void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self); -mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty); -mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(struct mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); -mip_cmd_result mip_filter_save_mag_magnitude_error_adaptive_measurement(struct mip_interface* device); -mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(struct mip_interface* device); -mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(struct mip_interface* device); +mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty); +mip_cmd_result mip_filter_read_mag_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement* adaptive_measurement_out, float* frequency_out, float* low_limit_out, float* high_limit_out, float* low_limit_uncertainty_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); +mip_cmd_result mip_filter_save_mag_magnitude_error_adaptive_measurement(mip_interface* device); +mip_cmd_result mip_filter_load_mag_magnitude_error_adaptive_measurement(mip_interface* device); +mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(mip_interface* device); ///@} /// @@ -1720,9 +1828,9 @@ struct mip_filter_mag_dip_angle_error_adaptive_measurement_command float high_limit; ///< [meters/second^2] float high_limit_uncertainty; ///< 1-Sigma [meters/second^2] float minimum_uncertainty; ///< 1-Sigma [meters/second^2] - }; typedef struct mip_filter_mag_dip_angle_error_adaptive_measurement_command mip_filter_mag_dip_angle_error_adaptive_measurement_command; + void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_command* self); @@ -1733,17 +1841,17 @@ struct mip_filter_mag_dip_angle_error_adaptive_measurement_response float high_limit; ///< [meters/second^2] float high_limit_uncertainty; ///< 1-Sigma [meters/second^2] float minimum_uncertainty; ///< 1-Sigma [meters/second^2] - }; typedef struct mip_filter_mag_dip_angle_error_adaptive_measurement_response mip_filter_mag_dip_angle_error_adaptive_measurement_response; + void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self); -mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool enable, float frequency, float high_limit, float high_limit_uncertainty, float minimum_uncertainty); -mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device, bool* enable_out, float* frequency_out, float* high_limit_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); -mip_cmd_result mip_filter_save_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device); -mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device); -mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(struct mip_interface* device); +mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(mip_interface* device, bool enable, float frequency, float high_limit, float high_limit_uncertainty, float minimum_uncertainty); +mip_cmd_result mip_filter_read_mag_dip_angle_error_adaptive_measurement(mip_interface* device, bool* enable_out, float* frequency_out, float* high_limit_out, float* high_limit_uncertainty_out, float* minimum_uncertainty_out); +mip_cmd_result mip_filter_save_mag_dip_angle_error_adaptive_measurement(mip_interface* device); +mip_cmd_result mip_filter_load_mag_dip_angle_error_adaptive_measurement(mip_interface* device); +mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(mip_interface* device); ///@} /// @@ -1755,47 +1863,59 @@ mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(struc /// ///@{ -typedef uint16_t mip_filter_aiding_measurement_enable_command_aiding_source; -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_GNSS_POS_VEL = 0; ///< GNSS Position and Velocity -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_GNSS_HEADING = 1; ///< GNSS Heading (dual antenna) -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_ALTIMETER = 2; ///< Pressure altimeter (built-in sensor) -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_SPEED = 3; ///< Speed sensor / Odometer -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_MAGNETOMETER = 4; ///< Magnetometer (built-in sensor) -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_HEADING = 5; ///< External heading input -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_ALTIMETER = 6; ///< External pressure altimeter input -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_MAGNETOMETER = 7; ///< External magnetomer input -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_VEHICLE_FRAME_VEL = 8; ///< External vehicle frame velocity input -static const mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_ALL = 65535; ///< Save/load/reset all options +enum mip_filter_aiding_measurement_enable_command_aiding_source +{ + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_GNSS_POS_VEL = 0, ///< GNSS Position and Velocity + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_GNSS_HEADING = 1, ///< GNSS Heading (dual antenna) + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_ALTIMETER = 2, ///< Pressure altimeter (built-in sensor) + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_SPEED = 3, ///< Speed sensor / Odometer + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_MAGNETOMETER = 4, ///< Magnetometer (built-in sensor) + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_HEADING = 5, ///< External heading input + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_ALTIMETER = 6, ///< External pressure altimeter input + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_MAGNETOMETER = 7, ///< External magnetomer input + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_VEHICLE_FRAME_VEL = 8, ///< External vehicle frame velocity input + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_ALL = 65535, ///< Save/load/reset all options +}; +typedef enum mip_filter_aiding_measurement_enable_command_aiding_source mip_filter_aiding_measurement_enable_command_aiding_source; + +inline void insert_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_filter_aiding_measurement_enable_command { mip_function_selector function; mip_filter_aiding_measurement_enable_command_aiding_source aiding_source; ///< Aiding measurement source bool enable; ///< Controls the aiding source - }; typedef struct mip_filter_aiding_measurement_enable_command mip_filter_aiding_measurement_enable_command; + void insert_mip_filter_aiding_measurement_enable_command(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command* self); void extract_mip_filter_aiding_measurement_enable_command(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command* self); -void insert_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self); -void extract_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self); - struct mip_filter_aiding_measurement_enable_response { mip_filter_aiding_measurement_enable_command_aiding_source aiding_source; ///< Aiding measurement source bool enable; ///< Controls the aiding source - }; typedef struct mip_filter_aiding_measurement_enable_response mip_filter_aiding_measurement_enable_response; + void insert_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self); void extract_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_response* self); -mip_cmd_result mip_filter_write_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool enable); -mip_cmd_result mip_filter_read_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool* enable_out); -mip_cmd_result mip_filter_save_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source); -mip_cmd_result mip_filter_load_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source); -mip_cmd_result mip_filter_default_aiding_measurement_enable(struct mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source); +mip_cmd_result mip_filter_write_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool enable); +mip_cmd_result mip_filter_read_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool* enable_out); +mip_cmd_result mip_filter_save_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source); +mip_cmd_result mip_filter_load_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source); +mip_cmd_result mip_filter_default_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source); ///@} /// @@ -1807,7 +1927,7 @@ mip_cmd_result mip_filter_default_aiding_measurement_enable(struct mip_interface /// ///@{ -mip_cmd_result mip_filter_run(struct mip_interface* device); +mip_cmd_result mip_filter_run(mip_interface* device); ///@} /// @@ -1825,9 +1945,9 @@ struct mip_filter_kinematic_constraint_command uint8_t acceleration_constraint_selection; ///< Acceleration constraint:
0=None (default),
1=Zero-acceleration. uint8_t velocity_constraint_selection; ///< 0=None (default),
1=Zero-velocity,
2=Wheeled-vehicle.
uint8_t angular_constraint_selection; ///< 0=None (default), 1=Zero-angular rate (ZUPT). - }; typedef struct mip_filter_kinematic_constraint_command mip_filter_kinematic_constraint_command; + void insert_mip_filter_kinematic_constraint_command(microstrain_serializer* serializer, const mip_filter_kinematic_constraint_command* self); void extract_mip_filter_kinematic_constraint_command(microstrain_serializer* serializer, mip_filter_kinematic_constraint_command* self); @@ -1836,17 +1956,17 @@ struct mip_filter_kinematic_constraint_response uint8_t acceleration_constraint_selection; ///< Acceleration constraint:
0=None (default),
1=Zero-acceleration. uint8_t velocity_constraint_selection; ///< 0=None (default),
1=Zero-velocity,
2=Wheeled-vehicle.
uint8_t angular_constraint_selection; ///< 0=None (default), 1=Zero-angular rate (ZUPT). - }; typedef struct mip_filter_kinematic_constraint_response mip_filter_kinematic_constraint_response; + void insert_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, const mip_filter_kinematic_constraint_response* self); void extract_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, mip_filter_kinematic_constraint_response* self); -mip_cmd_result mip_filter_write_kinematic_constraint(struct mip_interface* device, uint8_t acceleration_constraint_selection, uint8_t velocity_constraint_selection, uint8_t angular_constraint_selection); -mip_cmd_result mip_filter_read_kinematic_constraint(struct mip_interface* device, uint8_t* acceleration_constraint_selection_out, uint8_t* velocity_constraint_selection_out, uint8_t* angular_constraint_selection_out); -mip_cmd_result mip_filter_save_kinematic_constraint(struct mip_interface* device); -mip_cmd_result mip_filter_load_kinematic_constraint(struct mip_interface* device); -mip_cmd_result mip_filter_default_kinematic_constraint(struct mip_interface* device); +mip_cmd_result mip_filter_write_kinematic_constraint(mip_interface* device, uint8_t acceleration_constraint_selection, uint8_t velocity_constraint_selection, uint8_t angular_constraint_selection); +mip_cmd_result mip_filter_read_kinematic_constraint(mip_interface* device, uint8_t* acceleration_constraint_selection_out, uint8_t* velocity_constraint_selection_out, uint8_t* angular_constraint_selection_out); +mip_cmd_result mip_filter_save_kinematic_constraint(mip_interface* device); +mip_cmd_result mip_filter_load_kinematic_constraint(mip_interface* device); +mip_cmd_result mip_filter_default_kinematic_constraint(mip_interface* device); ///@} /// @@ -1867,12 +1987,37 @@ static const mip_filter_initialization_configuration_command_alignment_selector static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_MAGNETOMETER = 0x04; ///< Magnetometer heading alignment (Internal magnetometer determines initial heading) static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_EXTERNAL = 0x08; ///< External heading alignment (External heading input determines heading) static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_ALL = 0x0F; +inline void insert_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + +enum mip_filter_initialization_configuration_command_initial_condition_source +{ + MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_INITIAL_CONDITION_SOURCE_AUTO_POS_VEL_ATT = 0, ///< Automatic position, velocity and attitude + MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_INITIAL_CONDITION_SOURCE_AUTO_POS_VEL_PITCH_ROLL = 1, ///< Automatic position and velocity, automatic pitch and roll, and user-specified heading + MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_INITIAL_CONDITION_SOURCE_AUTO_POS_VEL = 2, ///< Automatic position and velocity, with fully user-specified attitude + MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_INITIAL_CONDITION_SOURCE_MANUAL = 3, ///< User-specified position, velocity, and attitude. +}; +typedef enum mip_filter_initialization_configuration_command_initial_condition_source mip_filter_initialization_configuration_command_initial_condition_source; + +inline void insert_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} -typedef uint8_t mip_filter_initialization_configuration_command_initial_condition_source; -static const mip_filter_initialization_configuration_command_initial_condition_source MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_INITIAL_CONDITION_SOURCE_AUTO_POS_VEL_ATT = 0; ///< Automatic position, velocity and attitude -static const mip_filter_initialization_configuration_command_initial_condition_source MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_INITIAL_CONDITION_SOURCE_AUTO_POS_VEL_PITCH_ROLL = 1; ///< Automatic position and velocity, automatic pitch and roll, and user-specified heading -static const mip_filter_initialization_configuration_command_initial_condition_source MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_INITIAL_CONDITION_SOURCE_AUTO_POS_VEL = 2; ///< Automatic position and velocity, with fully user-specified attitude -static const mip_filter_initialization_configuration_command_initial_condition_source MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_INITIAL_CONDITION_SOURCE_MANUAL = 3; ///< User-specified position, velocity, and attitude. struct mip_filter_initialization_configuration_command { @@ -1886,18 +2031,12 @@ struct mip_filter_initialization_configuration_command mip_vector3f initial_position; ///< User-specified initial platform position (units determined by reference frame selector, see note.) mip_vector3f initial_velocity; ///< User-specified initial platform velocity (units determined by reference frame selector, see note.) mip_filter_reference_frame reference_frame_selector; ///< User-specified initial position/velocity reference frames - }; typedef struct mip_filter_initialization_configuration_command mip_filter_initialization_configuration_command; + void insert_mip_filter_initialization_configuration_command(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command* self); void extract_mip_filter_initialization_configuration_command(microstrain_serializer* serializer, mip_filter_initialization_configuration_command* self); -void insert_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self); -void extract_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self); - -void insert_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self); -void extract_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self); - struct mip_filter_initialization_configuration_response { uint8_t wait_for_run_command; ///< Initialize filter only after receiving "run" command @@ -1909,17 +2048,17 @@ struct mip_filter_initialization_configuration_response mip_vector3f initial_position; ///< User-specified initial platform position (units determined by reference frame selector, see note.) mip_vector3f initial_velocity; ///< User-specified initial platform velocity (units determined by reference frame selector, see note.) mip_filter_reference_frame reference_frame_selector; ///< User-specified initial position/velocity reference frames - }; typedef struct mip_filter_initialization_configuration_response mip_filter_initialization_configuration_response; + void insert_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, const mip_filter_initialization_configuration_response* self); void extract_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, mip_filter_initialization_configuration_response* self); -mip_cmd_result mip_filter_write_initialization_configuration(struct mip_interface* device, uint8_t wait_for_run_command, mip_filter_initialization_configuration_command_initial_condition_source initial_cond_src, mip_filter_initialization_configuration_command_alignment_selector auto_heading_alignment_selector, float initial_heading, float initial_pitch, float initial_roll, const float* initial_position, const float* initial_velocity, mip_filter_reference_frame reference_frame_selector); -mip_cmd_result mip_filter_read_initialization_configuration(struct mip_interface* device, uint8_t* wait_for_run_command_out, mip_filter_initialization_configuration_command_initial_condition_source* initial_cond_src_out, mip_filter_initialization_configuration_command_alignment_selector* auto_heading_alignment_selector_out, float* initial_heading_out, float* initial_pitch_out, float* initial_roll_out, float* initial_position_out, float* initial_velocity_out, mip_filter_reference_frame* reference_frame_selector_out); -mip_cmd_result mip_filter_save_initialization_configuration(struct mip_interface* device); -mip_cmd_result mip_filter_load_initialization_configuration(struct mip_interface* device); -mip_cmd_result mip_filter_default_initialization_configuration(struct mip_interface* device); +mip_cmd_result mip_filter_write_initialization_configuration(mip_interface* device, uint8_t wait_for_run_command, mip_filter_initialization_configuration_command_initial_condition_source initial_cond_src, mip_filter_initialization_configuration_command_alignment_selector auto_heading_alignment_selector, float initial_heading, float initial_pitch, float initial_roll, const float* initial_position, const float* initial_velocity, mip_filter_reference_frame reference_frame_selector); +mip_cmd_result mip_filter_read_initialization_configuration(mip_interface* device, uint8_t* wait_for_run_command_out, mip_filter_initialization_configuration_command_initial_condition_source* initial_cond_src_out, mip_filter_initialization_configuration_command_alignment_selector* auto_heading_alignment_selector_out, float* initial_heading_out, float* initial_pitch_out, float* initial_roll_out, float* initial_position_out, float* initial_velocity_out, mip_filter_reference_frame* reference_frame_selector_out); +mip_cmd_result mip_filter_save_initialization_configuration(mip_interface* device); +mip_cmd_result mip_filter_load_initialization_configuration(mip_interface* device); +mip_cmd_result mip_filter_default_initialization_configuration(mip_interface* device); ///@} /// @@ -1934,9 +2073,9 @@ struct mip_filter_adaptive_filter_options_command mip_function_selector function; uint8_t level; ///< Auto-adaptive operating level:
0=Off,
1=Conservative,
2=Moderate (default),
3=Aggressive. uint16_t time_limit; ///< Maximum duration of measurement rejection before entering recovery mode (ms) - }; typedef struct mip_filter_adaptive_filter_options_command mip_filter_adaptive_filter_options_command; + void insert_mip_filter_adaptive_filter_options_command(microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_command* self); void extract_mip_filter_adaptive_filter_options_command(microstrain_serializer* serializer, mip_filter_adaptive_filter_options_command* self); @@ -1944,17 +2083,17 @@ struct mip_filter_adaptive_filter_options_response { uint8_t level; ///< Auto-adaptive operating level:
0=Off,
1=Conservative,
2=Moderate (default),
3=Aggressive. uint16_t time_limit; ///< Maximum duration of measurement rejection before entering recovery mode (ms) - }; typedef struct mip_filter_adaptive_filter_options_response mip_filter_adaptive_filter_options_response; + void insert_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_response* self); void extract_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, mip_filter_adaptive_filter_options_response* self); -mip_cmd_result mip_filter_write_adaptive_filter_options(struct mip_interface* device, uint8_t level, uint16_t time_limit); -mip_cmd_result mip_filter_read_adaptive_filter_options(struct mip_interface* device, uint8_t* level_out, uint16_t* time_limit_out); -mip_cmd_result mip_filter_save_adaptive_filter_options(struct mip_interface* device); -mip_cmd_result mip_filter_load_adaptive_filter_options(struct mip_interface* device); -mip_cmd_result mip_filter_default_adaptive_filter_options(struct mip_interface* device); +mip_cmd_result mip_filter_write_adaptive_filter_options(mip_interface* device, uint8_t level, uint16_t time_limit); +mip_cmd_result mip_filter_read_adaptive_filter_options(mip_interface* device, uint8_t* level_out, uint16_t* time_limit_out); +mip_cmd_result mip_filter_save_adaptive_filter_options(mip_interface* device); +mip_cmd_result mip_filter_load_adaptive_filter_options(mip_interface* device); +mip_cmd_result mip_filter_default_adaptive_filter_options(mip_interface* device); ///@} /// @@ -1972,9 +2111,9 @@ struct mip_filter_multi_antenna_offset_command mip_function_selector function; uint8_t receiver_id; ///< Receiver: 1, 2, etc... mip_vector3f antenna_offset; ///< Antenna lever arm offset vector in the vehicle frame (m) - }; typedef struct mip_filter_multi_antenna_offset_command mip_filter_multi_antenna_offset_command; + void insert_mip_filter_multi_antenna_offset_command(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_command* self); void extract_mip_filter_multi_antenna_offset_command(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_command* self); @@ -1982,17 +2121,17 @@ struct mip_filter_multi_antenna_offset_response { uint8_t receiver_id; mip_vector3f antenna_offset; - }; typedef struct mip_filter_multi_antenna_offset_response mip_filter_multi_antenna_offset_response; + void insert_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_response* self); void extract_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_response* self); -mip_cmd_result mip_filter_write_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, const float* antenna_offset); -mip_cmd_result mip_filter_read_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id, float* antenna_offset_out); -mip_cmd_result mip_filter_save_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id); -mip_cmd_result mip_filter_load_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id); -mip_cmd_result mip_filter_default_multi_antenna_offset(struct mip_interface* device, uint8_t receiver_id); +mip_cmd_result mip_filter_write_multi_antenna_offset(mip_interface* device, uint8_t receiver_id, const float* antenna_offset); +mip_cmd_result mip_filter_read_multi_antenna_offset(mip_interface* device, uint8_t receiver_id, float* antenna_offset_out); +mip_cmd_result mip_filter_save_multi_antenna_offset(mip_interface* device, uint8_t receiver_id); +mip_cmd_result mip_filter_load_multi_antenna_offset(mip_interface* device, uint8_t receiver_id); +mip_cmd_result mip_filter_default_multi_antenna_offset(mip_interface* device, uint8_t receiver_id); ///@} /// @@ -2008,9 +2147,9 @@ struct mip_filter_rel_pos_configuration_command uint8_t source; ///< 0 - auto (RTK base station), 1 - manual mip_filter_reference_frame reference_frame_selector; ///< ECEF or LLH mip_vector3d reference_coordinates; ///< reference coordinates, units determined by source selection - }; typedef struct mip_filter_rel_pos_configuration_command mip_filter_rel_pos_configuration_command; + void insert_mip_filter_rel_pos_configuration_command(microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_command* self); void extract_mip_filter_rel_pos_configuration_command(microstrain_serializer* serializer, mip_filter_rel_pos_configuration_command* self); @@ -2019,17 +2158,17 @@ struct mip_filter_rel_pos_configuration_response uint8_t source; ///< 0 - auto (RTK base station), 1 - manual mip_filter_reference_frame reference_frame_selector; ///< ECEF or LLH mip_vector3d reference_coordinates; ///< reference coordinates, units determined by source selection - }; typedef struct mip_filter_rel_pos_configuration_response mip_filter_rel_pos_configuration_response; + void insert_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_response* self); void extract_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, mip_filter_rel_pos_configuration_response* self); -mip_cmd_result mip_filter_write_rel_pos_configuration(struct mip_interface* device, uint8_t source, mip_filter_reference_frame reference_frame_selector, const double* reference_coordinates); -mip_cmd_result mip_filter_read_rel_pos_configuration(struct mip_interface* device, uint8_t* source_out, mip_filter_reference_frame* reference_frame_selector_out, double* reference_coordinates_out); -mip_cmd_result mip_filter_save_rel_pos_configuration(struct mip_interface* device); -mip_cmd_result mip_filter_load_rel_pos_configuration(struct mip_interface* device); -mip_cmd_result mip_filter_default_rel_pos_configuration(struct mip_interface* device); +mip_cmd_result mip_filter_write_rel_pos_configuration(mip_interface* device, uint8_t source, mip_filter_reference_frame reference_frame_selector, const double* reference_coordinates); +mip_cmd_result mip_filter_read_rel_pos_configuration(mip_interface* device, uint8_t* source_out, mip_filter_reference_frame* reference_frame_selector_out, double* reference_coordinates_out); +mip_cmd_result mip_filter_save_rel_pos_configuration(mip_interface* device); +mip_cmd_result mip_filter_load_rel_pos_configuration(mip_interface* device); +mip_cmd_result mip_filter_default_rel_pos_configuration(mip_interface* device); ///@} /// @@ -2046,38 +2185,50 @@ mip_cmd_result mip_filter_default_rel_pos_configuration(struct mip_interface* de /// ///@{ -typedef uint8_t mip_filter_ref_point_lever_arm_command_reference_point_selector; -static const mip_filter_ref_point_lever_arm_command_reference_point_selector MIP_FILTER_REF_POINT_LEVER_ARM_COMMAND_REFERENCE_POINT_SELECTOR_VEH = 1; ///< Defines the origin of the vehicle +enum mip_filter_ref_point_lever_arm_command_reference_point_selector +{ + MIP_FILTER_REF_POINT_LEVER_ARM_COMMAND_REFERENCE_POINT_SELECTOR_VEH = 1, ///< Defines the origin of the vehicle +}; +typedef enum mip_filter_ref_point_lever_arm_command_reference_point_selector mip_filter_ref_point_lever_arm_command_reference_point_selector; + +inline void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_filter_ref_point_lever_arm_command { mip_function_selector function; mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel; ///< Reserved, must be 1 mip_vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. - }; typedef struct mip_filter_ref_point_lever_arm_command mip_filter_ref_point_lever_arm_command; + void insert_mip_filter_ref_point_lever_arm_command(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command* self); void extract_mip_filter_ref_point_lever_arm_command(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command* self); -void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self); -void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self); - struct mip_filter_ref_point_lever_arm_response { mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel; ///< Reserved, must be 1 mip_vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. - }; typedef struct mip_filter_ref_point_lever_arm_response mip_filter_ref_point_lever_arm_response; + void insert_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_response* self); void extract_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_response* self); -mip_cmd_result mip_filter_write_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel, const float* lever_arm_offset); -mip_cmd_result mip_filter_read_ref_point_lever_arm(struct mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector* ref_point_sel_out, float* lever_arm_offset_out); -mip_cmd_result mip_filter_save_ref_point_lever_arm(struct mip_interface* device); -mip_cmd_result mip_filter_load_ref_point_lever_arm(struct mip_interface* device); -mip_cmd_result mip_filter_default_ref_point_lever_arm(struct mip_interface* device); +mip_cmd_result mip_filter_write_ref_point_lever_arm(mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel, const float* lever_arm_offset); +mip_cmd_result mip_filter_read_ref_point_lever_arm(mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector* ref_point_sel_out, float* lever_arm_offset_out); +mip_cmd_result mip_filter_save_ref_point_lever_arm(mip_interface* device); +mip_cmd_result mip_filter_load_ref_point_lever_arm(mip_interface* device); +mip_cmd_result mip_filter_default_ref_point_lever_arm(mip_interface* device); ///@} /// @@ -2095,13 +2246,13 @@ struct mip_filter_speed_measurement_command float time_of_week; ///< GPS time of week when speed was sampled float speed; ///< Estimated speed along vehicle's x-axis (may be positive or negative) [meters/second] float speed_uncertainty; ///< Estimated uncertainty in the speed measurement (1-sigma value) [meters/second] - }; typedef struct mip_filter_speed_measurement_command mip_filter_speed_measurement_command; + void insert_mip_filter_speed_measurement_command(microstrain_serializer* serializer, const mip_filter_speed_measurement_command* self); void extract_mip_filter_speed_measurement_command(microstrain_serializer* serializer, mip_filter_speed_measurement_command* self); -mip_cmd_result mip_filter_speed_measurement(struct mip_interface* device, uint8_t source, float time_of_week, float speed, float speed_uncertainty); +mip_cmd_result mip_filter_speed_measurement(mip_interface* device, uint8_t source, float time_of_week, float speed, float speed_uncertainty); ///@} /// @@ -2122,9 +2273,9 @@ struct mip_filter_speed_lever_arm_command mip_function_selector function; uint8_t source; ///< Reserved, must be 1. mip_vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. - }; typedef struct mip_filter_speed_lever_arm_command mip_filter_speed_lever_arm_command; + void insert_mip_filter_speed_lever_arm_command(microstrain_serializer* serializer, const mip_filter_speed_lever_arm_command* self); void extract_mip_filter_speed_lever_arm_command(microstrain_serializer* serializer, mip_filter_speed_lever_arm_command* self); @@ -2132,17 +2283,17 @@ struct mip_filter_speed_lever_arm_response { uint8_t source; ///< Reserved, must be 1. mip_vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. - }; typedef struct mip_filter_speed_lever_arm_response mip_filter_speed_lever_arm_response; + void insert_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, const mip_filter_speed_lever_arm_response* self); void extract_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, mip_filter_speed_lever_arm_response* self); -mip_cmd_result mip_filter_write_speed_lever_arm(struct mip_interface* device, uint8_t source, const float* lever_arm_offset); -mip_cmd_result mip_filter_read_speed_lever_arm(struct mip_interface* device, uint8_t source, float* lever_arm_offset_out); -mip_cmd_result mip_filter_save_speed_lever_arm(struct mip_interface* device, uint8_t source); -mip_cmd_result mip_filter_load_speed_lever_arm(struct mip_interface* device, uint8_t source); -mip_cmd_result mip_filter_default_speed_lever_arm(struct mip_interface* device, uint8_t source); +mip_cmd_result mip_filter_write_speed_lever_arm(mip_interface* device, uint8_t source, const float* lever_arm_offset); +mip_cmd_result mip_filter_read_speed_lever_arm(mip_interface* device, uint8_t source, float* lever_arm_offset_out); +mip_cmd_result mip_filter_save_speed_lever_arm(mip_interface* device, uint8_t source); +mip_cmd_result mip_filter_load_speed_lever_arm(mip_interface* device, uint8_t source); +mip_cmd_result mip_filter_default_speed_lever_arm(mip_interface* device, uint8_t source); ///@} /// @@ -2162,26 +2313,26 @@ struct mip_filter_wheeled_vehicle_constraint_control_command { mip_function_selector function; uint8_t enable; ///< 0 - Disable, 1 - Enable - }; typedef struct mip_filter_wheeled_vehicle_constraint_control_command mip_filter_wheeled_vehicle_constraint_control_command; + void insert_mip_filter_wheeled_vehicle_constraint_control_command(microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_command* self); void extract_mip_filter_wheeled_vehicle_constraint_control_command(microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_command* self); struct mip_filter_wheeled_vehicle_constraint_control_response { uint8_t enable; ///< 0 - Disable, 1 - Enable - }; typedef struct mip_filter_wheeled_vehicle_constraint_control_response mip_filter_wheeled_vehicle_constraint_control_response; + void insert_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self); void extract_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self); -mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t enable); -mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(struct mip_interface* device, uint8_t* enable_out); -mip_cmd_result mip_filter_save_wheeled_vehicle_constraint_control(struct mip_interface* device); -mip_cmd_result mip_filter_load_wheeled_vehicle_constraint_control(struct mip_interface* device); -mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(struct mip_interface* device); +mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(mip_interface* device, uint8_t enable); +mip_cmd_result mip_filter_read_wheeled_vehicle_constraint_control(mip_interface* device, uint8_t* enable_out); +mip_cmd_result mip_filter_save_wheeled_vehicle_constraint_control(mip_interface* device); +mip_cmd_result mip_filter_load_wheeled_vehicle_constraint_control(mip_interface* device); +mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(mip_interface* device); ///@} /// @@ -2199,26 +2350,26 @@ struct mip_filter_vertical_gyro_constraint_control_command { mip_function_selector function; uint8_t enable; ///< 0 - Disable, 1 - Enable - }; typedef struct mip_filter_vertical_gyro_constraint_control_command mip_filter_vertical_gyro_constraint_control_command; + void insert_mip_filter_vertical_gyro_constraint_control_command(microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_command* self); void extract_mip_filter_vertical_gyro_constraint_control_command(microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_command* self); struct mip_filter_vertical_gyro_constraint_control_response { uint8_t enable; ///< 0 - Disable, 1 - Enable - }; typedef struct mip_filter_vertical_gyro_constraint_control_response mip_filter_vertical_gyro_constraint_control_response; + void insert_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self); void extract_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self); -mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t enable); -mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(struct mip_interface* device, uint8_t* enable_out); -mip_cmd_result mip_filter_save_vertical_gyro_constraint_control(struct mip_interface* device); -mip_cmd_result mip_filter_load_vertical_gyro_constraint_control(struct mip_interface* device); -mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(struct mip_interface* device); +mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(mip_interface* device, uint8_t enable); +mip_cmd_result mip_filter_read_vertical_gyro_constraint_control(mip_interface* device, uint8_t* enable_out); +mip_cmd_result mip_filter_save_vertical_gyro_constraint_control(mip_interface* device); +mip_cmd_result mip_filter_load_vertical_gyro_constraint_control(mip_interface* device); +mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(mip_interface* device); ///@} /// @@ -2235,9 +2386,9 @@ struct mip_filter_gnss_antenna_cal_control_command mip_function_selector function; uint8_t enable; ///< 0 - Disable, 1 - Enable float max_offset; ///< Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter. - }; typedef struct mip_filter_gnss_antenna_cal_control_command mip_filter_gnss_antenna_cal_control_command; + void insert_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_command* self); void extract_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_command* self); @@ -2245,17 +2396,17 @@ struct mip_filter_gnss_antenna_cal_control_response { uint8_t enable; ///< 0 - Disable, 1 - Enable float max_offset; ///< Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter. - }; typedef struct mip_filter_gnss_antenna_cal_control_response mip_filter_gnss_antenna_cal_control_response; + void insert_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self); void extract_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self); -mip_cmd_result mip_filter_write_gnss_antenna_cal_control(struct mip_interface* device, uint8_t enable, float max_offset); -mip_cmd_result mip_filter_read_gnss_antenna_cal_control(struct mip_interface* device, uint8_t* enable_out, float* max_offset_out); -mip_cmd_result mip_filter_save_gnss_antenna_cal_control(struct mip_interface* device); -mip_cmd_result mip_filter_load_gnss_antenna_cal_control(struct mip_interface* device); -mip_cmd_result mip_filter_default_gnss_antenna_cal_control(struct mip_interface* device); +mip_cmd_result mip_filter_write_gnss_antenna_cal_control(mip_interface* device, uint8_t enable, float max_offset); +mip_cmd_result mip_filter_read_gnss_antenna_cal_control(mip_interface* device, uint8_t* enable_out, float* max_offset_out); +mip_cmd_result mip_filter_save_gnss_antenna_cal_control(mip_interface* device); +mip_cmd_result mip_filter_load_gnss_antenna_cal_control(mip_interface* device); +mip_cmd_result mip_filter_default_gnss_antenna_cal_control(mip_interface* device); ///@} /// @@ -2271,13 +2422,13 @@ mip_cmd_result mip_filter_default_gnss_antenna_cal_control(struct mip_interface* struct mip_filter_set_initial_heading_command { float heading; ///< Initial heading in radians [-pi, pi] - }; typedef struct mip_filter_set_initial_heading_command mip_filter_set_initial_heading_command; + void insert_mip_filter_set_initial_heading_command(microstrain_serializer* serializer, const mip_filter_set_initial_heading_command* self); void extract_mip_filter_set_initial_heading_command(microstrain_serializer* serializer, mip_filter_set_initial_heading_command* self); -mip_cmd_result mip_filter_set_initial_heading(struct mip_interface* device, float heading); +mip_cmd_result mip_filter_set_initial_heading(mip_interface* device, float heading); ///@} /// diff --git a/src/c/mip/definitions/commands_gnss.c b/src/c/mip/definitions/commands_gnss.c index 9e32ec9c1..34d3e0933 100644 --- a/src/c/mip/definitions/commands_gnss.c +++ b/src/c/mip/definitions/commands_gnss.c @@ -13,42 +13,13 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; - - -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, const mip_gnss_receiver_info_command_info* self) -{ - microstrain_insert_u8(serializer, self->receiver_id); - - microstrain_insert_u8(serializer, self->mip_data_descriptor_set); - - for(unsigned int i=0; i < 32; i++) - microstrain_insert_char(serializer, self->description[i]); - -} -void extract_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, mip_gnss_receiver_info_command_info* self) -{ - microstrain_extract_u8(serializer, &self->receiver_id); - - microstrain_extract_u8(serializer, &self->mip_data_descriptor_set); - - for(unsigned int i=0; i < 32; i++) - microstrain_extract_char(serializer, &self->description[i]); - -} - -mip_cmd_result mip_gnss_receiver_info(struct mip_interface* device, uint8_t* num_receivers_out, uint8_t num_receivers_out_max, mip_gnss_receiver_info_command_info* receiver_info_out) +mip_cmd_result mip_gnss_receiver_info(mip_interface* device, uint8_t* num_receivers_out, uint8_t num_receivers_out_max, mip_gnss_receiver_info_command_info* receiver_info_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -67,7 +38,7 @@ mip_cmd_result mip_gnss_receiver_info(struct mip_interface* device, uint8_t* num for(unsigned int i=0; i < *num_receivers_out; i++) extract_mip_gnss_receiver_info_command_info(&deserializer, &receiver_info_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -79,11 +50,11 @@ void insert_mip_gnss_signal_configuration_command(microstrain_serializer* serial if( self->function == MIP_FUNCTION_WRITE ) { microstrain_insert_u8(serializer, self->gps_enable); - + microstrain_insert_u8(serializer, self->glonass_enable); - + microstrain_insert_u8(serializer, self->galileo_enable); - + microstrain_insert_u8(serializer, self->beidou_enable); for(unsigned int i=0; i < 4; i++) @@ -98,11 +69,11 @@ void extract_mip_gnss_signal_configuration_command(microstrain_serializer* seria if( self->function == MIP_FUNCTION_WRITE ) { microstrain_extract_u8(serializer, &self->gps_enable); - + microstrain_extract_u8(serializer, &self->glonass_enable); - + microstrain_extract_u8(serializer, &self->galileo_enable); - + microstrain_extract_u8(serializer, &self->beidou_enable); for(unsigned int i=0; i < 4; i++) @@ -111,61 +82,31 @@ void extract_mip_gnss_signal_configuration_command(microstrain_serializer* seria } } -void insert_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, const mip_gnss_signal_configuration_response* self) -{ - microstrain_insert_u8(serializer, self->gps_enable); - - microstrain_insert_u8(serializer, self->glonass_enable); - - microstrain_insert_u8(serializer, self->galileo_enable); - - microstrain_insert_u8(serializer, self->beidou_enable); - - for(unsigned int i=0; i < 4; i++) - microstrain_insert_u8(serializer, self->reserved[i]); - -} -void extract_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, mip_gnss_signal_configuration_response* self) -{ - microstrain_extract_u8(serializer, &self->gps_enable); - - microstrain_extract_u8(serializer, &self->glonass_enable); - - microstrain_extract_u8(serializer, &self->galileo_enable); - - microstrain_extract_u8(serializer, &self->beidou_enable); - - for(unsigned int i=0; i < 4; i++) - microstrain_extract_u8(serializer, &self->reserved[i]); - -} - -mip_cmd_result mip_gnss_write_signal_configuration(struct mip_interface* device, uint8_t gps_enable, uint8_t glonass_enable, uint8_t galileo_enable, uint8_t beidou_enable, const uint8_t* reserved) +mip_cmd_result mip_gnss_write_signal_configuration(mip_interface* device, uint8_t gps_enable, uint8_t glonass_enable, uint8_t galileo_enable, uint8_t beidou_enable, const uint8_t* reserved) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, gps_enable); - + microstrain_insert_u8(&serializer, glonass_enable); - + microstrain_insert_u8(&serializer, galileo_enable); - + microstrain_insert_u8(&serializer, beidou_enable); - assert(reserved || (4 == 0)); + assert(reserved); for(unsigned int i=0; i < 4; i++) microstrain_insert_u8(&serializer, reserved[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, uint8_t* gps_enable_out, uint8_t* glonass_enable_out, uint8_t* galileo_enable_out, uint8_t* beidou_enable_out, uint8_t* reserved_out) +mip_cmd_result mip_gnss_read_signal_configuration(mip_interface* device, uint8_t* gps_enable_out, uint8_t* glonass_enable_out, uint8_t* galileo_enable_out, uint8_t* beidou_enable_out, uint8_t* reserved_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -176,8 +117,7 @@ mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -196,16 +136,16 @@ mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, assert(beidou_enable_out); microstrain_extract_u8(&deserializer, beidou_enable_out); - assert(reserved_out || (4 == 0)); + assert(reserved_out); for(unsigned int i=0; i < 4; i++) microstrain_extract_u8(&deserializer, &reserved_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_gnss_save_signal_configuration(struct mip_interface* device) +mip_cmd_result mip_gnss_save_signal_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -215,10 +155,9 @@ mip_cmd_result mip_gnss_save_signal_configuration(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_gnss_load_signal_configuration(struct mip_interface* device) +mip_cmd_result mip_gnss_load_signal_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -228,10 +167,9 @@ mip_cmd_result mip_gnss_load_signal_configuration(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_gnss_default_signal_configuration(struct mip_interface* device) +mip_cmd_result mip_gnss_default_signal_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -241,8 +179,7 @@ mip_cmd_result mip_gnss_default_signal_configuration(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_SIGNAL_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_gnss_rtk_dongle_configuration_command(microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_command* self) { @@ -271,43 +208,25 @@ void extract_mip_gnss_rtk_dongle_configuration_command(microstrain_serializer* s } } -void insert_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self) -{ - microstrain_insert_u8(serializer, self->enable); - - for(unsigned int i=0; i < 3; i++) - microstrain_insert_u8(serializer, self->reserved[i]); - -} -void extract_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self) -{ - microstrain_extract_u8(serializer, &self->enable); - - for(unsigned int i=0; i < 3; i++) - microstrain_extract_u8(serializer, &self->reserved[i]); - -} - -mip_cmd_result mip_gnss_write_rtk_dongle_configuration(struct mip_interface* device, uint8_t enable, const uint8_t* reserved) +mip_cmd_result mip_gnss_write_rtk_dongle_configuration(mip_interface* device, uint8_t enable, const uint8_t* reserved) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, enable); - assert(reserved || (3 == 0)); + assert(reserved); for(unsigned int i=0; i < 3; i++) microstrain_insert_u8(&serializer, reserved[i]); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* device, uint8_t* enable_out, uint8_t* reserved_out) +mip_cmd_result mip_gnss_read_rtk_dongle_configuration(mip_interface* device, uint8_t* enable_out, uint8_t* reserved_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -318,8 +237,7 @@ mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -329,16 +247,16 @@ mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* devi assert(enable_out); microstrain_extract_u8(&deserializer, enable_out); - assert(reserved_out || (3 == 0)); + assert(reserved_out); for(unsigned int i=0; i < 3; i++) microstrain_extract_u8(&deserializer, &reserved_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_gnss_save_rtk_dongle_configuration(struct mip_interface* device) +mip_cmd_result mip_gnss_save_rtk_dongle_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -348,10 +266,9 @@ mip_cmd_result mip_gnss_save_rtk_dongle_configuration(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_gnss_load_rtk_dongle_configuration(struct mip_interface* device) +mip_cmd_result mip_gnss_load_rtk_dongle_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -361,10 +278,9 @@ mip_cmd_result mip_gnss_load_rtk_dongle_configuration(struct mip_interface* devi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_gnss_default_rtk_dongle_configuration(struct mip_interface* device) +mip_cmd_result mip_gnss_default_rtk_dongle_configuration(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -374,8 +290,7 @@ mip_cmd_result mip_gnss_default_rtk_dongle_configuration(struct mip_interface* d assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_GNSS_CMD_DESC_SET, MIP_CMD_DESC_GNSS_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } #ifdef __cplusplus diff --git a/src/c/mip/definitions/commands_gnss.h b/src/c/mip/definitions/commands_gnss.h index 34c3c09d4..09669c6ad 100644 --- a/src/c/mip/definitions/commands_gnss.h +++ b/src/c/mip/definitions/commands_gnss.h @@ -1,25 +1,20 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include #include #ifdef __cplusplus -namespace microstrain { -struct microstrain_serializer; -} namespace mip { namespace C { extern "C" { -#else -struct microstrain_serializer; + #endif // __cplusplus -struct mip_interface; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipCommands_c MIP Commands [C] @@ -74,23 +69,24 @@ struct mip_gnss_receiver_info_command_info uint8_t receiver_id; ///< Receiver id: e.g. 1, 2, etc. uint8_t mip_data_descriptor_set; ///< MIP descriptor set associated with this receiver char description[32]; ///< Ascii description of receiver. Contains the following info (comma-delimited):
Module name/model
Firmware version info - }; typedef struct mip_gnss_receiver_info_command_info mip_gnss_receiver_info_command_info; + void insert_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, const mip_gnss_receiver_info_command_info* self); void extract_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, mip_gnss_receiver_info_command_info* self); + struct mip_gnss_receiver_info_response { uint8_t num_receivers; ///< Number of physical receivers in the device mip_gnss_receiver_info_command_info receiver_info[5]; - }; typedef struct mip_gnss_receiver_info_response mip_gnss_receiver_info_response; + void insert_mip_gnss_receiver_info_response(microstrain_serializer* serializer, const mip_gnss_receiver_info_response* self); void extract_mip_gnss_receiver_info_response(microstrain_serializer* serializer, mip_gnss_receiver_info_response* self); -mip_cmd_result mip_gnss_receiver_info(struct mip_interface* device, uint8_t* num_receivers_out, uint8_t num_receivers_out_max, mip_gnss_receiver_info_command_info* receiver_info_out); +mip_cmd_result mip_gnss_receiver_info(mip_interface* device, uint8_t* num_receivers_out, uint8_t num_receivers_out_max, mip_gnss_receiver_info_command_info* receiver_info_out); ///@} /// @@ -109,9 +105,9 @@ struct mip_gnss_signal_configuration_command uint8_t galileo_enable; ///< Bitfield 0: Enable E1, 1: Enable E5B uint8_t beidou_enable; ///< Bitfield 0: Enable B1, 1: Enable B2 uint8_t reserved[4]; - }; typedef struct mip_gnss_signal_configuration_command mip_gnss_signal_configuration_command; + void insert_mip_gnss_signal_configuration_command(microstrain_serializer* serializer, const mip_gnss_signal_configuration_command* self); void extract_mip_gnss_signal_configuration_command(microstrain_serializer* serializer, mip_gnss_signal_configuration_command* self); @@ -122,17 +118,17 @@ struct mip_gnss_signal_configuration_response uint8_t galileo_enable; ///< Bitfield 0: Enable E1, 1: Enable E5B uint8_t beidou_enable; ///< Bitfield 0: Enable B1, 1: Enable B2 uint8_t reserved[4]; - }; typedef struct mip_gnss_signal_configuration_response mip_gnss_signal_configuration_response; + void insert_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, const mip_gnss_signal_configuration_response* self); void extract_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, mip_gnss_signal_configuration_response* self); -mip_cmd_result mip_gnss_write_signal_configuration(struct mip_interface* device, uint8_t gps_enable, uint8_t glonass_enable, uint8_t galileo_enable, uint8_t beidou_enable, const uint8_t* reserved); -mip_cmd_result mip_gnss_read_signal_configuration(struct mip_interface* device, uint8_t* gps_enable_out, uint8_t* glonass_enable_out, uint8_t* galileo_enable_out, uint8_t* beidou_enable_out, uint8_t* reserved_out); -mip_cmd_result mip_gnss_save_signal_configuration(struct mip_interface* device); -mip_cmd_result mip_gnss_load_signal_configuration(struct mip_interface* device); -mip_cmd_result mip_gnss_default_signal_configuration(struct mip_interface* device); +mip_cmd_result mip_gnss_write_signal_configuration(mip_interface* device, uint8_t gps_enable, uint8_t glonass_enable, uint8_t galileo_enable, uint8_t beidou_enable, const uint8_t* reserved); +mip_cmd_result mip_gnss_read_signal_configuration(mip_interface* device, uint8_t* gps_enable_out, uint8_t* glonass_enable_out, uint8_t* galileo_enable_out, uint8_t* beidou_enable_out, uint8_t* reserved_out); +mip_cmd_result mip_gnss_save_signal_configuration(mip_interface* device); +mip_cmd_result mip_gnss_load_signal_configuration(mip_interface* device); +mip_cmd_result mip_gnss_default_signal_configuration(mip_interface* device); ///@} /// @@ -148,9 +144,9 @@ struct mip_gnss_rtk_dongle_configuration_command mip_function_selector function; uint8_t enable; ///< 0 - Disabled, 1- Enabled uint8_t reserved[3]; - }; typedef struct mip_gnss_rtk_dongle_configuration_command mip_gnss_rtk_dongle_configuration_command; + void insert_mip_gnss_rtk_dongle_configuration_command(microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_command* self); void extract_mip_gnss_rtk_dongle_configuration_command(microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_command* self); @@ -158,17 +154,17 @@ struct mip_gnss_rtk_dongle_configuration_response { uint8_t enable; uint8_t reserved[3]; - }; typedef struct mip_gnss_rtk_dongle_configuration_response mip_gnss_rtk_dongle_configuration_response; + void insert_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self); void extract_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self); -mip_cmd_result mip_gnss_write_rtk_dongle_configuration(struct mip_interface* device, uint8_t enable, const uint8_t* reserved); -mip_cmd_result mip_gnss_read_rtk_dongle_configuration(struct mip_interface* device, uint8_t* enable_out, uint8_t* reserved_out); -mip_cmd_result mip_gnss_save_rtk_dongle_configuration(struct mip_interface* device); -mip_cmd_result mip_gnss_load_rtk_dongle_configuration(struct mip_interface* device); -mip_cmd_result mip_gnss_default_rtk_dongle_configuration(struct mip_interface* device); +mip_cmd_result mip_gnss_write_rtk_dongle_configuration(mip_interface* device, uint8_t enable, const uint8_t* reserved); +mip_cmd_result mip_gnss_read_rtk_dongle_configuration(mip_interface* device, uint8_t* enable_out, uint8_t* reserved_out); +mip_cmd_result mip_gnss_save_rtk_dongle_configuration(mip_interface* device); +mip_cmd_result mip_gnss_load_rtk_dongle_configuration(mip_interface* device); +mip_cmd_result mip_gnss_default_rtk_dongle_configuration(mip_interface* device); ///@} /// diff --git a/src/c/mip/definitions/commands_rtk.c b/src/c/mip/definitions/commands_rtk.c index 3e6a43441..6dbd49bf8 100644 --- a/src/c/mip/definitions/commands_rtk.c +++ b/src/c/mip/definitions/commands_rtk.c @@ -13,65 +13,13 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; - - -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - -void insert_mip_media_selector(microstrain_serializer* serializer, const mip_media_selector self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_media_selector(microstrain_serializer* serializer, mip_media_selector* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_led_action(microstrain_serializer* serializer, const mip_led_action self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_led_action(microstrain_serializer* serializer, mip_led_action* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self) -{ - microstrain_insert_u32(serializer, (uint32_t) (self)); -} -void extract_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self) -{ - uint32_t tmp = 0; - microstrain_extract_u32(serializer, &tmp); - *self = tmp; -} - -void insert_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self) -{ - microstrain_insert_u32(serializer, (uint32_t) (self)); -} -void extract_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self) -{ - uint32_t tmp = 0; - microstrain_extract_u32(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_rtk_get_status_flags(struct mip_interface* device, mip_rtk_get_status_flags_command_status_flags* flags_out) +mip_cmd_result mip_rtk_get_status_flags(mip_interface* device, mip_rtk_get_status_flags_command_status_flags* flags_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -86,12 +34,12 @@ mip_cmd_result mip_rtk_get_status_flags(struct mip_interface* device, mip_rtk_ge assert(flags_out); extract_mip_rtk_get_status_flags_command_status_flags(&deserializer, flags_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_rtk_get_imei(struct mip_interface* device, char* imei_out) +mip_cmd_result mip_rtk_get_imei(mip_interface* device, char* imei_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -103,16 +51,16 @@ mip_cmd_result mip_rtk_get_imei(struct mip_interface* device, char* imei_out) microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(imei_out || (32 == 0)); + assert(imei_out); for(unsigned int i=0; i < 32; i++) microstrain_extract_char(&deserializer, &imei_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_rtk_get_imsi(struct mip_interface* device, char* imsi_out) +mip_cmd_result mip_rtk_get_imsi(mip_interface* device, char* imsi_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -124,16 +72,16 @@ mip_cmd_result mip_rtk_get_imsi(struct mip_interface* device, char* imsi_out) microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(imsi_out || (32 == 0)); + assert(imsi_out); for(unsigned int i=0; i < 32; i++) microstrain_extract_char(&deserializer, &imsi_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out) +mip_cmd_result mip_rtk_get_iccid(mip_interface* device, char* iccid_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -145,11 +93,11 @@ mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out) microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(iccid_out || (32 == 0)); + assert(iccid_out); for(unsigned int i=0; i < 32; i++) microstrain_extract_char(&deserializer, &iccid_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -175,29 +123,7 @@ void extract_mip_rtk_connected_device_type_command(microstrain_serializer* seria } } -void insert_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, const mip_rtk_connected_device_type_response* self) -{ - insert_mip_rtk_connected_device_type_command_type(serializer, self->devType); - -} -void extract_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, mip_rtk_connected_device_type_response* self) -{ - extract_mip_rtk_connected_device_type_command_type(serializer, &self->devType); - -} - -void insert_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_rtk_write_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type dev_type) +mip_cmd_result mip_rtk_write_connected_device_type(mip_interface* device, mip_rtk_connected_device_type_command_type dev_type) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -209,10 +135,9 @@ mip_cmd_result mip_rtk_write_connected_device_type(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type* dev_type_out) +mip_cmd_result mip_rtk_read_connected_device_type(mip_interface* device, mip_rtk_connected_device_type_command_type* dev_type_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -223,8 +148,7 @@ mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -234,12 +158,12 @@ mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, assert(dev_type_out); extract_mip_rtk_connected_device_type_command_type(&deserializer, dev_type_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_rtk_save_connected_device_type(struct mip_interface* device) +mip_cmd_result mip_rtk_save_connected_device_type(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -249,10 +173,9 @@ mip_cmd_result mip_rtk_save_connected_device_type(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_rtk_load_connected_device_type(struct mip_interface* device) +mip_cmd_result mip_rtk_load_connected_device_type(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -262,10 +185,9 @@ mip_cmd_result mip_rtk_load_connected_device_type(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_rtk_default_connected_device_type(struct mip_interface* device) +mip_cmd_result mip_rtk_default_connected_device_type(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -275,10 +197,9 @@ mip_cmd_result mip_rtk_default_connected_device_type(struct mip_interface* devic assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_rtk_get_act_code(struct mip_interface* device, char* activation_code_out) +mip_cmd_result mip_rtk_get_act_code(mip_interface* device, char* activation_code_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -290,16 +211,16 @@ mip_cmd_result mip_rtk_get_act_code(struct mip_interface* device, char* activati microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(activation_code_out || (32 == 0)); + assert(activation_code_out); for(unsigned int i=0; i < 32; i++) microstrain_extract_char(&deserializer, &activation_code_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_rtk_get_modem_firmware_version(struct mip_interface* device, char* modem_firmware_version_out) +mip_cmd_result mip_rtk_get_modem_firmware_version(mip_interface* device, char* modem_firmware_version_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -311,16 +232,16 @@ mip_cmd_result mip_rtk_get_modem_firmware_version(struct mip_interface* device, microstrain_serializer deserializer; microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); - assert(modem_firmware_version_out || (32 == 0)); + assert(modem_firmware_version_out); for(unsigned int i=0; i < 32; i++) microstrain_extract_char(&deserializer, &modem_firmware_version_out[i]); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_rtk_get_rssi(struct mip_interface* device, bool* valid_out, int32_t* rssi_out, int32_t* signal_quality_out) +mip_cmd_result mip_rtk_get_rssi(mip_interface* device, bool* valid_out, int32_t* rssi_out, int32_t* signal_quality_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); @@ -341,7 +262,7 @@ mip_cmd_result mip_rtk_get_rssi(struct mip_interface* device, bool* valid_out, i assert(signal_quality_out); microstrain_extract_s32(&deserializer, signal_quality_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -349,67 +270,32 @@ mip_cmd_result mip_rtk_get_rssi(struct mip_interface* device, bool* valid_out, i void insert_mip_rtk_service_status_command(microstrain_serializer* serializer, const mip_rtk_service_status_command* self) { microstrain_insert_u32(serializer, self->reserved1); - + microstrain_insert_u32(serializer, self->reserved2); } void extract_mip_rtk_service_status_command(microstrain_serializer* serializer, mip_rtk_service_status_command* self) { microstrain_extract_u32(serializer, &self->reserved1); - - microstrain_extract_u32(serializer, &self->reserved2); -} - -void insert_mip_rtk_service_status_response(microstrain_serializer* serializer, const mip_rtk_service_status_response* self) -{ - insert_mip_rtk_service_status_command_service_flags(serializer, self->flags); - - microstrain_insert_u32(serializer, self->receivedBytes); - - microstrain_insert_u32(serializer, self->lastBytes); - - microstrain_insert_u64(serializer, self->lastBytesTime); - -} -void extract_mip_rtk_service_status_response(microstrain_serializer* serializer, mip_rtk_service_status_response* self) -{ - extract_mip_rtk_service_status_command_service_flags(serializer, &self->flags); - - microstrain_extract_u32(serializer, &self->receivedBytes); - - microstrain_extract_u32(serializer, &self->lastBytes); - - microstrain_extract_u64(serializer, &self->lastBytesTime); + microstrain_extract_u32(serializer, &self->reserved2); } -void insert_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t reserved1, uint32_t reserved2, mip_rtk_service_status_command_service_flags* flags_out, uint32_t* received_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out) +mip_cmd_result mip_rtk_service_status(mip_interface* device, uint32_t reserved1, uint32_t reserved2, mip_rtk_service_status_command_service_flags* flags_out, uint32_t* received_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - + microstrain_insert_u32(&serializer, reserved1); - + microstrain_insert_u32(&serializer, reserved2); assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_SERVICE_STATUS, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_RTK_SERVICE_STATUS, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_SERVICE_STATUS, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_RTK_SERVICE_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -428,7 +314,7 @@ mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t res assert(last_bytes_time_out); microstrain_extract_u64(&deserializer, last_bytes_time_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; @@ -444,7 +330,7 @@ void extract_mip_rtk_prod_erase_storage_command(microstrain_serializer* serializ } -mip_cmd_result mip_rtk_prod_erase_storage(struct mip_interface* device, mip_media_selector media) +mip_cmd_result mip_rtk_prod_erase_storage(mip_interface* device, mip_media_selector media) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -454,8 +340,7 @@ mip_cmd_result mip_rtk_prod_erase_storage(struct mip_interface* device, mip_medi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_PROD_ERASE_STORAGE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_PROD_ERASE_STORAGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } void insert_mip_rtk_led_control_command(microstrain_serializer* serializer, const mip_rtk_led_control_command* self) { @@ -466,7 +351,7 @@ void insert_mip_rtk_led_control_command(microstrain_serializer* serializer, cons microstrain_insert_u8(serializer, self->altColor[i]); insert_mip_led_action(serializer, self->act); - + microstrain_insert_u32(serializer, self->period); } @@ -479,35 +364,34 @@ void extract_mip_rtk_led_control_command(microstrain_serializer* serializer, mip microstrain_extract_u8(serializer, &self->altColor[i]); extract_mip_led_action(serializer, &self->act); - + microstrain_extract_u32(serializer, &self->period); } -mip_cmd_result mip_rtk_led_control(struct mip_interface* device, const uint8_t* primary_color, const uint8_t* alt_color, mip_led_action act, uint32_t period) +mip_cmd_result mip_rtk_led_control(mip_interface* device, const uint8_t* primary_color, const uint8_t* alt_color, mip_led_action act, uint32_t period) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); - assert(primary_color || (3 == 0)); + assert(primary_color); for(unsigned int i=0; i < 3; i++) microstrain_insert_u8(&serializer, primary_color[i]); - assert(alt_color || (3 == 0)); + assert(alt_color); for(unsigned int i=0; i < 3; i++) microstrain_insert_u8(&serializer, alt_color[i]); insert_mip_led_action(&serializer, act); - + microstrain_insert_u32(&serializer, period); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_LED_CONTROL, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_LED_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_rtk_modem_hard_reset(struct mip_interface* device) +mip_cmd_result mip_rtk_modem_hard_reset(mip_interface* device) { return mip_interface_run_command(device, MIP_RTK_CMD_DESC_SET, MIP_CMD_DESC_RTK_MODEM_HARD_RESET, NULL, 0); } diff --git a/src/c/mip/definitions/commands_rtk.h b/src/c/mip/definitions/commands_rtk.h index 4381ba91b..e59309208 100644 --- a/src/c/mip/definitions/commands_rtk.h +++ b/src/c/mip/definitions/commands_rtk.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,9 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipCommands_c MIP Commands [C] @@ -61,20 +59,42 @@ enum // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -typedef uint8_t mip_media_selector; -static const mip_media_selector MIP_MEDIA_SELECTOR_MEDIA_EXTERNALFLASH = 0; ///< -static const mip_media_selector MIP_MEDIA_SELECTOR_MEDIA_SD = 1; ///< +enum mip_media_selector +{ + MIP_MEDIA_SELECTOR_MEDIA_EXTERNALFLASH = 0, ///< + MIP_MEDIA_SELECTOR_MEDIA_SD = 1, ///< +}; +typedef enum mip_media_selector mip_media_selector; -void insert_mip_media_selector(microstrain_serializer* serializer, const mip_media_selector self); -void extract_mip_media_selector(microstrain_serializer* serializer, mip_media_selector* self); +inline void insert_mip_media_selector(microstrain_serializer* serializer, const mip_media_selector self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_media_selector(microstrain_serializer* serializer, mip_media_selector* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} -typedef uint8_t mip_led_action; -static const mip_led_action MIP_LED_ACTION_LED_NONE = 0; ///< -static const mip_led_action MIP_LED_ACTION_LED_FLASH = 1; ///< -static const mip_led_action MIP_LED_ACTION_LED_PULSATE = 2; ///< +enum mip_led_action +{ + MIP_LED_ACTION_LED_NONE = 0, ///< + MIP_LED_ACTION_LED_FLASH = 1, ///< + MIP_LED_ACTION_LED_PULSATE = 2, ///< +}; +typedef enum mip_led_action mip_led_action; -void insert_mip_led_action(microstrain_serializer* serializer, const mip_led_action self); -void extract_mip_led_action(microstrain_serializer* serializer, mip_led_action* self); +inline void insert_mip_led_action(microstrain_serializer* serializer, const mip_led_action self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_led_action(microstrain_serializer* serializer, mip_led_action* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} //////////////////////////////////////////////////////////////////////////////// @@ -100,6 +120,16 @@ static const mip_rtk_get_status_flags_command_status_flags_legacy MIP_RTK_GET_ST static const mip_rtk_get_status_flags_command_status_flags_legacy MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_LEGACY_RSRQ = 0x30000000; ///< static const mip_rtk_get_status_flags_command_status_flags_legacy MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_LEGACY_SINR = 0xC0000000; ///< static const mip_rtk_get_status_flags_command_status_flags_legacy MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_LEGACY_ALL = 0xFFFFFFFF; +inline void insert_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self) +{ + microstrain_insert_u32(serializer, (uint32_t)(self)); +} +inline void extract_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self) +{ + uint32_t tmp = 0; + microstrain_extract_u32(serializer, &tmp); + *self = tmp; +} typedef uint32_t mip_rtk_get_status_flags_command_status_flags; static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_NONE = 0x00000000; @@ -116,23 +146,28 @@ static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FL static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_RESERVED = 0x20000000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_VERSION = 0xC0000000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_ALL = 0xFFFFFFFF; +inline void insert_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self) +{ + microstrain_insert_u32(serializer, (uint32_t)(self)); +} +inline void extract_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self) +{ + uint32_t tmp = 0; + microstrain_extract_u32(serializer, &tmp); + *self = tmp; +} -void insert_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self); -void extract_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self); - -void insert_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self); -void extract_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self); struct mip_rtk_get_status_flags_response { mip_rtk_get_status_flags_command_status_flags flags; ///< Model number dependent. See above structures. - }; typedef struct mip_rtk_get_status_flags_response mip_rtk_get_status_flags_response; + void insert_mip_rtk_get_status_flags_response(microstrain_serializer* serializer, const mip_rtk_get_status_flags_response* self); void extract_mip_rtk_get_status_flags_response(microstrain_serializer* serializer, mip_rtk_get_status_flags_response* self); -mip_cmd_result mip_rtk_get_status_flags(struct mip_interface* device, mip_rtk_get_status_flags_command_status_flags* flags_out); +mip_cmd_result mip_rtk_get_status_flags(mip_interface* device, mip_rtk_get_status_flags_command_status_flags* flags_out); ///@} /// @@ -144,13 +179,13 @@ mip_cmd_result mip_rtk_get_status_flags(struct mip_interface* device, mip_rtk_ge struct mip_rtk_get_imei_response { char IMEI[32]; - }; typedef struct mip_rtk_get_imei_response mip_rtk_get_imei_response; + void insert_mip_rtk_get_imei_response(microstrain_serializer* serializer, const mip_rtk_get_imei_response* self); void extract_mip_rtk_get_imei_response(microstrain_serializer* serializer, mip_rtk_get_imei_response* self); -mip_cmd_result mip_rtk_get_imei(struct mip_interface* device, char* imei_out); +mip_cmd_result mip_rtk_get_imei(mip_interface* device, char* imei_out); ///@} /// @@ -162,13 +197,13 @@ mip_cmd_result mip_rtk_get_imei(struct mip_interface* device, char* imei_out); struct mip_rtk_get_imsi_response { char IMSI[32]; - }; typedef struct mip_rtk_get_imsi_response mip_rtk_get_imsi_response; + void insert_mip_rtk_get_imsi_response(microstrain_serializer* serializer, const mip_rtk_get_imsi_response* self); void extract_mip_rtk_get_imsi_response(microstrain_serializer* serializer, mip_rtk_get_imsi_response* self); -mip_cmd_result mip_rtk_get_imsi(struct mip_interface* device, char* imsi_out); +mip_cmd_result mip_rtk_get_imsi(mip_interface* device, char* imsi_out); ///@} /// @@ -180,13 +215,13 @@ mip_cmd_result mip_rtk_get_imsi(struct mip_interface* device, char* imsi_out); struct mip_rtk_get_iccid_response { char ICCID[32]; - }; typedef struct mip_rtk_get_iccid_response mip_rtk_get_iccid_response; + void insert_mip_rtk_get_iccid_response(microstrain_serializer* serializer, const mip_rtk_get_iccid_response* self); void extract_mip_rtk_get_iccid_response(microstrain_serializer* serializer, mip_rtk_get_iccid_response* self); -mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out); +mip_cmd_result mip_rtk_get_iccid(mip_interface* device, char* iccid_out); ///@} /// @@ -195,37 +230,49 @@ mip_cmd_result mip_rtk_get_iccid(struct mip_interface* device, char* iccid_out); /// ///@{ -typedef uint8_t mip_rtk_connected_device_type_command_type; -static const mip_rtk_connected_device_type_command_type MIP_RTK_CONNECTED_DEVICE_TYPE_COMMAND_TYPE_GENERIC = 0; ///< -static const mip_rtk_connected_device_type_command_type MIP_RTK_CONNECTED_DEVICE_TYPE_COMMAND_TYPE_GQ7 = 1; ///< +enum mip_rtk_connected_device_type_command_type +{ + MIP_RTK_CONNECTED_DEVICE_TYPE_COMMAND_TYPE_GENERIC = 0, ///< + MIP_RTK_CONNECTED_DEVICE_TYPE_COMMAND_TYPE_GQ7 = 1, ///< +}; +typedef enum mip_rtk_connected_device_type_command_type mip_rtk_connected_device_type_command_type; + +inline void insert_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_rtk_connected_device_type_command { mip_function_selector function; mip_rtk_connected_device_type_command_type devType; - }; typedef struct mip_rtk_connected_device_type_command mip_rtk_connected_device_type_command; + void insert_mip_rtk_connected_device_type_command(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command* self); void extract_mip_rtk_connected_device_type_command(microstrain_serializer* serializer, mip_rtk_connected_device_type_command* self); -void insert_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self); -void extract_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self); - struct mip_rtk_connected_device_type_response { mip_rtk_connected_device_type_command_type devType; - }; typedef struct mip_rtk_connected_device_type_response mip_rtk_connected_device_type_response; + void insert_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, const mip_rtk_connected_device_type_response* self); void extract_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, mip_rtk_connected_device_type_response* self); -mip_cmd_result mip_rtk_write_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type dev_type); -mip_cmd_result mip_rtk_read_connected_device_type(struct mip_interface* device, mip_rtk_connected_device_type_command_type* dev_type_out); -mip_cmd_result mip_rtk_save_connected_device_type(struct mip_interface* device); -mip_cmd_result mip_rtk_load_connected_device_type(struct mip_interface* device); -mip_cmd_result mip_rtk_default_connected_device_type(struct mip_interface* device); +mip_cmd_result mip_rtk_write_connected_device_type(mip_interface* device, mip_rtk_connected_device_type_command_type dev_type); +mip_cmd_result mip_rtk_read_connected_device_type(mip_interface* device, mip_rtk_connected_device_type_command_type* dev_type_out); +mip_cmd_result mip_rtk_save_connected_device_type(mip_interface* device); +mip_cmd_result mip_rtk_load_connected_device_type(mip_interface* device); +mip_cmd_result mip_rtk_default_connected_device_type(mip_interface* device); ///@} /// @@ -237,13 +284,13 @@ mip_cmd_result mip_rtk_default_connected_device_type(struct mip_interface* devic struct mip_rtk_get_act_code_response { char ActivationCode[32]; - }; typedef struct mip_rtk_get_act_code_response mip_rtk_get_act_code_response; + void insert_mip_rtk_get_act_code_response(microstrain_serializer* serializer, const mip_rtk_get_act_code_response* self); void extract_mip_rtk_get_act_code_response(microstrain_serializer* serializer, mip_rtk_get_act_code_response* self); -mip_cmd_result mip_rtk_get_act_code(struct mip_interface* device, char* activation_code_out); +mip_cmd_result mip_rtk_get_act_code(mip_interface* device, char* activation_code_out); ///@} /// @@ -255,13 +302,13 @@ mip_cmd_result mip_rtk_get_act_code(struct mip_interface* device, char* activati struct mip_rtk_get_modem_firmware_version_response { char ModemFirmwareVersion[32]; - }; typedef struct mip_rtk_get_modem_firmware_version_response mip_rtk_get_modem_firmware_version_response; + void insert_mip_rtk_get_modem_firmware_version_response(microstrain_serializer* serializer, const mip_rtk_get_modem_firmware_version_response* self); void extract_mip_rtk_get_modem_firmware_version_response(microstrain_serializer* serializer, mip_rtk_get_modem_firmware_version_response* self); -mip_cmd_result mip_rtk_get_modem_firmware_version(struct mip_interface* device, char* modem_firmware_version_out); +mip_cmd_result mip_rtk_get_modem_firmware_version(mip_interface* device, char* modem_firmware_version_out); ///@} /// @@ -276,13 +323,13 @@ struct mip_rtk_get_rssi_response bool valid; int32_t rssi; int32_t signalQuality; - }; typedef struct mip_rtk_get_rssi_response mip_rtk_get_rssi_response; + void insert_mip_rtk_get_rssi_response(microstrain_serializer* serializer, const mip_rtk_get_rssi_response* self); void extract_mip_rtk_get_rssi_response(microstrain_serializer* serializer, mip_rtk_get_rssi_response* self); -mip_cmd_result mip_rtk_get_rssi(struct mip_interface* device, bool* valid_out, int32_t* rssi_out, int32_t* signal_quality_out); +mip_cmd_result mip_rtk_get_rssi(mip_interface* device, bool* valid_out, int32_t* rssi_out, int32_t* signal_quality_out); ///@} /// @@ -298,33 +345,41 @@ static const mip_rtk_service_status_command_service_flags MIP_RTK_SERVICE_STATUS static const mip_rtk_service_status_command_service_flags MIP_RTK_SERVICE_STATUS_COMMAND_SERVICE_FLAGS_CORRECTIONS_UNAVAILABLE = 0x02; ///< static const mip_rtk_service_status_command_service_flags MIP_RTK_SERVICE_STATUS_COMMAND_SERVICE_FLAGS_RESERVED = 0xFC; ///< static const mip_rtk_service_status_command_service_flags MIP_RTK_SERVICE_STATUS_COMMAND_SERVICE_FLAGS_ALL = 0xFF; +inline void insert_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_rtk_service_status_command { uint32_t reserved1; uint32_t reserved2; - }; typedef struct mip_rtk_service_status_command mip_rtk_service_status_command; + void insert_mip_rtk_service_status_command(microstrain_serializer* serializer, const mip_rtk_service_status_command* self); void extract_mip_rtk_service_status_command(microstrain_serializer* serializer, mip_rtk_service_status_command* self); -void insert_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self); -void extract_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self); - struct mip_rtk_service_status_response { mip_rtk_service_status_command_service_flags flags; uint32_t receivedBytes; uint32_t lastBytes; uint64_t lastBytesTime; - }; typedef struct mip_rtk_service_status_response mip_rtk_service_status_response; + void insert_mip_rtk_service_status_response(microstrain_serializer* serializer, const mip_rtk_service_status_response* self); void extract_mip_rtk_service_status_response(microstrain_serializer* serializer, mip_rtk_service_status_response* self); -mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t reserved1, uint32_t reserved2, mip_rtk_service_status_command_service_flags* flags_out, uint32_t* received_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out); +mip_cmd_result mip_rtk_service_status(mip_interface* device, uint32_t reserved1, uint32_t reserved2, mip_rtk_service_status_command_service_flags* flags_out, uint32_t* received_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out); ///@} /// @@ -338,13 +393,13 @@ mip_cmd_result mip_rtk_service_status(struct mip_interface* device, uint32_t res struct mip_rtk_prod_erase_storage_command { mip_media_selector media; - }; typedef struct mip_rtk_prod_erase_storage_command mip_rtk_prod_erase_storage_command; + void insert_mip_rtk_prod_erase_storage_command(microstrain_serializer* serializer, const mip_rtk_prod_erase_storage_command* self); void extract_mip_rtk_prod_erase_storage_command(microstrain_serializer* serializer, mip_rtk_prod_erase_storage_command* self); -mip_cmd_result mip_rtk_prod_erase_storage(struct mip_interface* device, mip_media_selector media); +mip_cmd_result mip_rtk_prod_erase_storage(mip_interface* device, mip_media_selector media); ///@} /// @@ -360,13 +415,13 @@ struct mip_rtk_led_control_command uint8_t altColor[3]; mip_led_action act; uint32_t period; - }; typedef struct mip_rtk_led_control_command mip_rtk_led_control_command; + void insert_mip_rtk_led_control_command(microstrain_serializer* serializer, const mip_rtk_led_control_command* self); void extract_mip_rtk_led_control_command(microstrain_serializer* serializer, mip_rtk_led_control_command* self); -mip_cmd_result mip_rtk_led_control(struct mip_interface* device, const uint8_t* primary_color, const uint8_t* alt_color, mip_led_action act, uint32_t period); +mip_cmd_result mip_rtk_led_control(mip_interface* device, const uint8_t* primary_color, const uint8_t* alt_color, mip_led_action act, uint32_t period); ///@} /// @@ -377,7 +432,7 @@ mip_cmd_result mip_rtk_led_control(struct mip_interface* device, const uint8_t* /// ///@{ -mip_cmd_result mip_rtk_modem_hard_reset(struct mip_interface* device); +mip_cmd_result mip_rtk_modem_hard_reset(mip_interface* device); ///@} /// diff --git a/src/c/mip/definitions/commands_system.c b/src/c/mip/definitions/commands_system.c index 998a8cae8..b79d9476c 100644 --- a/src/c/mip/definitions/commands_system.c +++ b/src/c/mip/definitions/commands_system.c @@ -13,14 +13,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; - - -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// @@ -48,33 +40,21 @@ void extract_mip_system_comm_mode_command(microstrain_serializer* serializer, mi } } -void insert_mip_system_comm_mode_response(microstrain_serializer* serializer, const mip_system_comm_mode_response* self) -{ - microstrain_insert_u8(serializer, self->mode); - -} -void extract_mip_system_comm_mode_response(microstrain_serializer* serializer, mip_system_comm_mode_response* self) -{ - microstrain_extract_u8(serializer, &self->mode); - -} - -mip_cmd_result mip_system_write_comm_mode(struct mip_interface* device, uint8_t mode) +mip_cmd_result mip_system_write_comm_mode(mip_interface* device, uint8_t mode) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; microstrain_serializer_init_insertion(&serializer, buffer, sizeof(buffer)); insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - + microstrain_insert_u8(&serializer, mode); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* mode_out) +mip_cmd_result mip_system_read_comm_mode(mip_interface* device, uint8_t* mode_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -85,8 +65,7 @@ mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* assert(microstrain_serializer_is_ok(&serializer)); uint8_t responseLength = sizeof(buffer); - mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t) microstrain_serializer_length( - &serializer), MIP_REPLY_DESC_SYSTEM_COM_MODE, buffer, &responseLength); + mip_cmd_result result = mip_interface_run_command_with_response(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer), MIP_REPLY_DESC_SYSTEM_COM_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -96,12 +75,12 @@ mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* assert(mode_out); microstrain_extract_u8(&deserializer, mode_out); - if(microstrain_serializer_remaining(&deserializer) != 0 ) + if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_system_default_comm_mode(struct mip_interface* device) +mip_cmd_result mip_system_default_comm_mode(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -111,8 +90,7 @@ mip_cmd_result mip_system_default_comm_mode(struct mip_interface* device) assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t) microstrain_serializer_length( - &serializer)); + return mip_interface_run_command(device, MIP_SYSTEM_CMD_DESC_SET, MIP_CMD_DESC_SYSTEM_COM_MODE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } #ifdef __cplusplus diff --git a/src/c/mip/definitions/commands_system.h b/src/c/mip/definitions/commands_system.h index 5219efcc1..71718063f 100644 --- a/src/c/mip/definitions/commands_system.h +++ b/src/c/mip/definitions/commands_system.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,9 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipCommands_c MIP Commands [C] @@ -74,24 +72,24 @@ struct mip_system_comm_mode_command { mip_function_selector function; uint8_t mode; - }; typedef struct mip_system_comm_mode_command mip_system_comm_mode_command; + void insert_mip_system_comm_mode_command(microstrain_serializer* serializer, const mip_system_comm_mode_command* self); void extract_mip_system_comm_mode_command(microstrain_serializer* serializer, mip_system_comm_mode_command* self); struct mip_system_comm_mode_response { uint8_t mode; - }; typedef struct mip_system_comm_mode_response mip_system_comm_mode_response; + void insert_mip_system_comm_mode_response(microstrain_serializer* serializer, const mip_system_comm_mode_response* self); void extract_mip_system_comm_mode_response(microstrain_serializer* serializer, mip_system_comm_mode_response* self); -mip_cmd_result mip_system_write_comm_mode(struct mip_interface* device, uint8_t mode); -mip_cmd_result mip_system_read_comm_mode(struct mip_interface* device, uint8_t* mode_out); -mip_cmd_result mip_system_default_comm_mode(struct mip_interface* device); +mip_cmd_result mip_system_write_comm_mode(mip_interface* device, uint8_t mode); +mip_cmd_result mip_system_read_comm_mode(mip_interface* device, uint8_t* mode_out); +mip_cmd_result mip_system_default_comm_mode(mip_interface* device); ///@} /// diff --git a/src/c/mip/definitions/data_filter.c b/src/c/mip/definitions/data_filter.c index 2aea2720f..74544ec13 100644 --- a/src/c/mip/definitions/data_filter.c +++ b/src/c/mip/definitions/data_filter.c @@ -13,80 +13,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; - - -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - -void insert_mip_filter_mode(microstrain_serializer* serializer, const mip_filter_mode self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_filter_mode(microstrain_serializer* serializer, mip_filter_mode* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -void insert_mip_filter_dynamics_mode(microstrain_serializer* serializer, const mip_filter_dynamics_mode self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_filter_dynamics_mode(microstrain_serializer* serializer, mip_filter_dynamics_mode* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -void insert_mip_filter_status_flags(microstrain_serializer* serializer, const mip_filter_status_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_filter_status_flags(microstrain_serializer* serializer, mip_filter_status_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -void insert_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_filter_measurement_indicator(microstrain_serializer* serializer, const mip_filter_measurement_indicator self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_measurement_indicator(microstrain_serializer* serializer, mip_filter_measurement_indicator* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_aid_status_flags(microstrain_serializer* serializer, const mip_gnss_aid_status_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_aid_status_flags(microstrain_serializer* serializer, mip_gnss_aid_status_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} //////////////////////////////////////////////////////////////////////////////// @@ -96,22 +22,22 @@ void extract_mip_gnss_aid_status_flags(microstrain_serializer* serializer, mip_g void insert_mip_filter_position_llh_data(microstrain_serializer* serializer, const mip_filter_position_llh_data* self) { microstrain_insert_double(serializer, self->latitude); - + microstrain_insert_double(serializer, self->longitude); - + microstrain_insert_double(serializer, self->ellipsoid_height); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_position_llh_data(microstrain_serializer* serializer, mip_filter_position_llh_data* self) { microstrain_extract_double(serializer, &self->latitude); - + microstrain_extract_double(serializer, &self->longitude); - + microstrain_extract_double(serializer, &self->ellipsoid_height); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -119,7 +45,7 @@ bool extract_mip_filter_position_llh_data_from_field(const mip_field_view* field { assert(ptr); mip_filter_position_llh_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_position_llh_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -128,22 +54,22 @@ bool extract_mip_filter_position_llh_data_from_field(const mip_field_view* field void insert_mip_filter_velocity_ned_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_data* self) { microstrain_insert_float(serializer, self->north); - + microstrain_insert_float(serializer, self->east); - + microstrain_insert_float(serializer, self->down); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_velocity_ned_data(microstrain_serializer* serializer, mip_filter_velocity_ned_data* self) { microstrain_extract_float(serializer, &self->north); - + microstrain_extract_float(serializer, &self->east); - + microstrain_extract_float(serializer, &self->down); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -151,7 +77,7 @@ bool extract_mip_filter_velocity_ned_data_from_field(const mip_field_view* field { assert(ptr); mip_filter_velocity_ned_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_velocity_ned_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -159,17 +85,15 @@ bool extract_mip_filter_velocity_ned_data_from_field(const mip_field_view* field void insert_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, const mip_filter_attitude_quaternion_data* self) { - for(unsigned int i=0; i < 4; i++) - microstrain_insert_float(serializer, self->q[i]); - + insert_mip_quatf(serializer, self->q); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, mip_filter_attitude_quaternion_data* self) { - for(unsigned int i=0; i < 4; i++) - microstrain_extract_float(serializer, &self->q[i]); - + extract_mip_quatf(serializer, self->q); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -177,7 +101,7 @@ bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field_view { assert(ptr); mip_filter_attitude_quaternion_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_attitude_quaternion_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -185,17 +109,15 @@ bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field_view void insert_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, const mip_filter_attitude_dcm_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->dcm[i]); - + insert_mip_matrix3f(serializer, self->dcm); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, mip_filter_attitude_dcm_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->dcm[i]); - + extract_mip_matrix3f(serializer, self->dcm); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -203,7 +125,7 @@ bool extract_mip_filter_attitude_dcm_data_from_field(const mip_field_view* field { assert(ptr); mip_filter_attitude_dcm_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_attitude_dcm_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -212,22 +134,22 @@ bool extract_mip_filter_attitude_dcm_data_from_field(const mip_field_view* field void insert_mip_filter_euler_angles_data(microstrain_serializer* serializer, const mip_filter_euler_angles_data* self) { microstrain_insert_float(serializer, self->roll); - + microstrain_insert_float(serializer, self->pitch); - + microstrain_insert_float(serializer, self->yaw); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_euler_angles_data(microstrain_serializer* serializer, mip_filter_euler_angles_data* self) { microstrain_extract_float(serializer, &self->roll); - + microstrain_extract_float(serializer, &self->pitch); - + microstrain_extract_float(serializer, &self->yaw); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -235,7 +157,7 @@ bool extract_mip_filter_euler_angles_data_from_field(const mip_field_view* field { assert(ptr); mip_filter_euler_angles_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_euler_angles_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -243,17 +165,15 @@ bool extract_mip_filter_euler_angles_data_from_field(const mip_field_view* field void insert_mip_filter_gyro_bias_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias[i]); - + insert_mip_vector3f(serializer, self->bias); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gyro_bias_data(microstrain_serializer* serializer, mip_filter_gyro_bias_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias[i]); - + extract_mip_vector3f(serializer, self->bias); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -261,7 +181,7 @@ bool extract_mip_filter_gyro_bias_data_from_field(const mip_field_view* field, v { assert(ptr); mip_filter_gyro_bias_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_bias_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -269,17 +189,15 @@ bool extract_mip_filter_gyro_bias_data_from_field(const mip_field_view* field, v void insert_mip_filter_accel_bias_data(microstrain_serializer* serializer, const mip_filter_accel_bias_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias[i]); - + insert_mip_vector3f(serializer, self->bias); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_accel_bias_data(microstrain_serializer* serializer, mip_filter_accel_bias_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias[i]); - + extract_mip_vector3f(serializer, self->bias); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -287,7 +205,7 @@ bool extract_mip_filter_accel_bias_data_from_field(const mip_field_view* field, { assert(ptr); mip_filter_accel_bias_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_bias_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -296,22 +214,22 @@ bool extract_mip_filter_accel_bias_data_from_field(const mip_field_view* field, void insert_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self) { microstrain_insert_float(serializer, self->north); - + microstrain_insert_float(serializer, self->east); - + microstrain_insert_float(serializer, self->down); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, mip_filter_position_llh_uncertainty_data* self) { microstrain_extract_float(serializer, &self->north); - + microstrain_extract_float(serializer, &self->east); - + microstrain_extract_float(serializer, &self->down); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -319,7 +237,7 @@ bool extract_mip_filter_position_llh_uncertainty_data_from_field(const mip_field { assert(ptr); mip_filter_position_llh_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_position_llh_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -328,22 +246,22 @@ bool extract_mip_filter_position_llh_uncertainty_data_from_field(const mip_field void insert_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self) { microstrain_insert_float(serializer, self->north); - + microstrain_insert_float(serializer, self->east); - + microstrain_insert_float(serializer, self->down); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self) { microstrain_extract_float(serializer, &self->north); - + microstrain_extract_float(serializer, &self->east); - + microstrain_extract_float(serializer, &self->down); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -351,7 +269,7 @@ bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const mip_field { assert(ptr); mip_filter_velocity_ned_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_velocity_ned_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -360,22 +278,22 @@ bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const mip_field void insert_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self) { microstrain_insert_float(serializer, self->roll); - + microstrain_insert_float(serializer, self->pitch); - + microstrain_insert_float(serializer, self->yaw); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self) { microstrain_extract_float(serializer, &self->roll); - + microstrain_extract_float(serializer, &self->pitch); - + microstrain_extract_float(serializer, &self->yaw); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -383,7 +301,7 @@ bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const mip_field { assert(ptr); mip_filter_euler_angles_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_euler_angles_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -391,17 +309,15 @@ bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const mip_field void insert_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias_uncert[i]); - + insert_mip_vector3f(serializer, self->bias_uncert); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias_uncert[i]); - + extract_mip_vector3f(serializer, self->bias_uncert); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -409,7 +325,7 @@ bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const mip_field_vi { assert(ptr); mip_filter_gyro_bias_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_bias_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -417,17 +333,15 @@ bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const mip_field_vi void insert_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias_uncert[i]); - + insert_mip_vector3f(serializer, self->bias_uncert); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias_uncert[i]); - + extract_mip_vector3f(serializer, self->bias_uncert); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -435,7 +349,7 @@ bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const mip_field_v { assert(ptr); mip_filter_accel_bias_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_bias_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -444,18 +358,18 @@ bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const mip_field_v void insert_mip_filter_timestamp_data(microstrain_serializer* serializer, const mip_filter_timestamp_data* self) { microstrain_insert_double(serializer, self->tow); - + microstrain_insert_u16(serializer, self->week_number); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_timestamp_data(microstrain_serializer* serializer, mip_filter_timestamp_data* self) { microstrain_extract_double(serializer, &self->tow); - + microstrain_extract_u16(serializer, &self->week_number); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -463,7 +377,7 @@ bool extract_mip_filter_timestamp_data_from_field(const mip_field_view* field, v { assert(ptr); mip_filter_timestamp_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -491,7 +405,7 @@ bool extract_mip_filter_status_data_from_field(const mip_field_view* field, void { assert(ptr); mip_filter_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -499,17 +413,15 @@ bool extract_mip_filter_status_data_from_field(const mip_field_view* field, void void insert_mip_filter_linear_accel_data(microstrain_serializer* serializer, const mip_filter_linear_accel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->accel[i]); - + insert_mip_vector3f(serializer, self->accel); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_linear_accel_data(microstrain_serializer* serializer, mip_filter_linear_accel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->accel[i]); - + extract_mip_vector3f(serializer, self->accel); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -517,7 +429,7 @@ bool extract_mip_filter_linear_accel_data_from_field(const mip_field_view* field { assert(ptr); mip_filter_linear_accel_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_linear_accel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -525,17 +437,15 @@ bool extract_mip_filter_linear_accel_data_from_field(const mip_field_view* field void insert_mip_filter_gravity_vector_data(microstrain_serializer* serializer, const mip_filter_gravity_vector_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->gravity[i]); - + insert_mip_vector3f(serializer, self->gravity); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gravity_vector_data(microstrain_serializer* serializer, mip_filter_gravity_vector_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->gravity[i]); - + extract_mip_vector3f(serializer, self->gravity); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -543,7 +453,7 @@ bool extract_mip_filter_gravity_vector_data_from_field(const mip_field_view* fie { assert(ptr); mip_filter_gravity_vector_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gravity_vector_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -551,17 +461,15 @@ bool extract_mip_filter_gravity_vector_data_from_field(const mip_field_view* fie void insert_mip_filter_comp_accel_data(microstrain_serializer* serializer, const mip_filter_comp_accel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->accel[i]); - + insert_mip_vector3f(serializer, self->accel); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_comp_accel_data(microstrain_serializer* serializer, mip_filter_comp_accel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->accel[i]); - + extract_mip_vector3f(serializer, self->accel); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -569,7 +477,7 @@ bool extract_mip_filter_comp_accel_data_from_field(const mip_field_view* field, { assert(ptr); mip_filter_comp_accel_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_comp_accel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -577,17 +485,15 @@ bool extract_mip_filter_comp_accel_data_from_field(const mip_field_view* field, void insert_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, const mip_filter_comp_angular_rate_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->gyro[i]); - + insert_mip_vector3f(serializer, self->gyro); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, mip_filter_comp_angular_rate_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->gyro[i]); - + extract_mip_vector3f(serializer, self->gyro); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -595,7 +501,7 @@ bool extract_mip_filter_comp_angular_rate_data_from_field(const mip_field_view* { assert(ptr); mip_filter_comp_angular_rate_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_comp_angular_rate_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -603,17 +509,15 @@ bool extract_mip_filter_comp_angular_rate_data_from_field(const mip_field_view* void insert_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self) { - for(unsigned int i=0; i < 4; i++) - microstrain_insert_float(serializer, self->q[i]); - + insert_mip_quatf(serializer, self->q); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self) { - for(unsigned int i=0; i < 4; i++) - microstrain_extract_float(serializer, &self->q[i]); - + extract_mip_quatf(serializer, self->q); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -621,7 +525,7 @@ bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const mi { assert(ptr); mip_filter_quaternion_attitude_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_quaternion_attitude_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -630,14 +534,14 @@ bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const mi void insert_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self) { microstrain_insert_float(serializer, self->magnitude); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self) { microstrain_extract_float(serializer, &self->magnitude); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -645,7 +549,7 @@ bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const mip_field_view* { assert(ptr); mip_filter_wgs84_gravity_mag_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_wgs84_gravity_mag_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -654,22 +558,22 @@ bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const mip_field_view* void insert_mip_filter_heading_update_state_data(microstrain_serializer* serializer, const mip_filter_heading_update_state_data* self) { microstrain_insert_float(serializer, self->heading); - + microstrain_insert_float(serializer, self->heading_1sigma); insert_mip_filter_heading_update_state_data_heading_source(serializer, self->source); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_heading_update_state_data(microstrain_serializer* serializer, mip_filter_heading_update_state_data* self) { microstrain_extract_float(serializer, &self->heading); - + microstrain_extract_float(serializer, &self->heading_1sigma); extract_mip_filter_heading_update_state_data_heading_source(serializer, &self->source); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -677,50 +581,39 @@ bool extract_mip_filter_heading_update_state_data_from_field(const mip_field_vie { assert(ptr); mip_filter_heading_update_state_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_heading_update_state_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_filter_magnetic_model_data(microstrain_serializer* serializer, const mip_filter_magnetic_model_data* self) { microstrain_insert_float(serializer, self->intensity_north); - + microstrain_insert_float(serializer, self->intensity_east); - + microstrain_insert_float(serializer, self->intensity_down); - + microstrain_insert_float(serializer, self->inclination); - + microstrain_insert_float(serializer, self->declination); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetic_model_data(microstrain_serializer* serializer, mip_filter_magnetic_model_data* self) { microstrain_extract_float(serializer, &self->intensity_north); - + microstrain_extract_float(serializer, &self->intensity_east); - + microstrain_extract_float(serializer, &self->intensity_down); - + microstrain_extract_float(serializer, &self->inclination); - + microstrain_extract_float(serializer, &self->declination); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -728,7 +621,7 @@ bool extract_mip_filter_magnetic_model_data_from_field(const mip_field_view* fie { assert(ptr); mip_filter_magnetic_model_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetic_model_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -736,17 +629,15 @@ bool extract_mip_filter_magnetic_model_data_from_field(const mip_field_view* fie void insert_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->scale_factor[i]); - + insert_mip_vector3f(serializer, self->scale_factor); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->scale_factor[i]); - + extract_mip_vector3f(serializer, self->scale_factor); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -754,7 +645,7 @@ bool extract_mip_filter_accel_scale_factor_data_from_field(const mip_field_view* { assert(ptr); mip_filter_accel_scale_factor_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_scale_factor_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -762,17 +653,15 @@ bool extract_mip_filter_accel_scale_factor_data_from_field(const mip_field_view* void insert_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->scale_factor_uncert[i]); - + insert_mip_vector3f(serializer, self->scale_factor_uncert); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->scale_factor_uncert[i]); - + extract_mip_vector3f(serializer, self->scale_factor_uncert); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -780,7 +669,7 @@ bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const mip { assert(ptr); mip_filter_accel_scale_factor_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_accel_scale_factor_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -788,17 +677,15 @@ bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const mip void insert_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->scale_factor[i]); - + insert_mip_vector3f(serializer, self->scale_factor); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->scale_factor[i]); - + extract_mip_vector3f(serializer, self->scale_factor); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -806,7 +693,7 @@ bool extract_mip_filter_gyro_scale_factor_data_from_field(const mip_field_view* { assert(ptr); mip_filter_gyro_scale_factor_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_scale_factor_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -814,17 +701,15 @@ bool extract_mip_filter_gyro_scale_factor_data_from_field(const mip_field_view* void insert_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->scale_factor_uncert[i]); - + insert_mip_vector3f(serializer, self->scale_factor_uncert); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->scale_factor_uncert[i]); - + extract_mip_vector3f(serializer, self->scale_factor_uncert); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -832,7 +717,7 @@ bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const mip_ { assert(ptr); mip_filter_gyro_scale_factor_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gyro_scale_factor_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -840,17 +725,15 @@ bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const mip_ void insert_mip_filter_mag_bias_data(microstrain_serializer* serializer, const mip_filter_mag_bias_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias[i]); - + insert_mip_vector3f(serializer, self->bias); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_mag_bias_data(microstrain_serializer* serializer, mip_filter_mag_bias_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias[i]); - + extract_mip_vector3f(serializer, self->bias); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -858,7 +741,7 @@ bool extract_mip_filter_mag_bias_data_from_field(const mip_field_view* field, vo { assert(ptr); mip_filter_mag_bias_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_mag_bias_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -866,17 +749,15 @@ bool extract_mip_filter_mag_bias_data_from_field(const mip_field_view* field, vo void insert_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->bias_uncert[i]); - + insert_mip_vector3f(serializer, self->bias_uncert); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->bias_uncert[i]); - + extract_mip_vector3f(serializer, self->bias_uncert); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -884,7 +765,7 @@ bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const mip_field_vie { assert(ptr); mip_filter_mag_bias_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_mag_bias_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -893,30 +774,30 @@ bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const mip_field_vie void insert_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, const mip_filter_standard_atmosphere_data* self) { microstrain_insert_float(serializer, self->geometric_altitude); - + microstrain_insert_float(serializer, self->geopotential_altitude); - + microstrain_insert_float(serializer, self->standard_temperature); - + microstrain_insert_float(serializer, self->standard_pressure); - + microstrain_insert_float(serializer, self->standard_density); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, mip_filter_standard_atmosphere_data* self) { microstrain_extract_float(serializer, &self->geometric_altitude); - + microstrain_extract_float(serializer, &self->geopotential_altitude); - + microstrain_extract_float(serializer, &self->standard_temperature); - + microstrain_extract_float(serializer, &self->standard_pressure); - + microstrain_extract_float(serializer, &self->standard_density); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -924,7 +805,7 @@ bool extract_mip_filter_standard_atmosphere_data_from_field(const mip_field_view { assert(ptr); mip_filter_standard_atmosphere_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_standard_atmosphere_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -933,14 +814,14 @@ bool extract_mip_filter_standard_atmosphere_data_from_field(const mip_field_view void insert_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, const mip_filter_pressure_altitude_data* self) { microstrain_insert_float(serializer, self->pressure_altitude); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, mip_filter_pressure_altitude_data* self) { microstrain_extract_float(serializer, &self->pressure_altitude); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -948,7 +829,7 @@ bool extract_mip_filter_pressure_altitude_data_from_field(const mip_field_view* { assert(ptr); mip_filter_pressure_altitude_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_pressure_altitude_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -957,14 +838,14 @@ bool extract_mip_filter_pressure_altitude_data_from_field(const mip_field_view* void insert_mip_filter_density_altitude_data(microstrain_serializer* serializer, const mip_filter_density_altitude_data* self) { microstrain_insert_float(serializer, self->density_altitude); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_density_altitude_data(microstrain_serializer* serializer, mip_filter_density_altitude_data* self) { microstrain_extract_float(serializer, &self->density_altitude); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -972,7 +853,7 @@ bool extract_mip_filter_density_altitude_data_from_field(const mip_field_view* f { assert(ptr); mip_filter_density_altitude_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_density_altitude_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -980,17 +861,15 @@ bool extract_mip_filter_density_altitude_data_from_field(const mip_field_view* f void insert_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset[i]); - + insert_mip_vector3f(serializer, self->offset); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset[i]); - + extract_mip_vector3f(serializer, self->offset); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -998,7 +877,7 @@ bool extract_mip_filter_antenna_offset_correction_data_from_field(const mip_fiel { assert(ptr); mip_filter_antenna_offset_correction_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_antenna_offset_correction_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1006,17 +885,15 @@ bool extract_mip_filter_antenna_offset_correction_data_from_field(const mip_fiel void insert_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset_uncert[i]); - + insert_mip_vector3f(serializer, self->offset_uncert); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset_uncert[i]); - + extract_mip_vector3f(serializer, self->offset_uncert); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1024,7 +901,7 @@ bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(co { assert(ptr); mip_filter_antenna_offset_correction_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_antenna_offset_correction_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1034,9 +911,8 @@ void insert_mip_filter_multi_antenna_offset_correction_data(microstrain_serializ { microstrain_insert_u8(serializer, self->receiver_id); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset[i]); - + insert_mip_vector3f(serializer, self->offset); + microstrain_insert_u16(serializer, self->valid_flags); } @@ -1044,9 +920,8 @@ void extract_mip_filter_multi_antenna_offset_correction_data(microstrain_seriali { microstrain_extract_u8(serializer, &self->receiver_id); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset[i]); - + extract_mip_vector3f(serializer, self->offset); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1054,7 +929,7 @@ bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const mi { assert(ptr); mip_filter_multi_antenna_offset_correction_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_multi_antenna_offset_correction_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1064,9 +939,8 @@ void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(microstr { microstrain_insert_u8(serializer, self->receiver_id); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->offset_uncert[i]); - + insert_mip_vector3f(serializer, self->offset_uncert); + microstrain_insert_u16(serializer, self->valid_flags); } @@ -1074,9 +948,8 @@ void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(microst { microstrain_extract_u8(serializer, &self->receiver_id); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->offset_uncert[i]); - + extract_mip_vector3f(serializer, self->offset_uncert); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1084,7 +957,7 @@ bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_fi { assert(ptr); mip_filter_multi_antenna_offset_correction_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1092,17 +965,15 @@ bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_fi void insert_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->hard_iron[i]); - + insert_mip_vector3f(serializer, self->hard_iron); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->hard_iron[i]); - + extract_mip_vector3f(serializer, self->hard_iron); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1110,7 +981,7 @@ bool extract_mip_filter_magnetometer_offset_data_from_field(const mip_field_view { assert(ptr); mip_filter_magnetometer_offset_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_offset_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1118,17 +989,15 @@ bool extract_mip_filter_magnetometer_offset_data_from_field(const mip_field_view void insert_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->soft_iron[i]); - + insert_mip_matrix3f(serializer, self->soft_iron); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->soft_iron[i]); - + extract_mip_matrix3f(serializer, self->soft_iron); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1136,7 +1005,7 @@ bool extract_mip_filter_magnetometer_matrix_data_from_field(const mip_field_view { assert(ptr); mip_filter_magnetometer_matrix_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_matrix_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1144,17 +1013,15 @@ bool extract_mip_filter_magnetometer_matrix_data_from_field(const mip_field_view void insert_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->hard_iron_uncertainty[i]); - + insert_mip_vector3f(serializer, self->hard_iron_uncertainty); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->hard_iron_uncertainty[i]); - + extract_mip_vector3f(serializer, self->hard_iron_uncertainty); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1162,7 +1029,7 @@ bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const mi { assert(ptr); mip_filter_magnetometer_offset_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_offset_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1170,17 +1037,15 @@ bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const mi void insert_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->soft_iron_uncertainty[i]); - + insert_mip_matrix3f(serializer, self->soft_iron_uncertainty); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->soft_iron_uncertainty[i]); - + extract_mip_matrix3f(serializer, self->soft_iron_uncertainty); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1188,7 +1053,7 @@ bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const mi { assert(ptr); mip_filter_magnetometer_matrix_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_matrix_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1196,17 +1061,15 @@ bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const mi void insert_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->covariance[i]); - + insert_mip_matrix3f(serializer, self->covariance); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->covariance[i]); - + extract_mip_matrix3f(serializer, self->covariance); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1214,7 +1077,7 @@ bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const mip { assert(ptr); mip_filter_magnetometer_covariance_matrix_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_covariance_matrix_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1222,17 +1085,15 @@ bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const mip void insert_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->residual[i]); - + insert_mip_vector3f(serializer, self->residual); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->residual[i]); - + extract_mip_vector3f(serializer, self->residual); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1240,7 +1101,7 @@ bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const mip_f { assert(ptr); mip_filter_magnetometer_residual_vector_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_magnetometer_residual_vector_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1249,22 +1110,22 @@ bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const mip_f void insert_mip_filter_clock_correction_data(microstrain_serializer* serializer, const mip_filter_clock_correction_data* self) { microstrain_insert_u8(serializer, self->receiver_id); - + microstrain_insert_float(serializer, self->bias); - + microstrain_insert_float(serializer, self->bias_drift); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_clock_correction_data(microstrain_serializer* serializer, mip_filter_clock_correction_data* self) { microstrain_extract_u8(serializer, &self->receiver_id); - + microstrain_extract_float(serializer, &self->bias); - + microstrain_extract_float(serializer, &self->bias_drift); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1272,7 +1133,7 @@ bool extract_mip_filter_clock_correction_data_from_field(const mip_field_view* f { assert(ptr); mip_filter_clock_correction_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_clock_correction_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1281,22 +1142,22 @@ bool extract_mip_filter_clock_correction_data_from_field(const mip_field_view* f void insert_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self) { microstrain_insert_u8(serializer, self->receiver_id); - + microstrain_insert_float(serializer, self->bias_uncertainty); - + microstrain_insert_float(serializer, self->bias_drift_uncertainty); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self) { microstrain_extract_u8(serializer, &self->receiver_id); - + microstrain_extract_float(serializer, &self->bias_uncertainty); - + microstrain_extract_float(serializer, &self->bias_drift_uncertainty); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1304,7 +1165,7 @@ bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const mip_f { assert(ptr); mip_filter_clock_correction_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_clock_correction_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1313,7 +1174,7 @@ bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const mip_f void insert_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self) { microstrain_insert_u8(serializer, self->receiver_id); - + microstrain_insert_float(serializer, self->time_of_week); insert_mip_gnss_aid_status_flags(serializer, self->status); @@ -1325,7 +1186,7 @@ void insert_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializ void extract_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self) { microstrain_extract_u8(serializer, &self->receiver_id); - + microstrain_extract_float(serializer, &self->time_of_week); extract_mip_gnss_aid_status_flags(serializer, &self->status); @@ -1338,7 +1199,7 @@ bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const mip_field_view { assert(ptr); mip_filter_gnss_pos_aid_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gnss_pos_aid_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1368,7 +1229,7 @@ bool extract_mip_filter_gnss_att_aid_status_data_from_field(const mip_field_view { assert(ptr); mip_filter_gnss_att_aid_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gnss_att_aid_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1398,36 +1259,23 @@ bool extract_mip_filter_head_aid_status_data_from_field(const mip_field_view* fi { assert(ptr); mip_filter_head_aid_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_head_aid_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - void insert_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, const mip_filter_rel_pos_ned_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_double(serializer, self->relative_position[i]); - + insert_mip_vector3d(serializer, self->relative_position); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, mip_filter_rel_pos_ned_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_double(serializer, &self->relative_position[i]); - + extract_mip_vector3d(serializer, self->relative_position); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1435,7 +1283,7 @@ bool extract_mip_filter_rel_pos_ned_data_from_field(const mip_field_view* field, { assert(ptr); mip_filter_rel_pos_ned_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_rel_pos_ned_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1443,17 +1291,15 @@ bool extract_mip_filter_rel_pos_ned_data_from_field(const mip_field_view* field, void insert_mip_filter_ecef_pos_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_double(serializer, self->position_ecef[i]); - + insert_mip_vector3d(serializer, self->position_ecef); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_ecef_pos_data(microstrain_serializer* serializer, mip_filter_ecef_pos_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_double(serializer, &self->position_ecef[i]); - + extract_mip_vector3d(serializer, self->position_ecef); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1461,7 +1307,7 @@ bool extract_mip_filter_ecef_pos_data_from_field(const mip_field_view* field, vo { assert(ptr); mip_filter_ecef_pos_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_pos_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1469,17 +1315,15 @@ bool extract_mip_filter_ecef_pos_data_from_field(const mip_field_view* field, vo void insert_mip_filter_ecef_vel_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->velocity_ecef[i]); - + insert_mip_vector3f(serializer, self->velocity_ecef); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_ecef_vel_data(microstrain_serializer* serializer, mip_filter_ecef_vel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->velocity_ecef[i]); - + extract_mip_vector3f(serializer, self->velocity_ecef); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1487,7 +1331,7 @@ bool extract_mip_filter_ecef_vel_data_from_field(const mip_field_view* field, vo { assert(ptr); mip_filter_ecef_vel_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_vel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1495,17 +1339,15 @@ bool extract_mip_filter_ecef_vel_data_from_field(const mip_field_view* field, vo void insert_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->pos_uncertainty[i]); - + insert_mip_vector3f(serializer, self->pos_uncertainty); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->pos_uncertainty[i]); - + extract_mip_vector3f(serializer, self->pos_uncertainty); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1513,7 +1355,7 @@ bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const mip_field_vie { assert(ptr); mip_filter_ecef_pos_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_pos_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1521,17 +1363,15 @@ bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const mip_field_vie void insert_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->vel_uncertainty[i]); - + insert_mip_vector3f(serializer, self->vel_uncertainty); + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->vel_uncertainty[i]); - + extract_mip_vector3f(serializer, self->vel_uncertainty); + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1539,7 +1379,7 @@ bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const mip_field_vie { assert(ptr); mip_filter_ecef_vel_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_ecef_vel_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1548,7 +1388,7 @@ bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const mip_field_vie void insert_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self) { microstrain_insert_float(serializer, self->time_of_week); - + microstrain_insert_u8(serializer, self->source); insert_mip_filter_aiding_measurement_type(serializer, self->type); @@ -1559,7 +1399,7 @@ void insert_mip_filter_aiding_measurement_summary_data(microstrain_serializer* s void extract_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, mip_filter_aiding_measurement_summary_data* self) { microstrain_extract_float(serializer, &self->time_of_week); - + microstrain_extract_u8(serializer, &self->source); extract_mip_filter_aiding_measurement_type(serializer, &self->type); @@ -1571,7 +1411,7 @@ bool extract_mip_filter_aiding_measurement_summary_data_from_field(const mip_fie { assert(ptr); mip_filter_aiding_measurement_summary_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_aiding_measurement_summary_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1580,14 +1420,14 @@ bool extract_mip_filter_aiding_measurement_summary_data_from_field(const mip_fie void insert_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self) { microstrain_insert_float(serializer, self->scale_factor_error); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self) { microstrain_extract_float(serializer, &self->scale_factor_error); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1595,7 +1435,7 @@ bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const mip_fi { assert(ptr); mip_filter_odometer_scale_factor_error_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_odometer_scale_factor_error_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1604,14 +1444,14 @@ bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const mip_fi void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self) { microstrain_insert_float(serializer, self->scale_factor_error_uncertainty); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self) { microstrain_extract_float(serializer, &self->scale_factor_error_uncertainty); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1619,7 +1459,7 @@ bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field( { assert(ptr); mip_filter_odometer_scale_factor_error_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_odometer_scale_factor_error_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1628,30 +1468,30 @@ bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field( void insert_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self) { microstrain_insert_float(serializer, self->time_of_week); - + microstrain_insert_float(serializer, self->heading); - + microstrain_insert_float(serializer, self->heading_unc); insert_mip_filter_gnss_dual_antenna_status_data_fix_type(serializer, self->fix_type); insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(serializer, self->status_flags); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self) { microstrain_extract_float(serializer, &self->time_of_week); - + microstrain_extract_float(serializer, &self->heading); - + microstrain_extract_float(serializer, &self->heading_unc); extract_mip_filter_gnss_dual_antenna_status_data_fix_type(serializer, &self->fix_type); extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(serializer, &self->status_flags); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -1659,61 +1499,35 @@ bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const mip_field { assert(ptr); mip_filter_gnss_dual_antenna_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_gnss_dual_antenna_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self) { microstrain_insert_u8(serializer, self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->translation[i]); + insert_mip_vector3f(serializer, self->translation); - for(unsigned int i=0; i < 4; i++) - microstrain_insert_float(serializer, self->attitude[i]); + insert_mip_quatf(serializer, self->attitude); } void extract_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_data* self) { microstrain_extract_u8(serializer, &self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->translation[i]); + extract_mip_vector3f(serializer, self->translation); - for(unsigned int i=0; i < 4; i++) - microstrain_extract_float(serializer, &self->attitude[i]); + extract_mip_quatf(serializer, self->attitude); } bool extract_mip_filter_aiding_frame_config_error_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_aiding_frame_config_error_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_aiding_frame_config_error_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -1723,29 +1537,25 @@ void insert_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_se { microstrain_insert_u8(serializer, self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->translation_unc[i]); + insert_mip_vector3f(serializer, self->translation_unc); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->attitude_unc[i]); + insert_mip_vector3f(serializer, self->attitude_unc); } void extract_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self) { microstrain_extract_u8(serializer, &self->frame_id); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->translation_unc[i]); + extract_mip_vector3f(serializer, self->translation_unc); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->attitude_unc[i]); + extract_mip_vector3f(serializer, self->attitude_unc); } bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_filter_aiding_frame_config_error_uncertainty_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_filter_aiding_frame_config_error_uncertainty_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); diff --git a/src/c/mip/definitions/data_filter.h b/src/c/mip/definitions/data_filter.h index 5b3fab150..b1e0bd50d 100644 --- a/src/c/mip/definitions/data_filter.h +++ b/src/c/mip/definitions/data_filter.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,9 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipData_c MIP Data [C] @@ -102,27 +100,49 @@ enum // Shared Type Definitions //////////////////////////////////////////////////////////////////////////////// -typedef uint16_t mip_filter_mode; -static const mip_filter_mode MIP_FILTER_MODE_GX5_STARTUP = 0; ///< -static const mip_filter_mode MIP_FILTER_MODE_GX5_INIT = 1; ///< -static const mip_filter_mode MIP_FILTER_MODE_GX5_RUN_SOLUTION_VALID = 2; ///< -static const mip_filter_mode MIP_FILTER_MODE_GX5_RUN_SOLUTION_ERROR = 3; ///< -static const mip_filter_mode MIP_FILTER_MODE_INIT = 1; ///< -static const mip_filter_mode MIP_FILTER_MODE_VERT_GYRO = 2; ///< -static const mip_filter_mode MIP_FILTER_MODE_AHRS = 3; ///< -static const mip_filter_mode MIP_FILTER_MODE_FULL_NAV = 4; ///< +enum mip_filter_mode +{ + MIP_FILTER_MODE_GX5_STARTUP = 0, ///< + MIP_FILTER_MODE_GX5_INIT = 1, ///< + MIP_FILTER_MODE_GX5_RUN_SOLUTION_VALID = 2, ///< + MIP_FILTER_MODE_GX5_RUN_SOLUTION_ERROR = 3, ///< + MIP_FILTER_MODE_INIT = 1, ///< + MIP_FILTER_MODE_VERT_GYRO = 2, ///< + MIP_FILTER_MODE_AHRS = 3, ///< + MIP_FILTER_MODE_FULL_NAV = 4, ///< +}; +typedef enum mip_filter_mode mip_filter_mode; -void insert_mip_filter_mode(microstrain_serializer* serializer, const mip_filter_mode self); -void extract_mip_filter_mode(microstrain_serializer* serializer, mip_filter_mode* self); +inline void insert_mip_filter_mode(microstrain_serializer* serializer, const mip_filter_mode self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_filter_mode(microstrain_serializer* serializer, mip_filter_mode* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} -typedef uint16_t mip_filter_dynamics_mode; -static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GX5_PORTABLE = 1; ///< -static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GX5_AUTOMOTIVE = 2; ///< -static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GX5_AIRBORNE = 3; ///< -static const mip_filter_dynamics_mode MIP_FILTER_DYNAMICS_MODE_GQ7_DEFAULT = 1; ///< +enum mip_filter_dynamics_mode +{ + MIP_FILTER_DYNAMICS_MODE_GX5_PORTABLE = 1, ///< + MIP_FILTER_DYNAMICS_MODE_GX5_AUTOMOTIVE = 2, ///< + MIP_FILTER_DYNAMICS_MODE_GX5_AIRBORNE = 3, ///< + MIP_FILTER_DYNAMICS_MODE_GQ7_DEFAULT = 1, ///< +}; +typedef enum mip_filter_dynamics_mode mip_filter_dynamics_mode; -void insert_mip_filter_dynamics_mode(microstrain_serializer* serializer, const mip_filter_dynamics_mode self); -void extract_mip_filter_dynamics_mode(microstrain_serializer* serializer, mip_filter_dynamics_mode* self); +inline void insert_mip_filter_dynamics_mode(microstrain_serializer* serializer, const mip_filter_dynamics_mode self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_filter_dynamics_mode(microstrain_serializer* serializer, mip_filter_dynamics_mode* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_filter_status_flags; static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_NONE = 0x0000; @@ -155,26 +175,44 @@ static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_MOUNTING_TRANSF static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_TIME_SYNC_WARNING = 0x0400; ///< No time synchronization pulse detected static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_SOLUTION_ERROR = 0xF000; ///< Filter computation warning flags. If any bits 12-15 are set, and all filter outputs will be invalid. static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_ALL = 0xFFFF; +inline void insert_mip_filter_status_flags(microstrain_serializer* serializer, const mip_filter_status_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_filter_status_flags(microstrain_serializer* serializer, mip_filter_status_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} -void insert_mip_filter_status_flags(microstrain_serializer* serializer, const mip_filter_status_flags self); -void extract_mip_filter_status_flags(microstrain_serializer* serializer, mip_filter_status_flags* self); - -typedef uint8_t mip_filter_aiding_measurement_type; -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_DUAL_ANTENNA = 2; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING = 3; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_PRESSURE = 4; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_MAGNETOMETER = 5; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_SPEED = 6; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_ECEF = 33; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_LLH = 34; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_ECEF = 40; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_NED = 41; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_VEHICLE_FRAME = 42; ///< -static const mip_filter_aiding_measurement_type MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING_TRUE = 49; ///< - -void insert_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self); -void extract_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self); +enum mip_filter_aiding_measurement_type +{ + MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_DUAL_ANTENNA = 2, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING = 3, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_PRESSURE = 4, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_MAGNETOMETER = 5, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_SPEED = 6, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_ECEF = 33, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_LLH = 34, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_ECEF = 40, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_NED = 41, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_VEHICLE_FRAME = 42, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING_TRUE = 49, ///< +}; +typedef enum mip_filter_aiding_measurement_type mip_filter_aiding_measurement_type; + +inline void insert_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint8_t mip_filter_measurement_indicator; static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_NONE = 0x00; @@ -185,9 +223,16 @@ static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_S static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_CONFIGURATION_ERROR = 0x10; ///< static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_MAX_NUM_MEAS_EXCEEDED = 0x20; ///< static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_ALL = 0x3F; - -void insert_mip_filter_measurement_indicator(microstrain_serializer* serializer, const mip_filter_measurement_indicator self); -void extract_mip_filter_measurement_indicator(microstrain_serializer* serializer, mip_filter_measurement_indicator* self); +inline void insert_mip_filter_measurement_indicator(microstrain_serializer* serializer, const mip_filter_measurement_indicator self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_measurement_indicator(microstrain_serializer* serializer, mip_filter_measurement_indicator* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_aid_status_flags; static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_NONE = 0x0000; @@ -208,9 +253,16 @@ static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_BEI_B3 static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_NO_FIX = 0x4000; ///< If 1, this GNSS module is reporting no position fix static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_CONFIG_ERROR = 0x8000; ///< If 1, there is likely an issue with the antenna offset for this GNSS module static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_ALL = 0xFFFF; - -void insert_mip_gnss_aid_status_flags(microstrain_serializer* serializer, const mip_gnss_aid_status_flags self); -void extract_mip_gnss_aid_status_flags(microstrain_serializer* serializer, mip_gnss_aid_status_flags* self); +inline void insert_mip_gnss_aid_status_flags(microstrain_serializer* serializer, const mip_gnss_aid_status_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_aid_status_flags(microstrain_serializer* serializer, mip_gnss_aid_status_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} //////////////////////////////////////////////////////////////////////////////// @@ -229,12 +281,12 @@ struct mip_filter_position_llh_data double longitude; ///< [degrees] double ellipsoid_height; ///< [meters] uint16_t valid_flags; ///< 0 - Invalid, 1 - valid - }; typedef struct mip_filter_position_llh_data mip_filter_position_llh_data; + void insert_mip_filter_position_llh_data(microstrain_serializer* serializer, const mip_filter_position_llh_data* self); void extract_mip_filter_position_llh_data(microstrain_serializer* serializer, mip_filter_position_llh_data* self); -bool extract_mip_filter_position_llh_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_position_llh_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -251,12 +303,12 @@ struct mip_filter_velocity_ned_data float east; ///< [meters/second] float down; ///< [meters/second] uint16_t valid_flags; ///< 0 - Invalid, 1 - valid - }; typedef struct mip_filter_velocity_ned_data mip_filter_velocity_ned_data; + void insert_mip_filter_velocity_ned_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_data* self); void extract_mip_filter_velocity_ned_data(microstrain_serializer* serializer, mip_filter_velocity_ned_data* self); -bool extract_mip_filter_velocity_ned_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_velocity_ned_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -279,12 +331,12 @@ struct mip_filter_attitude_quaternion_data { mip_quatf q; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_attitude_quaternion_data mip_filter_attitude_quaternion_data; + void insert_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, const mip_filter_attitude_quaternion_data* self); void extract_mip_filter_attitude_quaternion_data(microstrain_serializer* serializer, mip_filter_attitude_quaternion_data* self); -bool extract_mip_filter_attitude_quaternion_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -309,12 +361,12 @@ struct mip_filter_attitude_dcm_data { mip_matrix3f dcm; ///< Matrix elements in row-major order. uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_attitude_dcm_data mip_filter_attitude_dcm_data; + void insert_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, const mip_filter_attitude_dcm_data* self); void extract_mip_filter_attitude_dcm_data(microstrain_serializer* serializer, mip_filter_attitude_dcm_data* self); -bool extract_mip_filter_attitude_dcm_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_attitude_dcm_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -332,12 +384,12 @@ struct mip_filter_euler_angles_data float pitch; ///< [radians] float yaw; ///< [radians] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_euler_angles_data mip_filter_euler_angles_data; + void insert_mip_filter_euler_angles_data(microstrain_serializer* serializer, const mip_filter_euler_angles_data* self); void extract_mip_filter_euler_angles_data(microstrain_serializer* serializer, mip_filter_euler_angles_data* self); -bool extract_mip_filter_euler_angles_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_euler_angles_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -352,12 +404,12 @@ struct mip_filter_gyro_bias_data { mip_vector3f bias; ///< (x, y, z) [radians/second] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_gyro_bias_data mip_filter_gyro_bias_data; + void insert_mip_filter_gyro_bias_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_data* self); void extract_mip_filter_gyro_bias_data(microstrain_serializer* serializer, mip_filter_gyro_bias_data* self); -bool extract_mip_filter_gyro_bias_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_gyro_bias_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -372,12 +424,12 @@ struct mip_filter_accel_bias_data { mip_vector3f bias; ///< (x, y, z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_accel_bias_data mip_filter_accel_bias_data; + void insert_mip_filter_accel_bias_data(microstrain_serializer* serializer, const mip_filter_accel_bias_data* self); void extract_mip_filter_accel_bias_data(microstrain_serializer* serializer, mip_filter_accel_bias_data* self); -bool extract_mip_filter_accel_bias_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_accel_bias_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -394,12 +446,12 @@ struct mip_filter_position_llh_uncertainty_data float east; ///< [meters] float down; ///< [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_position_llh_uncertainty_data mip_filter_position_llh_uncertainty_data; + void insert_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, const mip_filter_position_llh_uncertainty_data* self); void extract_mip_filter_position_llh_uncertainty_data(microstrain_serializer* serializer, mip_filter_position_llh_uncertainty_data* self); -bool extract_mip_filter_position_llh_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_position_llh_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -416,12 +468,12 @@ struct mip_filter_velocity_ned_uncertainty_data float east; ///< [meters/second] float down; ///< [meters/second] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_velocity_ned_uncertainty_data mip_filter_velocity_ned_uncertainty_data; + void insert_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, const mip_filter_velocity_ned_uncertainty_data* self); void extract_mip_filter_velocity_ned_uncertainty_data(microstrain_serializer* serializer, mip_filter_velocity_ned_uncertainty_data* self); -bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -439,12 +491,12 @@ struct mip_filter_euler_angles_uncertainty_data float pitch; ///< [radians] float yaw; ///< [radians] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_euler_angles_uncertainty_data mip_filter_euler_angles_uncertainty_data; + void insert_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, const mip_filter_euler_angles_uncertainty_data* self); void extract_mip_filter_euler_angles_uncertainty_data(microstrain_serializer* serializer, mip_filter_euler_angles_uncertainty_data* self); -bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -459,12 +511,12 @@ struct mip_filter_gyro_bias_uncertainty_data { mip_vector3f bias_uncert; ///< (x,y,z) [radians/sec] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_gyro_bias_uncertainty_data mip_filter_gyro_bias_uncertainty_data; + void insert_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_bias_uncertainty_data* self); void extract_mip_filter_gyro_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_bias_uncertainty_data* self); -bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -479,12 +531,12 @@ struct mip_filter_accel_bias_uncertainty_data { mip_vector3f bias_uncert; ///< (x,y,z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_accel_bias_uncertainty_data mip_filter_accel_bias_uncertainty_data; + void insert_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_bias_uncertainty_data* self); void extract_mip_filter_accel_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_bias_uncertainty_data* self); -bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -506,12 +558,12 @@ struct mip_filter_timestamp_data double tow; ///< GPS Time of Week [seconds] uint16_t week_number; ///< GPS Week Number since 1980 [weeks] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_timestamp_data mip_filter_timestamp_data; + void insert_mip_filter_timestamp_data(microstrain_serializer* serializer, const mip_filter_timestamp_data* self); void extract_mip_filter_timestamp_data(microstrain_serializer* serializer, mip_filter_timestamp_data* self); -bool extract_mip_filter_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_timestamp_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -527,12 +579,12 @@ struct mip_filter_status_data mip_filter_mode filter_state; ///< Device-specific filter state. Please consult the user manual for definition. mip_filter_dynamics_mode dynamics_mode; ///< Device-specific dynamics mode. Please consult the user manual for definition. mip_filter_status_flags status_flags; ///< Device-specific status flags. Please consult the user manual for definition. - }; typedef struct mip_filter_status_data mip_filter_status_data; + void insert_mip_filter_status_data(microstrain_serializer* serializer, const mip_filter_status_data* self); void extract_mip_filter_status_data(microstrain_serializer* serializer, mip_filter_status_data* self); -bool extract_mip_filter_status_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -548,12 +600,12 @@ struct mip_filter_linear_accel_data { mip_vector3f accel; ///< (x,y,z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_linear_accel_data mip_filter_linear_accel_data; + void insert_mip_filter_linear_accel_data(microstrain_serializer* serializer, const mip_filter_linear_accel_data* self); void extract_mip_filter_linear_accel_data(microstrain_serializer* serializer, mip_filter_linear_accel_data* self); -bool extract_mip_filter_linear_accel_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_linear_accel_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -568,12 +620,12 @@ struct mip_filter_gravity_vector_data { mip_vector3f gravity; ///< (x, y, z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_gravity_vector_data mip_filter_gravity_vector_data; + void insert_mip_filter_gravity_vector_data(microstrain_serializer* serializer, const mip_filter_gravity_vector_data* self); void extract_mip_filter_gravity_vector_data(microstrain_serializer* serializer, mip_filter_gravity_vector_data* self); -bool extract_mip_filter_gravity_vector_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_gravity_vector_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -588,12 +640,12 @@ struct mip_filter_comp_accel_data { mip_vector3f accel; ///< (x,y,z) [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_comp_accel_data mip_filter_comp_accel_data; + void insert_mip_filter_comp_accel_data(microstrain_serializer* serializer, const mip_filter_comp_accel_data* self); void extract_mip_filter_comp_accel_data(microstrain_serializer* serializer, mip_filter_comp_accel_data* self); -bool extract_mip_filter_comp_accel_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_comp_accel_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -608,12 +660,12 @@ struct mip_filter_comp_angular_rate_data { mip_vector3f gyro; ///< (x, y, z) [radians/second] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_comp_angular_rate_data mip_filter_comp_angular_rate_data; + void insert_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, const mip_filter_comp_angular_rate_data* self); void extract_mip_filter_comp_angular_rate_data(microstrain_serializer* serializer, mip_filter_comp_angular_rate_data* self); -bool extract_mip_filter_comp_angular_rate_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_comp_angular_rate_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -628,12 +680,12 @@ struct mip_filter_quaternion_attitude_uncertainty_data { mip_quatf q; ///< [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_quaternion_attitude_uncertainty_data mip_filter_quaternion_attitude_uncertainty_data; + void insert_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, const mip_filter_quaternion_attitude_uncertainty_data* self); void extract_mip_filter_quaternion_attitude_uncertainty_data(microstrain_serializer* serializer, mip_filter_quaternion_attitude_uncertainty_data* self); -bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -648,12 +700,12 @@ struct mip_filter_wgs84_gravity_mag_data { float magnitude; ///< [meters/second^2] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_wgs84_gravity_mag_data mip_filter_wgs84_gravity_mag_data; + void insert_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, const mip_filter_wgs84_gravity_mag_data* self); void extract_mip_filter_wgs84_gravity_mag_data(microstrain_serializer* serializer, mip_filter_wgs84_gravity_mag_data* self); -bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -667,12 +719,27 @@ bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const struct mip_field /// ///@{ -typedef uint16_t mip_filter_heading_update_state_data_heading_source; -static const mip_filter_heading_update_state_data_heading_source MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_NONE = 0; ///< -static const mip_filter_heading_update_state_data_heading_source MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_MAGNETOMETER = 1; ///< -static const mip_filter_heading_update_state_data_heading_source MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_GNSS_VELOCITY_VECTOR = 2; ///< -static const mip_filter_heading_update_state_data_heading_source MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_EXTERNAL = 4; ///< -static const mip_filter_heading_update_state_data_heading_source MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_DUAL_ANTENNA = 8; ///< +enum mip_filter_heading_update_state_data_heading_source +{ + MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_NONE = 0, ///< + MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_MAGNETOMETER = 1, ///< + MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_GNSS_VELOCITY_VECTOR = 2, ///< + MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_EXTERNAL = 4, ///< + MIP_FILTER_HEADING_UPDATE_STATE_DATA_HEADING_SOURCE_DUAL_ANTENNA = 8, ///< +}; +typedef enum mip_filter_heading_update_state_data_heading_source mip_filter_heading_update_state_data_heading_source; + +inline void insert_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_filter_heading_update_state_data { @@ -680,15 +747,12 @@ struct mip_filter_heading_update_state_data float heading_1sigma; ///< [radians] mip_filter_heading_update_state_data_heading_source source; uint16_t valid_flags; ///< 1 if a valid heading update was received in 2 seconds, 0 otherwise. - }; typedef struct mip_filter_heading_update_state_data mip_filter_heading_update_state_data; + void insert_mip_filter_heading_update_state_data(microstrain_serializer* serializer, const mip_filter_heading_update_state_data* self); void extract_mip_filter_heading_update_state_data(microstrain_serializer* serializer, mip_filter_heading_update_state_data* self); -bool extract_mip_filter_heading_update_state_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self); -void extract_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self); +bool extract_mip_filter_heading_update_state_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -708,12 +772,12 @@ struct mip_filter_magnetic_model_data float inclination; ///< [radians] float declination; ///< [radians] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_magnetic_model_data mip_filter_magnetic_model_data; + void insert_mip_filter_magnetic_model_data(microstrain_serializer* serializer, const mip_filter_magnetic_model_data* self); void extract_mip_filter_magnetic_model_data(microstrain_serializer* serializer, mip_filter_magnetic_model_data* self); -bool extract_mip_filter_magnetic_model_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_magnetic_model_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -728,12 +792,12 @@ struct mip_filter_accel_scale_factor_data { mip_vector3f scale_factor; ///< (x,y,z) [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_accel_scale_factor_data mip_filter_accel_scale_factor_data; + void insert_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_data* self); void extract_mip_filter_accel_scale_factor_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_data* self); -bool extract_mip_filter_accel_scale_factor_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_accel_scale_factor_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -748,12 +812,12 @@ struct mip_filter_accel_scale_factor_uncertainty_data { mip_vector3f scale_factor_uncert; ///< (x,y,z) [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_accel_scale_factor_uncertainty_data mip_filter_accel_scale_factor_uncertainty_data; + void insert_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_accel_scale_factor_uncertainty_data* self); void extract_mip_filter_accel_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_accel_scale_factor_uncertainty_data* self); -bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -768,12 +832,12 @@ struct mip_filter_gyro_scale_factor_data { mip_vector3f scale_factor; ///< (x,y,z) [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_gyro_scale_factor_data mip_filter_gyro_scale_factor_data; + void insert_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_data* self); void extract_mip_filter_gyro_scale_factor_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_data* self); -bool extract_mip_filter_gyro_scale_factor_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_gyro_scale_factor_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -788,12 +852,12 @@ struct mip_filter_gyro_scale_factor_uncertainty_data { mip_vector3f scale_factor_uncert; ///< (x,y,z) [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_gyro_scale_factor_uncertainty_data mip_filter_gyro_scale_factor_uncertainty_data; + void insert_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, const mip_filter_gyro_scale_factor_uncertainty_data* self); void extract_mip_filter_gyro_scale_factor_uncertainty_data(microstrain_serializer* serializer, mip_filter_gyro_scale_factor_uncertainty_data* self); -bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -808,12 +872,12 @@ struct mip_filter_mag_bias_data { mip_vector3f bias; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_mag_bias_data mip_filter_mag_bias_data; + void insert_mip_filter_mag_bias_data(microstrain_serializer* serializer, const mip_filter_mag_bias_data* self); void extract_mip_filter_mag_bias_data(microstrain_serializer* serializer, mip_filter_mag_bias_data* self); -bool extract_mip_filter_mag_bias_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_mag_bias_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -828,12 +892,12 @@ struct mip_filter_mag_bias_uncertainty_data { mip_vector3f bias_uncert; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_mag_bias_uncertainty_data mip_filter_mag_bias_uncertainty_data; + void insert_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, const mip_filter_mag_bias_uncertainty_data* self); void extract_mip_filter_mag_bias_uncertainty_data(microstrain_serializer* serializer, mip_filter_mag_bias_uncertainty_data* self); -bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -854,12 +918,12 @@ struct mip_filter_standard_atmosphere_data float standard_pressure; ///< [milliBar] float standard_density; ///< [kilogram/meter^3] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_standard_atmosphere_data mip_filter_standard_atmosphere_data; + void insert_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, const mip_filter_standard_atmosphere_data* self); void extract_mip_filter_standard_atmosphere_data(microstrain_serializer* serializer, mip_filter_standard_atmosphere_data* self); -bool extract_mip_filter_standard_atmosphere_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_standard_atmosphere_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -878,12 +942,12 @@ struct mip_filter_pressure_altitude_data { float pressure_altitude; ///< [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_pressure_altitude_data mip_filter_pressure_altitude_data; + void insert_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, const mip_filter_pressure_altitude_data* self); void extract_mip_filter_pressure_altitude_data(microstrain_serializer* serializer, mip_filter_pressure_altitude_data* self); -bool extract_mip_filter_pressure_altitude_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_pressure_altitude_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -897,12 +961,12 @@ struct mip_filter_density_altitude_data { float density_altitude; ///< m uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_density_altitude_data mip_filter_density_altitude_data; + void insert_mip_filter_density_altitude_data(microstrain_serializer* serializer, const mip_filter_density_altitude_data* self); void extract_mip_filter_density_altitude_data(microstrain_serializer* serializer, mip_filter_density_altitude_data* self); -bool extract_mip_filter_density_altitude_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_density_altitude_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -919,12 +983,12 @@ struct mip_filter_antenna_offset_correction_data { mip_vector3f offset; ///< (x,y,z) [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_antenna_offset_correction_data mip_filter_antenna_offset_correction_data; + void insert_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_data* self); void extract_mip_filter_antenna_offset_correction_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_data* self); -bool extract_mip_filter_antenna_offset_correction_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_antenna_offset_correction_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -939,12 +1003,12 @@ struct mip_filter_antenna_offset_correction_uncertainty_data { mip_vector3f offset_uncert; ///< (x,y,z) [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_antenna_offset_correction_uncertainty_data mip_filter_antenna_offset_correction_uncertainty_data; + void insert_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_antenna_offset_correction_uncertainty_data* self); void extract_mip_filter_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_antenna_offset_correction_uncertainty_data* self); -bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -962,12 +1026,12 @@ struct mip_filter_multi_antenna_offset_correction_data uint8_t receiver_id; ///< Receiver ID for the receiver to which the antenna is attached mip_vector3f offset; ///< (x,y,z) [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_multi_antenna_offset_correction_data mip_filter_multi_antenna_offset_correction_data; + void insert_mip_filter_multi_antenna_offset_correction_data(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_data* self); void extract_mip_filter_multi_antenna_offset_correction_data(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_data* self); -bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -983,12 +1047,12 @@ struct mip_filter_multi_antenna_offset_correction_uncertainty_data uint8_t receiver_id; ///< Receiver ID for the receiver to which the antenna is attached mip_vector3f offset_uncert; ///< (x,y,z) [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_multi_antenna_offset_correction_uncertainty_data mip_filter_multi_antenna_offset_correction_uncertainty_data; + void insert_mip_filter_multi_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_correction_uncertainty_data* self); void extract_mip_filter_multi_antenna_offset_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_correction_uncertainty_data* self); -bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1005,12 +1069,12 @@ struct mip_filter_magnetometer_offset_data { mip_vector3f hard_iron; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_magnetometer_offset_data mip_filter_magnetometer_offset_data; + void insert_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_data* self); void extract_mip_filter_magnetometer_offset_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_data* self); -bool extract_mip_filter_magnetometer_offset_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_magnetometer_offset_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1027,12 +1091,12 @@ struct mip_filter_magnetometer_matrix_data { mip_matrix3f soft_iron; ///< Row-major [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_magnetometer_matrix_data mip_filter_magnetometer_matrix_data; + void insert_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_data* self); void extract_mip_filter_magnetometer_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_data* self); -bool extract_mip_filter_magnetometer_matrix_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_magnetometer_matrix_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1047,12 +1111,12 @@ struct mip_filter_magnetometer_offset_uncertainty_data { mip_vector3f hard_iron_uncertainty; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_magnetometer_offset_uncertainty_data mip_filter_magnetometer_offset_uncertainty_data; + void insert_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_offset_uncertainty_data* self); void extract_mip_filter_magnetometer_offset_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_offset_uncertainty_data* self); -bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1067,12 +1131,12 @@ struct mip_filter_magnetometer_matrix_uncertainty_data { mip_matrix3f soft_iron_uncertainty; ///< Row-major [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_magnetometer_matrix_uncertainty_data mip_filter_magnetometer_matrix_uncertainty_data; + void insert_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, const mip_filter_magnetometer_matrix_uncertainty_data* self); void extract_mip_filter_magnetometer_matrix_uncertainty_data(microstrain_serializer* serializer, mip_filter_magnetometer_matrix_uncertainty_data* self); -bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1086,12 +1150,12 @@ struct mip_filter_magnetometer_covariance_matrix_data { mip_matrix3f covariance; uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_magnetometer_covariance_matrix_data mip_filter_magnetometer_covariance_matrix_data; + void insert_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, const mip_filter_magnetometer_covariance_matrix_data* self); void extract_mip_filter_magnetometer_covariance_matrix_data(microstrain_serializer* serializer, mip_filter_magnetometer_covariance_matrix_data* self); -bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1106,12 +1170,12 @@ struct mip_filter_magnetometer_residual_vector_data { mip_vector3f residual; ///< (x,y,z) [Gauss] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_magnetometer_residual_vector_data mip_filter_magnetometer_residual_vector_data; + void insert_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, const mip_filter_magnetometer_residual_vector_data* self); void extract_mip_filter_magnetometer_residual_vector_data(microstrain_serializer* serializer, mip_filter_magnetometer_residual_vector_data* self); -bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1128,12 +1192,12 @@ struct mip_filter_clock_correction_data float bias; ///< [seconds] float bias_drift; ///< [seconds/second] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_clock_correction_data mip_filter_clock_correction_data; + void insert_mip_filter_clock_correction_data(microstrain_serializer* serializer, const mip_filter_clock_correction_data* self); void extract_mip_filter_clock_correction_data(microstrain_serializer* serializer, mip_filter_clock_correction_data* self); -bool extract_mip_filter_clock_correction_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_clock_correction_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1150,12 +1214,12 @@ struct mip_filter_clock_correction_uncertainty_data float bias_uncertainty; ///< [seconds] float bias_drift_uncertainty; ///< [seconds/second] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_clock_correction_uncertainty_data mip_filter_clock_correction_uncertainty_data; + void insert_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, const mip_filter_clock_correction_uncertainty_data* self); void extract_mip_filter_clock_correction_uncertainty_data(microstrain_serializer* serializer, mip_filter_clock_correction_uncertainty_data* self); -bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1172,12 +1236,12 @@ struct mip_filter_gnss_pos_aid_status_data float time_of_week; ///< Last GNSS aiding measurement time of week [seconds] mip_gnss_aid_status_flags status; ///< Aiding measurement status bitfield uint8_t reserved[8]; - }; typedef struct mip_filter_gnss_pos_aid_status_data mip_filter_gnss_pos_aid_status_data; + void insert_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, const mip_filter_gnss_pos_aid_status_data* self); void extract_mip_filter_gnss_pos_aid_status_data(microstrain_serializer* serializer, mip_filter_gnss_pos_aid_status_data* self); -bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1193,12 +1257,12 @@ struct mip_filter_gnss_att_aid_status_data float time_of_week; ///< Last valid aiding measurement time of week [seconds] [processed instead of measured?] mip_gnss_aid_status_flags status; ///< Last valid aiding measurement status bitfield uint8_t reserved[8]; - }; typedef struct mip_filter_gnss_att_aid_status_data mip_filter_gnss_att_aid_status_data; + void insert_mip_filter_gnss_att_aid_status_data(microstrain_serializer* serializer, const mip_filter_gnss_att_aid_status_data* self); void extract_mip_filter_gnss_att_aid_status_data(microstrain_serializer* serializer, mip_filter_gnss_att_aid_status_data* self); -bool extract_mip_filter_gnss_att_aid_status_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_gnss_att_aid_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1209,24 +1273,36 @@ bool extract_mip_filter_gnss_att_aid_status_data_from_field(const struct mip_fie /// ///@{ -typedef uint8_t mip_filter_head_aid_status_data_heading_aid_type; -static const mip_filter_head_aid_status_data_heading_aid_type MIP_FILTER_HEAD_AID_STATUS_DATA_HEADING_AID_TYPE_DUAL_ANTENNA = 1; ///< -static const mip_filter_head_aid_status_data_heading_aid_type MIP_FILTER_HEAD_AID_STATUS_DATA_HEADING_AID_TYPE_EXTERNAL_MESSAGE = 2; ///< +enum mip_filter_head_aid_status_data_heading_aid_type +{ + MIP_FILTER_HEAD_AID_STATUS_DATA_HEADING_AID_TYPE_DUAL_ANTENNA = 1, ///< + MIP_FILTER_HEAD_AID_STATUS_DATA_HEADING_AID_TYPE_EXTERNAL_MESSAGE = 2, ///< +}; +typedef enum mip_filter_head_aid_status_data_heading_aid_type mip_filter_head_aid_status_data_heading_aid_type; + +inline void insert_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + struct mip_filter_head_aid_status_data { float time_of_week; ///< Last valid aiding measurement time of week [seconds] [processed instead of measured?] mip_filter_head_aid_status_data_heading_aid_type type; ///< 1 - Dual antenna, 2 - External heading message (user supplied) float reserved[2]; - }; typedef struct mip_filter_head_aid_status_data mip_filter_head_aid_status_data; + void insert_mip_filter_head_aid_status_data(microstrain_serializer* serializer, const mip_filter_head_aid_status_data* self); void extract_mip_filter_head_aid_status_data(microstrain_serializer* serializer, mip_filter_head_aid_status_data* self); -bool extract_mip_filter_head_aid_status_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self); -void extract_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self); +bool extract_mip_filter_head_aid_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1241,12 +1317,12 @@ struct mip_filter_rel_pos_ned_data { mip_vector3d relative_position; ///< [meters, NED] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_rel_pos_ned_data mip_filter_rel_pos_ned_data; + void insert_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, const mip_filter_rel_pos_ned_data* self); void extract_mip_filter_rel_pos_ned_data(microstrain_serializer* serializer, mip_filter_rel_pos_ned_data* self); -bool extract_mip_filter_rel_pos_ned_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_rel_pos_ned_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1261,12 +1337,12 @@ struct mip_filter_ecef_pos_data { mip_vector3d position_ecef; ///< [meters, ECEF] uint16_t valid_flags; ///< 0 - invalid, 1 valid - }; typedef struct mip_filter_ecef_pos_data mip_filter_ecef_pos_data; + void insert_mip_filter_ecef_pos_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_data* self); void extract_mip_filter_ecef_pos_data(microstrain_serializer* serializer, mip_filter_ecef_pos_data* self); -bool extract_mip_filter_ecef_pos_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_ecef_pos_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1281,12 +1357,12 @@ struct mip_filter_ecef_vel_data { mip_vector3f velocity_ecef; ///< [meters/second, ECEF] uint16_t valid_flags; ///< 0 - invalid, 1 valid - }; typedef struct mip_filter_ecef_vel_data mip_filter_ecef_vel_data; + void insert_mip_filter_ecef_vel_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_data* self); void extract_mip_filter_ecef_vel_data(microstrain_serializer* serializer, mip_filter_ecef_vel_data* self); -bool extract_mip_filter_ecef_vel_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_ecef_vel_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1301,12 +1377,12 @@ struct mip_filter_ecef_pos_uncertainty_data { mip_vector3f pos_uncertainty; ///< [meters] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_ecef_pos_uncertainty_data mip_filter_ecef_pos_uncertainty_data; + void insert_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_pos_uncertainty_data* self); void extract_mip_filter_ecef_pos_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_pos_uncertainty_data* self); -bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1321,12 +1397,12 @@ struct mip_filter_ecef_vel_uncertainty_data { mip_vector3f vel_uncertainty; ///< [meters/second] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_ecef_vel_uncertainty_data mip_filter_ecef_vel_uncertainty_data; + void insert_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, const mip_filter_ecef_vel_uncertainty_data* self); void extract_mip_filter_ecef_vel_uncertainty_data(microstrain_serializer* serializer, mip_filter_ecef_vel_uncertainty_data* self); -bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1343,12 +1419,12 @@ struct mip_filter_aiding_measurement_summary_data uint8_t source; mip_filter_aiding_measurement_type type; ///< (see product manual for supported types) Note: values 0x20 and above correspond to commanded aiding measurements in the 0x13 Aiding command set. mip_filter_measurement_indicator indicator; - }; typedef struct mip_filter_aiding_measurement_summary_data mip_filter_aiding_measurement_summary_data; + void insert_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, const mip_filter_aiding_measurement_summary_data* self); void extract_mip_filter_aiding_measurement_summary_data(microstrain_serializer* serializer, mip_filter_aiding_measurement_summary_data* self); -bool extract_mip_filter_aiding_measurement_summary_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_aiding_measurement_summary_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1363,12 +1439,12 @@ struct mip_filter_odometer_scale_factor_error_data { float scale_factor_error; ///< [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_odometer_scale_factor_error_data mip_filter_odometer_scale_factor_error_data; + void insert_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_data* self); void extract_mip_filter_odometer_scale_factor_error_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_data* self); -bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1383,12 +1459,12 @@ struct mip_filter_odometer_scale_factor_error_uncertainty_data { float scale_factor_error_uncertainty; ///< [dimensionless] uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_odometer_scale_factor_error_uncertainty_data mip_filter_odometer_scale_factor_error_uncertainty_data; + void insert_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, const mip_filter_odometer_scale_factor_error_uncertainty_data* self); void extract_mip_filter_odometer_scale_factor_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_odometer_scale_factor_error_uncertainty_data* self); -bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1399,10 +1475,24 @@ bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field( /// ///@{ -typedef uint8_t mip_filter_gnss_dual_antenna_status_data_fix_type; -static const mip_filter_gnss_dual_antenna_status_data_fix_type MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_FIX_TYPE_FIX_NONE = 0; ///< -static const mip_filter_gnss_dual_antenna_status_data_fix_type MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_FIX_TYPE_FIX_DA_FLOAT = 1; ///< -static const mip_filter_gnss_dual_antenna_status_data_fix_type MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_FIX_TYPE_FIX_DA_FIXED = 2; ///< +enum mip_filter_gnss_dual_antenna_status_data_fix_type +{ + MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_FIX_TYPE_FIX_NONE = 0, ///< + MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_FIX_TYPE_FIX_DA_FLOAT = 1, ///< + MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_FIX_TYPE_FIX_DA_FIXED = 2, ///< +}; +typedef enum mip_filter_gnss_dual_antenna_status_data_fix_type mip_filter_gnss_dual_antenna_status_data_fix_type; + +inline void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags; static const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_DUAL_ANTENNA_STATUS_FLAGS_NONE = 0x0000; @@ -1410,6 +1500,17 @@ static const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags static const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_DUAL_ANTENNA_STATUS_FLAGS_RCV_2_DATA_VALID = 0x0002; ///< static const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_DUAL_ANTENNA_STATUS_FLAGS_ANTENNA_OFFSETS_VALID = 0x0004; ///< static const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_DUAL_ANTENNA_STATUS_FLAGS_ALL = 0x0007; +inline void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_filter_gnss_dual_antenna_status_data { @@ -1419,18 +1520,12 @@ struct mip_filter_gnss_dual_antenna_status_data mip_filter_gnss_dual_antenna_status_data_fix_type fix_type; ///< Fix type indicator mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags status_flags; uint16_t valid_flags; ///< 0 - invalid, 1 - valid - }; typedef struct mip_filter_gnss_dual_antenna_status_data mip_filter_gnss_dual_antenna_status_data; + void insert_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data* self); void extract_mip_filter_gnss_dual_antenna_status_data(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data* self); -bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self); -void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self); - -void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self); -void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self); +bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1448,12 +1543,12 @@ struct mip_filter_aiding_frame_config_error_data uint8_t frame_id; ///< Frame ID for the receiver to which the antenna is attached mip_vector3f translation; ///< Translation config X, Y, and Z (m). mip_quatf attitude; ///< Attitude quaternion - }; typedef struct mip_filter_aiding_frame_config_error_data mip_filter_aiding_frame_config_error_data; + void insert_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_data* self); void extract_mip_filter_aiding_frame_config_error_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_data* self); -bool extract_mip_filter_aiding_frame_config_error_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_aiding_frame_config_error_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1471,12 +1566,12 @@ struct mip_filter_aiding_frame_config_error_uncertainty_data uint8_t frame_id; ///< Frame ID for the receiver to which the antenna is attached mip_vector3f translation_unc; ///< Translation uncertaint X, Y, and Z (m). mip_vector3f attitude_unc; ///< Attitude uncertainty, X, Y, and Z (radians). - }; typedef struct mip_filter_aiding_frame_config_error_uncertainty_data mip_filter_aiding_frame_config_error_uncertainty_data; + void insert_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_serializer* serializer, const mip_filter_aiding_frame_config_error_uncertainty_data* self); void extract_mip_filter_aiding_frame_config_error_uncertainty_data(microstrain_serializer* serializer, mip_filter_aiding_frame_config_error_uncertainty_data* self); -bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(const mip_field_view* field, void* ptr); ///@} diff --git a/src/c/mip/definitions/data_gnss.c b/src/c/mip/definitions/data_gnss.c index 177db782a..4aae568b7 100644 --- a/src/c/mip/definitions/data_gnss.c +++ b/src/c/mip/definitions/data_gnss.c @@ -13,47 +13,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; - - -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - -void insert_mip_gnss_constellation_id(microstrain_serializer* serializer, const mip_gnss_constellation_id self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_constellation_id(microstrain_serializer* serializer, mip_gnss_constellation_id* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_signal_id(microstrain_serializer* serializer, const mip_gnss_signal_id self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_signal_id(microstrain_serializer* serializer, mip_gnss_signal_id* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_sbas_system(microstrain_serializer* serializer, const mip_sbas_system self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_sbas_system(microstrain_serializer* serializer, mip_sbas_system* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} //////////////////////////////////////////////////////////////////////////////// @@ -63,15 +22,15 @@ void extract_mip_sbas_system(microstrain_serializer* serializer, mip_sbas_system void insert_mip_gnss_pos_llh_data(microstrain_serializer* serializer, const mip_gnss_pos_llh_data* self) { microstrain_insert_double(serializer, self->latitude); - + microstrain_insert_double(serializer, self->longitude); - + microstrain_insert_double(serializer, self->ellipsoid_height); - + microstrain_insert_double(serializer, self->msl_height); - + microstrain_insert_float(serializer, self->horizontal_accuracy); - + microstrain_insert_float(serializer, self->vertical_accuracy); insert_mip_gnss_pos_llh_data_valid_flags(serializer, self->valid_flags); @@ -80,15 +39,15 @@ void insert_mip_gnss_pos_llh_data(microstrain_serializer* serializer, const mip_ void extract_mip_gnss_pos_llh_data(microstrain_serializer* serializer, mip_gnss_pos_llh_data* self) { microstrain_extract_double(serializer, &self->latitude); - + microstrain_extract_double(serializer, &self->longitude); - + microstrain_extract_double(serializer, &self->ellipsoid_height); - + microstrain_extract_double(serializer, &self->msl_height); - + microstrain_extract_float(serializer, &self->horizontal_accuracy); - + microstrain_extract_float(serializer, &self->vertical_accuracy); extract_mip_gnss_pos_llh_data_valid_flags(serializer, &self->valid_flags); @@ -98,28 +57,16 @@ bool extract_mip_gnss_pos_llh_data_from_field(const mip_field_view* field, void* { assert(ptr); mip_gnss_pos_llh_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_pos_llh_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_double(serializer, self->x[i]); - + insert_mip_vector3d(serializer, self->x); + microstrain_insert_float(serializer, self->x_accuracy); insert_mip_gnss_pos_ecef_data_valid_flags(serializer, self->valid_flags); @@ -127,9 +74,8 @@ void insert_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, const mip } void extract_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, mip_gnss_pos_ecef_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_double(serializer, &self->x[i]); - + extract_mip_vector3d(serializer, self->x); + microstrain_extract_float(serializer, &self->x_accuracy); extract_mip_gnss_pos_ecef_data_valid_flags(serializer, &self->valid_flags); @@ -139,36 +85,24 @@ bool extract_mip_gnss_pos_ecef_data_from_field(const mip_field_view* field, void { assert(ptr); mip_gnss_pos_ecef_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_pos_ecef_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_vel_ned_data(microstrain_serializer* serializer, const mip_gnss_vel_ned_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->v[i]); - + insert_mip_vector3f(serializer, self->v); + microstrain_insert_float(serializer, self->speed); - + microstrain_insert_float(serializer, self->ground_speed); - + microstrain_insert_float(serializer, self->heading); - + microstrain_insert_float(serializer, self->speed_accuracy); - + microstrain_insert_float(serializer, self->heading_accuracy); insert_mip_gnss_vel_ned_data_valid_flags(serializer, self->valid_flags); @@ -176,17 +110,16 @@ void insert_mip_gnss_vel_ned_data(microstrain_serializer* serializer, const mip_ } void extract_mip_gnss_vel_ned_data(microstrain_serializer* serializer, mip_gnss_vel_ned_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->v[i]); - + extract_mip_vector3f(serializer, self->v); + microstrain_extract_float(serializer, &self->speed); - + microstrain_extract_float(serializer, &self->ground_speed); - + microstrain_extract_float(serializer, &self->heading); - + microstrain_extract_float(serializer, &self->speed_accuracy); - + microstrain_extract_float(serializer, &self->heading_accuracy); extract_mip_gnss_vel_ned_data_valid_flags(serializer, &self->valid_flags); @@ -196,28 +129,16 @@ bool extract_mip_gnss_vel_ned_data_from_field(const mip_field_view* field, void* { assert(ptr); mip_gnss_vel_ned_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_vel_ned_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->v[i]); - + insert_mip_vector3f(serializer, self->v); + microstrain_insert_float(serializer, self->v_accuracy); insert_mip_gnss_vel_ecef_data_valid_flags(serializer, self->valid_flags); @@ -225,9 +146,8 @@ void insert_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, const mip } void extract_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, mip_gnss_vel_ecef_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->v[i]); - + extract_mip_vector3f(serializer, self->v); + microstrain_extract_float(serializer, &self->v_accuracy); extract_mip_gnss_vel_ecef_data_valid_flags(serializer, &self->valid_flags); @@ -237,37 +157,26 @@ bool extract_mip_gnss_vel_ecef_data_from_field(const mip_field_view* field, void { assert(ptr); mip_gnss_vel_ecef_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_vel_ecef_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_dop_data(microstrain_serializer* serializer, const mip_gnss_dop_data* self) { microstrain_insert_float(serializer, self->gdop); - + microstrain_insert_float(serializer, self->pdop); - + microstrain_insert_float(serializer, self->hdop); - + microstrain_insert_float(serializer, self->vdop); - + microstrain_insert_float(serializer, self->tdop); - + microstrain_insert_float(serializer, self->ndop); - + microstrain_insert_float(serializer, self->edop); insert_mip_gnss_dop_data_valid_flags(serializer, self->valid_flags); @@ -276,17 +185,17 @@ void insert_mip_gnss_dop_data(microstrain_serializer* serializer, const mip_gnss void extract_mip_gnss_dop_data(microstrain_serializer* serializer, mip_gnss_dop_data* self) { microstrain_extract_float(serializer, &self->gdop); - + microstrain_extract_float(serializer, &self->pdop); - + microstrain_extract_float(serializer, &self->hdop); - + microstrain_extract_float(serializer, &self->vdop); - + microstrain_extract_float(serializer, &self->tdop); - + microstrain_extract_float(serializer, &self->ndop); - + microstrain_extract_float(serializer, &self->edop); extract_mip_gnss_dop_data_valid_flags(serializer, &self->valid_flags); @@ -296,37 +205,26 @@ bool extract_mip_gnss_dop_data_from_field(const mip_field_view* field, void* ptr { assert(ptr); mip_gnss_dop_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_dop_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_utc_time_data(microstrain_serializer* serializer, const mip_gnss_utc_time_data* self) { microstrain_insert_u16(serializer, self->year); - + microstrain_insert_u8(serializer, self->month); - + microstrain_insert_u8(serializer, self->day); - + microstrain_insert_u8(serializer, self->hour); - + microstrain_insert_u8(serializer, self->min); - + microstrain_insert_u8(serializer, self->sec); - + microstrain_insert_u32(serializer, self->msec); insert_mip_gnss_utc_time_data_valid_flags(serializer, self->valid_flags); @@ -335,17 +233,17 @@ void insert_mip_gnss_utc_time_data(microstrain_serializer* serializer, const mip void extract_mip_gnss_utc_time_data(microstrain_serializer* serializer, mip_gnss_utc_time_data* self) { microstrain_extract_u16(serializer, &self->year); - + microstrain_extract_u8(serializer, &self->month); - + microstrain_extract_u8(serializer, &self->day); - + microstrain_extract_u8(serializer, &self->hour); - + microstrain_extract_u8(serializer, &self->min); - + microstrain_extract_u8(serializer, &self->sec); - + microstrain_extract_u32(serializer, &self->msec); extract_mip_gnss_utc_time_data_valid_flags(serializer, &self->valid_flags); @@ -355,27 +253,16 @@ bool extract_mip_gnss_utc_time_data_from_field(const mip_field_view* field, void { assert(ptr); mip_gnss_utc_time_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_utc_time_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_gps_time_data(microstrain_serializer* serializer, const mip_gnss_gps_time_data* self) { microstrain_insert_double(serializer, self->tow); - + microstrain_insert_u16(serializer, self->week_number); insert_mip_gnss_gps_time_data_valid_flags(serializer, self->valid_flags); @@ -384,7 +271,7 @@ void insert_mip_gnss_gps_time_data(microstrain_serializer* serializer, const mip void extract_mip_gnss_gps_time_data(microstrain_serializer* serializer, mip_gnss_gps_time_data* self) { microstrain_extract_double(serializer, &self->tow); - + microstrain_extract_u16(serializer, &self->week_number); extract_mip_gnss_gps_time_data_valid_flags(serializer, &self->valid_flags); @@ -394,29 +281,18 @@ bool extract_mip_gnss_gps_time_data_from_field(const mip_field_view* field, void { assert(ptr); mip_gnss_gps_time_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_time_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_clock_info_data(microstrain_serializer* serializer, const mip_gnss_clock_info_data* self) { microstrain_insert_double(serializer, self->bias); - + microstrain_insert_double(serializer, self->drift); - + microstrain_insert_double(serializer, self->accuracy_estimate); insert_mip_gnss_clock_info_data_valid_flags(serializer, self->valid_flags); @@ -425,9 +301,9 @@ void insert_mip_gnss_clock_info_data(microstrain_serializer* serializer, const m void extract_mip_gnss_clock_info_data(microstrain_serializer* serializer, mip_gnss_clock_info_data* self) { microstrain_extract_double(serializer, &self->bias); - + microstrain_extract_double(serializer, &self->drift); - + microstrain_extract_double(serializer, &self->accuracy_estimate); extract_mip_gnss_clock_info_data_valid_flags(serializer, &self->valid_flags); @@ -437,27 +313,16 @@ bool extract_mip_gnss_clock_info_data_from_field(const mip_field_view* field, vo { assert(ptr); mip_gnss_clock_info_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_clock_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_fix_info_data(microstrain_serializer* serializer, const mip_gnss_fix_info_data* self) { insert_mip_gnss_fix_info_data_fix_type(serializer, self->fix_type); - + microstrain_insert_u8(serializer, self->num_sv); insert_mip_gnss_fix_info_data_fix_flags(serializer, self->fix_flags); @@ -468,7 +333,7 @@ void insert_mip_gnss_fix_info_data(microstrain_serializer* serializer, const mip void extract_mip_gnss_fix_info_data(microstrain_serializer* serializer, mip_gnss_fix_info_data* self) { extract_mip_gnss_fix_info_data_fix_type(serializer, &self->fix_type); - + microstrain_extract_u8(serializer, &self->num_sv); extract_mip_gnss_fix_info_data_fix_flags(serializer, &self->fix_flags); @@ -480,55 +345,22 @@ bool extract_mip_gnss_fix_info_data_from_field(const mip_field_view* field, void { assert(ptr); mip_gnss_fix_info_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_fix_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_sv_info_data(microstrain_serializer* serializer, const mip_gnss_sv_info_data* self) { microstrain_insert_u8(serializer, self->channel); - + microstrain_insert_u8(serializer, self->sv_id); - + microstrain_insert_u16(serializer, self->carrier_noise_ratio); - + microstrain_insert_s16(serializer, self->azimuth); - + microstrain_insert_s16(serializer, self->elevation); insert_mip_gnss_sv_info_data_svflags(serializer, self->sv_flags); @@ -539,13 +371,13 @@ void insert_mip_gnss_sv_info_data(microstrain_serializer* serializer, const mip_ void extract_mip_gnss_sv_info_data(microstrain_serializer* serializer, mip_gnss_sv_info_data* self) { microstrain_extract_u8(serializer, &self->channel); - + microstrain_extract_u8(serializer, &self->sv_id); - + microstrain_extract_u16(serializer, &self->carrier_noise_ratio); - + microstrain_extract_s16(serializer, &self->azimuth); - + microstrain_extract_s16(serializer, &self->elevation); extract_mip_gnss_sv_info_data_svflags(serializer, &self->sv_flags); @@ -557,34 +389,12 @@ bool extract_mip_gnss_sv_info_data_from_field(const mip_field_view* field, void* { assert(ptr); mip_gnss_sv_info_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_sv_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_hw_status_data(microstrain_serializer* serializer, const mip_gnss_hw_status_data* self) { insert_mip_gnss_hw_status_data_receiver_state(serializer, self->receiver_state); @@ -611,64 +421,20 @@ bool extract_mip_gnss_hw_status_data_from_field(const mip_field_view* field, voi { assert(ptr); mip_gnss_hw_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_hw_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_dgps_info_data(microstrain_serializer* serializer, const mip_gnss_dgps_info_data* self) { microstrain_insert_u8(serializer, self->sv_id); - + microstrain_insert_float(serializer, self->age); - + microstrain_insert_float(serializer, self->range_correction); - + microstrain_insert_float(serializer, self->range_rate_correction); insert_mip_gnss_dgps_info_data_valid_flags(serializer, self->valid_flags); @@ -677,11 +443,11 @@ void insert_mip_gnss_dgps_info_data(microstrain_serializer* serializer, const mi void extract_mip_gnss_dgps_info_data(microstrain_serializer* serializer, mip_gnss_dgps_info_data* self) { microstrain_extract_u8(serializer, &self->sv_id); - + microstrain_extract_float(serializer, &self->age); - + microstrain_extract_float(serializer, &self->range_correction); - + microstrain_extract_float(serializer, &self->range_rate_correction); extract_mip_gnss_dgps_info_data_valid_flags(serializer, &self->valid_flags); @@ -691,31 +457,20 @@ bool extract_mip_gnss_dgps_info_data_from_field(const mip_field_view* field, voi { assert(ptr); mip_gnss_dgps_info_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_dgps_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data* self) { microstrain_insert_u8(serializer, self->sv_id); - + microstrain_insert_float(serializer, self->age); - + microstrain_insert_float(serializer, self->range_correction); - + microstrain_insert_float(serializer, self->range_rate_correction); insert_mip_gnss_dgps_channel_data_valid_flags(serializer, self->valid_flags); @@ -724,11 +479,11 @@ void insert_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, const void extract_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, mip_gnss_dgps_channel_data* self) { microstrain_extract_u8(serializer, &self->sv_id); - + microstrain_extract_float(serializer, &self->age); - + microstrain_extract_float(serializer, &self->range_correction); - + microstrain_extract_float(serializer, &self->range_rate_correction); extract_mip_gnss_dgps_channel_data_valid_flags(serializer, &self->valid_flags); @@ -738,31 +493,20 @@ bool extract_mip_gnss_dgps_channel_data_from_field(const mip_field_view* field, { assert(ptr); mip_gnss_dgps_channel_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_dgps_channel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data* self) { microstrain_insert_double(serializer, self->bias); - + microstrain_insert_double(serializer, self->drift); - + microstrain_insert_double(serializer, self->bias_accuracy_estimate); - + microstrain_insert_double(serializer, self->drift_accuracy_estimate); insert_mip_gnss_clock_info_2_data_valid_flags(serializer, self->valid_flags); @@ -771,11 +515,11 @@ void insert_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, const void extract_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, mip_gnss_clock_info_2_data* self) { microstrain_extract_double(serializer, &self->bias); - + microstrain_extract_double(serializer, &self->drift); - + microstrain_extract_double(serializer, &self->bias_accuracy_estimate); - + microstrain_extract_double(serializer, &self->drift_accuracy_estimate); extract_mip_gnss_clock_info_2_data_valid_flags(serializer, &self->valid_flags); @@ -785,23 +529,12 @@ bool extract_mip_gnss_clock_info_2_data_from_field(const mip_field_view* field, { assert(ptr); mip_gnss_clock_info_2_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_clock_info_2_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self) { microstrain_insert_u8(serializer, self->leap_seconds); @@ -820,33 +553,22 @@ bool extract_mip_gnss_gps_leap_seconds_data_from_field(const mip_field_view* fie { assert(ptr); mip_gnss_gps_leap_seconds_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_leap_seconds_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_sbas_info_data(microstrain_serializer* serializer, const mip_gnss_sbas_info_data* self) { microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); insert_mip_sbas_system(serializer, self->sbas_system); - + microstrain_insert_u8(serializer, self->sbas_id); - + microstrain_insert_u8(serializer, self->count); insert_mip_gnss_sbas_info_data_sbas_status(serializer, self->sbas_status); @@ -857,13 +579,13 @@ void insert_mip_gnss_sbas_info_data(microstrain_serializer* serializer, const mi void extract_mip_gnss_sbas_info_data(microstrain_serializer* serializer, mip_gnss_sbas_info_data* self) { microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); extract_mip_sbas_system(serializer, &self->sbas_system); - + microstrain_extract_u8(serializer, &self->sbas_id); - + microstrain_extract_u8(serializer, &self->count); extract_mip_gnss_sbas_info_data_sbas_status(serializer, &self->sbas_status); @@ -875,52 +597,30 @@ bool extract_mip_gnss_sbas_info_data_from_field(const mip_field_view* field, voi { assert(ptr); mip_gnss_sbas_info_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_sbas_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data* self) { microstrain_insert_u8(serializer, self->index); - + microstrain_insert_u8(serializer, self->count); - + microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); insert_mip_gnss_constellation_id(serializer, self->gnss_id); - + microstrain_insert_u8(serializer, self->sv_id); - + microstrain_insert_u8(serializer, self->udrei); - + microstrain_insert_float(serializer, self->pseudorange_correction); - + microstrain_insert_float(serializer, self->iono_correction); insert_mip_gnss_sbas_correction_data_valid_flags(serializer, self->valid_flags); @@ -929,21 +629,21 @@ void insert_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, co void extract_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, mip_gnss_sbas_correction_data* self) { microstrain_extract_u8(serializer, &self->index); - + microstrain_extract_u8(serializer, &self->count); - + microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); extract_mip_gnss_constellation_id(serializer, &self->gnss_id); - + microstrain_extract_u8(serializer, &self->sv_id); - + microstrain_extract_u8(serializer, &self->udrei); - + microstrain_extract_float(serializer, &self->pseudorange_correction); - + microstrain_extract_float(serializer, &self->iono_correction); extract_mip_gnss_sbas_correction_data_valid_flags(serializer, &self->valid_flags); @@ -953,23 +653,12 @@ bool extract_mip_gnss_sbas_correction_data_from_field(const mip_field_view* fiel { assert(ptr); mip_gnss_sbas_correction_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_sbas_correction_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data* self) { insert_mip_gnss_rf_error_detection_data_rfband(serializer, self->rf_band); @@ -1002,67 +691,22 @@ bool extract_mip_gnss_rf_error_detection_data_from_field(const mip_field_view* f { assert(ptr); mip_gnss_rf_error_detection_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_rf_error_detection_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_base_station_info_data(microstrain_serializer* serializer, const mip_gnss_base_station_info_data* self) { microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_double(serializer, self->ecef_pos[i]); - + insert_mip_vector3d(serializer, self->ecef_pos); + microstrain_insert_float(serializer, self->height); - + microstrain_insert_u16(serializer, self->station_id); insert_mip_gnss_base_station_info_data_indicator_flags(serializer, self->indicators); @@ -1073,14 +717,13 @@ void insert_mip_gnss_base_station_info_data(microstrain_serializer* serializer, void extract_mip_gnss_base_station_info_data(microstrain_serializer* serializer, mip_gnss_base_station_info_data* self) { microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_double(serializer, &self->ecef_pos[i]); - + extract_mip_vector3d(serializer, self->ecef_pos); + microstrain_extract_float(serializer, &self->height); - + microstrain_extract_u16(serializer, &self->station_id); extract_mip_gnss_base_station_info_data_indicator_flags(serializer, &self->indicators); @@ -1092,50 +735,28 @@ bool extract_mip_gnss_base_station_info_data_from_field(const mip_field_view* fi { assert(ptr); mip_gnss_base_station_info_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_base_station_info_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self) { microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); insert_mip_gnss_rtk_corrections_status_data_epoch_status(serializer, self->epoch_status); - + microstrain_insert_u32(serializer, self->dongle_status); - + microstrain_insert_float(serializer, self->gps_correction_latency); - + microstrain_insert_float(serializer, self->glonass_correction_latency); - + microstrain_insert_float(serializer, self->galileo_correction_latency); - + microstrain_insert_float(serializer, self->beidou_correction_latency); for(unsigned int i=0; i < 4; i++) @@ -1147,19 +768,19 @@ void insert_mip_gnss_rtk_corrections_status_data(microstrain_serializer* seriali void extract_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data* self) { microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); extract_mip_gnss_rtk_corrections_status_data_epoch_status(serializer, &self->epoch_status); - + microstrain_extract_u32(serializer, &self->dongle_status); - + microstrain_extract_float(serializer, &self->gps_correction_latency); - + microstrain_extract_float(serializer, &self->glonass_correction_latency); - + microstrain_extract_float(serializer, &self->galileo_correction_latency); - + microstrain_extract_float(serializer, &self->beidou_correction_latency); for(unsigned int i=0; i < 4; i++) @@ -1172,52 +793,30 @@ bool extract_mip_gnss_rtk_corrections_status_data_from_field(const mip_field_vie { assert(ptr); mip_gnss_rtk_corrections_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_rtk_corrections_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_satellite_status_data(microstrain_serializer* serializer, const mip_gnss_satellite_status_data* self) { microstrain_insert_u8(serializer, self->index); - + microstrain_insert_u8(serializer, self->count); - + microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); insert_mip_gnss_constellation_id(serializer, self->gnss_id); - + microstrain_insert_u8(serializer, self->satellite_id); - + microstrain_insert_float(serializer, self->elevation); - + microstrain_insert_float(serializer, self->azimuth); - + microstrain_insert_bool(serializer, self->health); insert_mip_gnss_satellite_status_data_valid_flags(serializer, self->valid_flags); @@ -1226,21 +825,21 @@ void insert_mip_gnss_satellite_status_data(microstrain_serializer* serializer, c void extract_mip_gnss_satellite_status_data(microstrain_serializer* serializer, mip_gnss_satellite_status_data* self) { microstrain_extract_u8(serializer, &self->index); - + microstrain_extract_u8(serializer, &self->count); - + microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); extract_mip_gnss_constellation_id(serializer, &self->gnss_id); - + microstrain_extract_u8(serializer, &self->satellite_id); - + microstrain_extract_float(serializer, &self->elevation); - + microstrain_extract_float(serializer, &self->azimuth); - + microstrain_extract_bool(serializer, &self->health); extract_mip_gnss_satellite_status_data_valid_flags(serializer, &self->valid_flags); @@ -1250,59 +849,48 @@ bool extract_mip_gnss_satellite_status_data_from_field(const mip_field_view* fie { assert(ptr); mip_gnss_satellite_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_satellite_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_raw_data(microstrain_serializer* serializer, const mip_gnss_raw_data* self) { microstrain_insert_u8(serializer, self->index); - + microstrain_insert_u8(serializer, self->count); - + microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); - + microstrain_insert_u16(serializer, self->receiver_id); - + microstrain_insert_u8(serializer, self->tracking_channel); insert_mip_gnss_constellation_id(serializer, self->gnss_id); - + microstrain_insert_u8(serializer, self->satellite_id); insert_mip_gnss_signal_id(serializer, self->signal_id); - + microstrain_insert_float(serializer, self->signal_strength); insert_mip_gnss_raw_data_gnss_signal_quality(serializer, self->quality); - + microstrain_insert_double(serializer, self->pseudorange); - + microstrain_insert_double(serializer, self->carrier_phase); - + microstrain_insert_float(serializer, self->doppler); - + microstrain_insert_float(serializer, self->range_uncert); - + microstrain_insert_float(serializer, self->phase_uncert); - + microstrain_insert_float(serializer, self->doppler_uncert); - + microstrain_insert_float(serializer, self->lock_time); insert_mip_gnss_raw_data_valid_flags(serializer, self->valid_flags); @@ -1311,39 +899,39 @@ void insert_mip_gnss_raw_data(microstrain_serializer* serializer, const mip_gnss void extract_mip_gnss_raw_data(microstrain_serializer* serializer, mip_gnss_raw_data* self) { microstrain_extract_u8(serializer, &self->index); - + microstrain_extract_u8(serializer, &self->count); - + microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); - + microstrain_extract_u16(serializer, &self->receiver_id); - + microstrain_extract_u8(serializer, &self->tracking_channel); extract_mip_gnss_constellation_id(serializer, &self->gnss_id); - + microstrain_extract_u8(serializer, &self->satellite_id); extract_mip_gnss_signal_id(serializer, &self->signal_id); - + microstrain_extract_float(serializer, &self->signal_strength); extract_mip_gnss_raw_data_gnss_signal_quality(serializer, &self->quality); - + microstrain_extract_double(serializer, &self->pseudorange); - + microstrain_extract_double(serializer, &self->carrier_phase); - + microstrain_extract_float(serializer, &self->doppler); - + microstrain_extract_float(serializer, &self->range_uncert); - + microstrain_extract_float(serializer, &self->phase_uncert); - + microstrain_extract_float(serializer, &self->doppler_uncert); - + microstrain_extract_float(serializer, &self->lock_time); extract_mip_gnss_raw_data_valid_flags(serializer, &self->valid_flags); @@ -1353,100 +941,78 @@ bool extract_mip_gnss_raw_data_from_field(const mip_field_view* field, void* ptr { assert(ptr); mip_gnss_raw_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_raw_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self) -{ - microstrain_insert_u8(serializer, (uint8_t) (self)); -} -void extract_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self) -{ - uint8_t tmp = 0; - microstrain_extract_u8(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - -void insert_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data* self) +void insert_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data* self) { microstrain_insert_u8(serializer, self->index); - + microstrain_insert_u8(serializer, self->count); - + microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); - + microstrain_insert_u8(serializer, self->satellite_id); - + microstrain_insert_u8(serializer, self->health); - + microstrain_insert_u8(serializer, self->iodc); - + microstrain_insert_u8(serializer, self->iode); - + microstrain_insert_double(serializer, self->t_oc); - + microstrain_insert_double(serializer, self->af0); - + microstrain_insert_double(serializer, self->af1); - + microstrain_insert_double(serializer, self->af2); - + microstrain_insert_double(serializer, self->t_gd); - + microstrain_insert_double(serializer, self->ISC_L1CA); - + microstrain_insert_double(serializer, self->ISC_L2C); - + microstrain_insert_double(serializer, self->t_oe); - + microstrain_insert_double(serializer, self->a); - + microstrain_insert_double(serializer, self->a_dot); - + microstrain_insert_double(serializer, self->mean_anomaly); - + microstrain_insert_double(serializer, self->delta_mean_motion); - + microstrain_insert_double(serializer, self->delta_mean_motion_dot); - + microstrain_insert_double(serializer, self->eccentricity); - + microstrain_insert_double(serializer, self->argument_of_perigee); - + microstrain_insert_double(serializer, self->omega); - + microstrain_insert_double(serializer, self->omega_dot); - + microstrain_insert_double(serializer, self->inclination); - + microstrain_insert_double(serializer, self->inclination_dot); - + microstrain_insert_double(serializer, self->c_ic); - + microstrain_insert_double(serializer, self->c_is); - + microstrain_insert_double(serializer, self->c_uc); - + microstrain_insert_double(serializer, self->c_us); - + microstrain_insert_double(serializer, self->c_rc); - + microstrain_insert_double(serializer, self->c_rs); insert_mip_gnss_gps_ephemeris_data_valid_flags(serializer, self->valid_flags); @@ -1455,69 +1021,69 @@ void insert_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, cons void extract_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data* self) { microstrain_extract_u8(serializer, &self->index); - + microstrain_extract_u8(serializer, &self->count); - + microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); - + microstrain_extract_u8(serializer, &self->satellite_id); - + microstrain_extract_u8(serializer, &self->health); - + microstrain_extract_u8(serializer, &self->iodc); - + microstrain_extract_u8(serializer, &self->iode); - + microstrain_extract_double(serializer, &self->t_oc); - + microstrain_extract_double(serializer, &self->af0); - + microstrain_extract_double(serializer, &self->af1); - + microstrain_extract_double(serializer, &self->af2); - + microstrain_extract_double(serializer, &self->t_gd); - + microstrain_extract_double(serializer, &self->ISC_L1CA); - + microstrain_extract_double(serializer, &self->ISC_L2C); - + microstrain_extract_double(serializer, &self->t_oe); - + microstrain_extract_double(serializer, &self->a); - + microstrain_extract_double(serializer, &self->a_dot); - + microstrain_extract_double(serializer, &self->mean_anomaly); - + microstrain_extract_double(serializer, &self->delta_mean_motion); - + microstrain_extract_double(serializer, &self->delta_mean_motion_dot); - + microstrain_extract_double(serializer, &self->eccentricity); - + microstrain_extract_double(serializer, &self->argument_of_perigee); - + microstrain_extract_double(serializer, &self->omega); - + microstrain_extract_double(serializer, &self->omega_dot); - + microstrain_extract_double(serializer, &self->inclination); - + microstrain_extract_double(serializer, &self->inclination_dot); - + microstrain_extract_double(serializer, &self->c_ic); - + microstrain_extract_double(serializer, &self->c_is); - + microstrain_extract_double(serializer, &self->c_uc); - + microstrain_extract_double(serializer, &self->c_us); - + microstrain_extract_double(serializer, &self->c_rc); - + microstrain_extract_double(serializer, &self->c_rs); extract_mip_gnss_gps_ephemeris_data_valid_flags(serializer, &self->valid_flags); @@ -1527,89 +1093,78 @@ bool extract_mip_gnss_gps_ephemeris_data_from_field(const mip_field_view* field, { assert(ptr); mip_gnss_gps_ephemeris_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_ephemeris_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self) { microstrain_insert_u8(serializer, self->index); - + microstrain_insert_u8(serializer, self->count); - + microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); - + microstrain_insert_u8(serializer, self->satellite_id); - + microstrain_insert_u8(serializer, self->health); - + microstrain_insert_u8(serializer, self->iodc); - + microstrain_insert_u8(serializer, self->iode); - + microstrain_insert_double(serializer, self->t_oc); - + microstrain_insert_double(serializer, self->af0); - + microstrain_insert_double(serializer, self->af1); - + microstrain_insert_double(serializer, self->af2); - + microstrain_insert_double(serializer, self->t_gd); - + microstrain_insert_double(serializer, self->ISC_L1CA); - + microstrain_insert_double(serializer, self->ISC_L2C); - + microstrain_insert_double(serializer, self->t_oe); - + microstrain_insert_double(serializer, self->a); - + microstrain_insert_double(serializer, self->a_dot); - + microstrain_insert_double(serializer, self->mean_anomaly); - + microstrain_insert_double(serializer, self->delta_mean_motion); - + microstrain_insert_double(serializer, self->delta_mean_motion_dot); - + microstrain_insert_double(serializer, self->eccentricity); - + microstrain_insert_double(serializer, self->argument_of_perigee); - + microstrain_insert_double(serializer, self->omega); - + microstrain_insert_double(serializer, self->omega_dot); - + microstrain_insert_double(serializer, self->inclination); - + microstrain_insert_double(serializer, self->inclination_dot); - + microstrain_insert_double(serializer, self->c_ic); - + microstrain_insert_double(serializer, self->c_is); - + microstrain_insert_double(serializer, self->c_uc); - + microstrain_insert_double(serializer, self->c_us); - + microstrain_insert_double(serializer, self->c_rc); - + microstrain_insert_double(serializer, self->c_rs); insert_mip_gnss_galileo_ephemeris_data_valid_flags(serializer, self->valid_flags); @@ -1618,69 +1173,69 @@ void insert_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, void extract_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data* self) { microstrain_extract_u8(serializer, &self->index); - + microstrain_extract_u8(serializer, &self->count); - + microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); - + microstrain_extract_u8(serializer, &self->satellite_id); - + microstrain_extract_u8(serializer, &self->health); - + microstrain_extract_u8(serializer, &self->iodc); - + microstrain_extract_u8(serializer, &self->iode); - + microstrain_extract_double(serializer, &self->t_oc); - + microstrain_extract_double(serializer, &self->af0); - + microstrain_extract_double(serializer, &self->af1); - + microstrain_extract_double(serializer, &self->af2); - + microstrain_extract_double(serializer, &self->t_gd); - + microstrain_extract_double(serializer, &self->ISC_L1CA); - + microstrain_extract_double(serializer, &self->ISC_L2C); - + microstrain_extract_double(serializer, &self->t_oe); - + microstrain_extract_double(serializer, &self->a); - + microstrain_extract_double(serializer, &self->a_dot); - + microstrain_extract_double(serializer, &self->mean_anomaly); - + microstrain_extract_double(serializer, &self->delta_mean_motion); - + microstrain_extract_double(serializer, &self->delta_mean_motion_dot); - + microstrain_extract_double(serializer, &self->eccentricity); - + microstrain_extract_double(serializer, &self->argument_of_perigee); - + microstrain_extract_double(serializer, &self->omega); - + microstrain_extract_double(serializer, &self->omega_dot); - + microstrain_extract_double(serializer, &self->inclination); - + microstrain_extract_double(serializer, &self->inclination_dot); - + microstrain_extract_double(serializer, &self->c_ic); - + microstrain_extract_double(serializer, &self->c_is); - + microstrain_extract_double(serializer, &self->c_uc); - + microstrain_extract_double(serializer, &self->c_us); - + microstrain_extract_double(serializer, &self->c_rc); - + microstrain_extract_double(serializer, &self->c_rs); extract_mip_gnss_galileo_ephemeris_data_valid_flags(serializer, &self->valid_flags); @@ -1690,74 +1245,60 @@ bool extract_mip_gnss_galileo_ephemeris_data_from_field(const mip_field_view* fi { assert(ptr); mip_gnss_galileo_ephemeris_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_galileo_ephemeris_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data* self) { microstrain_insert_u8(serializer, self->index); - + microstrain_insert_u8(serializer, self->count); - + microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); - + microstrain_insert_u8(serializer, self->satellite_id); - + microstrain_insert_s8(serializer, self->freq_number); - + microstrain_insert_u32(serializer, self->tk); - + microstrain_insert_u32(serializer, self->tb); - + microstrain_insert_u8(serializer, self->sat_type); - + microstrain_insert_double(serializer, self->gamma); - + microstrain_insert_double(serializer, self->tau_n); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_double(serializer, self->x[i]); + insert_mip_vector3d(serializer, self->x); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->v[i]); + insert_mip_vector3f(serializer, self->v); + + insert_mip_vector3f(serializer, self->a); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->a[i]); - microstrain_insert_u8(serializer, self->health); - + microstrain_insert_u8(serializer, self->P); - + microstrain_insert_u8(serializer, self->NT); - + microstrain_insert_float(serializer, self->delta_tau_n); - + microstrain_insert_u8(serializer, self->Ft); - + microstrain_insert_u8(serializer, self->En); - + microstrain_insert_u8(serializer, self->P1); - + microstrain_insert_u8(serializer, self->P2); - + microstrain_insert_u8(serializer, self->P3); - + microstrain_insert_u8(serializer, self->P4); insert_mip_gnss_glo_ephemeris_data_valid_flags(serializer, self->valid_flags); @@ -1766,54 +1307,51 @@ void insert_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, cons void extract_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data* self) { microstrain_extract_u8(serializer, &self->index); - + microstrain_extract_u8(serializer, &self->count); - + microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); - + microstrain_extract_u8(serializer, &self->satellite_id); - + microstrain_extract_s8(serializer, &self->freq_number); - + microstrain_extract_u32(serializer, &self->tk); - + microstrain_extract_u32(serializer, &self->tb); - + microstrain_extract_u8(serializer, &self->sat_type); - + microstrain_extract_double(serializer, &self->gamma); - + microstrain_extract_double(serializer, &self->tau_n); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_double(serializer, &self->x[i]); + extract_mip_vector3d(serializer, self->x); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->v[i]); + extract_mip_vector3f(serializer, self->v); + + extract_mip_vector3f(serializer, self->a); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->a[i]); - microstrain_extract_u8(serializer, &self->health); - + microstrain_extract_u8(serializer, &self->P); - + microstrain_extract_u8(serializer, &self->NT); - + microstrain_extract_float(serializer, &self->delta_tau_n); - + microstrain_extract_u8(serializer, &self->Ft); - + microstrain_extract_u8(serializer, &self->En); - + microstrain_extract_u8(serializer, &self->P1); - + microstrain_extract_u8(serializer, &self->P2); - + microstrain_extract_u8(serializer, &self->P3); - + microstrain_extract_u8(serializer, &self->P4); extract_mip_gnss_glo_ephemeris_data_valid_flags(serializer, &self->valid_flags); @@ -1823,27 +1361,16 @@ bool extract_mip_gnss_glo_ephemeris_data_from_field(const mip_field_view* field, { assert(ptr); mip_gnss_glo_ephemeris_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_glo_ephemeris_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data* self) { microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); for(unsigned int i=0; i < 4; i++) @@ -1858,7 +1385,7 @@ void insert_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, cons void extract_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data* self) { microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); for(unsigned int i=0; i < 4; i++) @@ -1874,32 +1401,20 @@ bool extract_mip_gnss_gps_iono_corr_data_from_field(const mip_field_view* field, { assert(ptr); mip_gnss_gps_iono_corr_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_gps_iono_corr_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self) { microstrain_insert_double(serializer, self->time_of_week); - + microstrain_insert_u16(serializer, self->week_number); - for(unsigned int i=0; i < 3; i++) - microstrain_insert_double(serializer, self->alpha[i]); - + insert_mip_vector3d(serializer, self->alpha); + microstrain_insert_u8(serializer, self->disturbance_flags); insert_mip_gnss_galileo_iono_corr_data_valid_flags(serializer, self->valid_flags); @@ -1908,12 +1423,11 @@ void insert_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, void extract_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data* self) { microstrain_extract_double(serializer, &self->time_of_week); - + microstrain_extract_u16(serializer, &self->week_number); - for(unsigned int i=0; i < 3; i++) - microstrain_extract_double(serializer, &self->alpha[i]); - + extract_mip_vector3d(serializer, self->alpha); + microstrain_extract_u8(serializer, &self->disturbance_flags); extract_mip_gnss_galileo_iono_corr_data_valid_flags(serializer, &self->valid_flags); @@ -1923,23 +1437,12 @@ bool extract_mip_gnss_galileo_iono_corr_data_from_field(const mip_field_view* fi { assert(ptr); mip_gnss_galileo_iono_corr_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_gnss_galileo_iono_corr_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - #ifdef __cplusplus } // namespace C diff --git a/src/c/mip/definitions/data_gnss.h b/src/c/mip/definitions/data_gnss.h index b240b6d5f..7c6cfc9dc 100644 --- a/src/c/mip/definitions/data_gnss.h +++ b/src/c/mip/definitions/data_gnss.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,9 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipData_c MIP Data [C] @@ -74,96 +72,129 @@ enum { MIP_GNSS2_DATA_DESC_SET = 0x92 }; enum { MIP_GNSS3_DATA_DESC_SET = 0x93 }; enum { MIP_GNSS4_DATA_DESC_SET = 0x94 }; enum { MIP_GNSS5_DATA_DESC_SET = 0x95 }; -typedef uint8_t mip_gnss_constellation_id; -static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_UNKNOWN = 0; ///< -static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_GPS = 1; ///< -static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_GLONASS = 2; ///< -static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_GALILEO = 3; ///< -static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_BEIDOU = 4; ///< -static const mip_gnss_constellation_id MIP_GNSS_CONSTELLATION_ID_SBAS = 5; ///< - -void insert_mip_gnss_constellation_id(microstrain_serializer* serializer, const mip_gnss_constellation_id self); -void extract_mip_gnss_constellation_id(microstrain_serializer* serializer, mip_gnss_constellation_id* self); - -typedef uint8_t mip_gnss_signal_id; -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_UNKNOWN = 0; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L1CA = 1; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L1P = 2; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L1Z = 3; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L2CA = 4; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L2P = 5; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L2Z = 6; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L2CL = 7; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L2CM = 8; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L2CML = 9; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L5I = 10; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L5Q = 11; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L5IQ = 12; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L1CD = 13; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L1CP = 14; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GPS_L1CDP = 15; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GLONASS_G1CA = 32; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GLONASS_G1P = 33; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GLONASS_G2C = 34; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GLONASS_G2P = 35; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E1C = 64; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E1A = 65; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E1B = 66; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E1BC = 67; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E1ABC = 68; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E6C = 69; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E6A = 70; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E6B = 71; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E6BC = 72; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E6ABC = 73; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E5BI = 74; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E5BQ = 75; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E5BIQ = 76; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E5ABI = 77; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E5ABQ = 78; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E5ABIQ = 79; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E5AI = 80; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E5AQ = 81; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_GALILEO_E5AIQ = 82; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_SBAS_L1CA = 96; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_SBAS_L5I = 97; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_SBAS_L5Q = 98; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_SBAS_L5IQ = 99; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L1CA = 128; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_LEXS = 129; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_LEXL = 130; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_LEXSL = 131; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L2CM = 132; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L2CL = 133; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L2CML = 134; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L5I = 135; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L5Q = 136; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L5IQ = 137; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L1CD = 138; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L1CP = 139; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_QZSS_L1CDP = 140; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B1I = 160; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B1Q = 161; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B1IQ = 162; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B3I = 163; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B3Q = 164; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B3IQ = 165; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2I = 166; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2Q = 167; ///< -static const mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2IQ = 168; ///< - -void insert_mip_gnss_signal_id(microstrain_serializer* serializer, const mip_gnss_signal_id self); -void extract_mip_gnss_signal_id(microstrain_serializer* serializer, mip_gnss_signal_id* self); - -typedef uint8_t mip_sbas_system; -static const mip_sbas_system MIP_SBAS_SYSTEM_UNKNOWN = 0; ///< -static const mip_sbas_system MIP_SBAS_SYSTEM_WAAS = 1; ///< -static const mip_sbas_system MIP_SBAS_SYSTEM_EGNOS = 2; ///< -static const mip_sbas_system MIP_SBAS_SYSTEM_MSAS = 3; ///< -static const mip_sbas_system MIP_SBAS_SYSTEM_GAGAN = 4; ///< - -void insert_mip_sbas_system(microstrain_serializer* serializer, const mip_sbas_system self); -void extract_mip_sbas_system(microstrain_serializer* serializer, mip_sbas_system* self); +enum mip_gnss_constellation_id +{ + MIP_GNSS_CONSTELLATION_ID_UNKNOWN = 0, ///< + MIP_GNSS_CONSTELLATION_ID_GPS = 1, ///< + MIP_GNSS_CONSTELLATION_ID_GLONASS = 2, ///< + MIP_GNSS_CONSTELLATION_ID_GALILEO = 3, ///< + MIP_GNSS_CONSTELLATION_ID_BEIDOU = 4, ///< + MIP_GNSS_CONSTELLATION_ID_SBAS = 5, ///< +}; +typedef enum mip_gnss_constellation_id mip_gnss_constellation_id; + +inline void insert_mip_gnss_constellation_id(microstrain_serializer* serializer, const mip_gnss_constellation_id self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_constellation_id(microstrain_serializer* serializer, mip_gnss_constellation_id* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + +enum mip_gnss_signal_id +{ + MIP_GNSS_SIGNAL_ID_UNKNOWN = 0, ///< + MIP_GNSS_SIGNAL_ID_GPS_L1CA = 1, ///< + MIP_GNSS_SIGNAL_ID_GPS_L1P = 2, ///< + MIP_GNSS_SIGNAL_ID_GPS_L1Z = 3, ///< + MIP_GNSS_SIGNAL_ID_GPS_L2CA = 4, ///< + MIP_GNSS_SIGNAL_ID_GPS_L2P = 5, ///< + MIP_GNSS_SIGNAL_ID_GPS_L2Z = 6, ///< + MIP_GNSS_SIGNAL_ID_GPS_L2CL = 7, ///< + MIP_GNSS_SIGNAL_ID_GPS_L2CM = 8, ///< + MIP_GNSS_SIGNAL_ID_GPS_L2CML = 9, ///< + MIP_GNSS_SIGNAL_ID_GPS_L5I = 10, ///< + MIP_GNSS_SIGNAL_ID_GPS_L5Q = 11, ///< + MIP_GNSS_SIGNAL_ID_GPS_L5IQ = 12, ///< + MIP_GNSS_SIGNAL_ID_GPS_L1CD = 13, ///< + MIP_GNSS_SIGNAL_ID_GPS_L1CP = 14, ///< + MIP_GNSS_SIGNAL_ID_GPS_L1CDP = 15, ///< + MIP_GNSS_SIGNAL_ID_GLONASS_G1CA = 32, ///< + MIP_GNSS_SIGNAL_ID_GLONASS_G1P = 33, ///< + MIP_GNSS_SIGNAL_ID_GLONASS_G2C = 34, ///< + MIP_GNSS_SIGNAL_ID_GLONASS_G2P = 35, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E1C = 64, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E1A = 65, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E1B = 66, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E1BC = 67, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E1ABC = 68, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E6C = 69, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E6A = 70, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E6B = 71, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E6BC = 72, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E6ABC = 73, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E5BI = 74, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E5BQ = 75, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E5BIQ = 76, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E5ABI = 77, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E5ABQ = 78, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E5ABIQ = 79, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E5AI = 80, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E5AQ = 81, ///< + MIP_GNSS_SIGNAL_ID_GALILEO_E5AIQ = 82, ///< + MIP_GNSS_SIGNAL_ID_SBAS_L1CA = 96, ///< + MIP_GNSS_SIGNAL_ID_SBAS_L5I = 97, ///< + MIP_GNSS_SIGNAL_ID_SBAS_L5Q = 98, ///< + MIP_GNSS_SIGNAL_ID_SBAS_L5IQ = 99, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L1CA = 128, ///< + MIP_GNSS_SIGNAL_ID_QZSS_LEXS = 129, ///< + MIP_GNSS_SIGNAL_ID_QZSS_LEXL = 130, ///< + MIP_GNSS_SIGNAL_ID_QZSS_LEXSL = 131, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L2CM = 132, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L2CL = 133, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L2CML = 134, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L5I = 135, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L5Q = 136, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L5IQ = 137, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L1CD = 138, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L1CP = 139, ///< + MIP_GNSS_SIGNAL_ID_QZSS_L1CDP = 140, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B1I = 160, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B1Q = 161, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B1IQ = 162, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B3I = 163, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B3Q = 164, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B3IQ = 165, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B2I = 166, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B2Q = 167, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B2IQ = 168, ///< +}; +typedef enum mip_gnss_signal_id mip_gnss_signal_id; + +inline void insert_mip_gnss_signal_id(microstrain_serializer* serializer, const mip_gnss_signal_id self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_signal_id(microstrain_serializer* serializer, mip_gnss_signal_id* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + +enum mip_sbas_system +{ + MIP_SBAS_SYSTEM_UNKNOWN = 0, ///< + MIP_SBAS_SYSTEM_WAAS = 1, ///< + MIP_SBAS_SYSTEM_EGNOS = 2, ///< + MIP_SBAS_SYSTEM_MSAS = 3, ///< + MIP_SBAS_SYSTEM_GAGAN = 4, ///< +}; +typedef enum mip_sbas_system mip_sbas_system; + +inline void insert_mip_sbas_system(microstrain_serializer* serializer, const mip_sbas_system self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_sbas_system(microstrain_serializer* serializer, mip_sbas_system* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} enum { MIP_GNSS_DGPS_INFO_MAX_CHANNEL_NUMBER = 32 }; enum { MIP_GNSS_SV_INFO_MAX_SV_NUMBER = 32 }; @@ -187,6 +218,17 @@ static const mip_gnss_pos_llh_data_valid_flags MIP_GNSS_POS_LLH_DATA_VALID_FLAGS static const mip_gnss_pos_llh_data_valid_flags MIP_GNSS_POS_LLH_DATA_VALID_FLAGS_VERTICAL_ACCURACY = 0x0010; ///< static const mip_gnss_pos_llh_data_valid_flags MIP_GNSS_POS_LLH_DATA_VALID_FLAGS_FLAGS = 0x001F; ///< static const mip_gnss_pos_llh_data_valid_flags MIP_GNSS_POS_LLH_DATA_VALID_FLAGS_ALL = 0x001F; +inline void insert_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_pos_llh_data { @@ -197,15 +239,12 @@ struct mip_gnss_pos_llh_data float horizontal_accuracy; ///< [meters] float vertical_accuracy; ///< [meters] mip_gnss_pos_llh_data_valid_flags valid_flags; - }; typedef struct mip_gnss_pos_llh_data mip_gnss_pos_llh_data; + void insert_mip_gnss_pos_llh_data(microstrain_serializer* serializer, const mip_gnss_pos_llh_data* self); void extract_mip_gnss_pos_llh_data(microstrain_serializer* serializer, mip_gnss_pos_llh_data* self); -bool extract_mip_gnss_pos_llh_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self); -void extract_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self); +bool extract_mip_gnss_pos_llh_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -222,21 +261,29 @@ static const mip_gnss_pos_ecef_data_valid_flags MIP_GNSS_POS_ECEF_DATA_VALID_FLA static const mip_gnss_pos_ecef_data_valid_flags MIP_GNSS_POS_ECEF_DATA_VALID_FLAGS_POSITION_ACCURACY = 0x0002; ///< static const mip_gnss_pos_ecef_data_valid_flags MIP_GNSS_POS_ECEF_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_pos_ecef_data_valid_flags MIP_GNSS_POS_ECEF_DATA_VALID_FLAGS_ALL = 0x0003; +inline void insert_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_pos_ecef_data { mip_vector3d x; ///< [meters] float x_accuracy; ///< [meters] mip_gnss_pos_ecef_data_valid_flags valid_flags; - }; typedef struct mip_gnss_pos_ecef_data mip_gnss_pos_ecef_data; + void insert_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data* self); void extract_mip_gnss_pos_ecef_data(microstrain_serializer* serializer, mip_gnss_pos_ecef_data* self); -bool extract_mip_gnss_pos_ecef_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self); -void extract_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self); +bool extract_mip_gnss_pos_ecef_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -257,6 +304,17 @@ static const mip_gnss_vel_ned_data_valid_flags MIP_GNSS_VEL_NED_DATA_VALID_FLAGS static const mip_gnss_vel_ned_data_valid_flags MIP_GNSS_VEL_NED_DATA_VALID_FLAGS_HEADING_ACCURACY = 0x0020; ///< static const mip_gnss_vel_ned_data_valid_flags MIP_GNSS_VEL_NED_DATA_VALID_FLAGS_FLAGS = 0x003F; ///< static const mip_gnss_vel_ned_data_valid_flags MIP_GNSS_VEL_NED_DATA_VALID_FLAGS_ALL = 0x003F; +inline void insert_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_vel_ned_data { @@ -267,15 +325,12 @@ struct mip_gnss_vel_ned_data float speed_accuracy; ///< [meters/second] float heading_accuracy; ///< [degrees] mip_gnss_vel_ned_data_valid_flags valid_flags; - }; typedef struct mip_gnss_vel_ned_data mip_gnss_vel_ned_data; + void insert_mip_gnss_vel_ned_data(microstrain_serializer* serializer, const mip_gnss_vel_ned_data* self); void extract_mip_gnss_vel_ned_data(microstrain_serializer* serializer, mip_gnss_vel_ned_data* self); -bool extract_mip_gnss_vel_ned_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self); -void extract_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self); +bool extract_mip_gnss_vel_ned_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -292,21 +347,29 @@ static const mip_gnss_vel_ecef_data_valid_flags MIP_GNSS_VEL_ECEF_DATA_VALID_FLA static const mip_gnss_vel_ecef_data_valid_flags MIP_GNSS_VEL_ECEF_DATA_VALID_FLAGS_VELOCITY_ACCURACY = 0x0002; ///< static const mip_gnss_vel_ecef_data_valid_flags MIP_GNSS_VEL_ECEF_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_vel_ecef_data_valid_flags MIP_GNSS_VEL_ECEF_DATA_VALID_FLAGS_ALL = 0x0003; +inline void insert_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_vel_ecef_data { mip_vector3f v; ///< [meters/second] float v_accuracy; ///< [meters/second] mip_gnss_vel_ecef_data_valid_flags valid_flags; - }; typedef struct mip_gnss_vel_ecef_data mip_gnss_vel_ecef_data; + void insert_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data* self); void extract_mip_gnss_vel_ecef_data(microstrain_serializer* serializer, mip_gnss_vel_ecef_data* self); -bool extract_mip_gnss_vel_ecef_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self); -void extract_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self); +bool extract_mip_gnss_vel_ecef_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -328,6 +391,17 @@ static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_NDOP = static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_EDOP = 0x0040; ///< static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_FLAGS = 0x007F; ///< static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_ALL = 0x007F; +inline void insert_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_dop_data { @@ -339,15 +413,12 @@ struct mip_gnss_dop_data float ndop; ///< Northing DOP float edop; ///< Easting DOP mip_gnss_dop_data_valid_flags valid_flags; - }; typedef struct mip_gnss_dop_data mip_gnss_dop_data; + void insert_mip_gnss_dop_data(microstrain_serializer* serializer, const mip_gnss_dop_data* self); void extract_mip_gnss_dop_data(microstrain_serializer* serializer, mip_gnss_dop_data* self); -bool extract_mip_gnss_dop_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self); -void extract_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self); +bool extract_mip_gnss_dop_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -364,6 +435,17 @@ static const mip_gnss_utc_time_data_valid_flags MIP_GNSS_UTC_TIME_DATA_VALID_FLA static const mip_gnss_utc_time_data_valid_flags MIP_GNSS_UTC_TIME_DATA_VALID_FLAGS_LEAP_SECONDS_KNOWN = 0x0002; ///< static const mip_gnss_utc_time_data_valid_flags MIP_GNSS_UTC_TIME_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_utc_time_data_valid_flags MIP_GNSS_UTC_TIME_DATA_VALID_FLAGS_ALL = 0x0003; +inline void insert_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_utc_time_data { @@ -375,15 +457,12 @@ struct mip_gnss_utc_time_data uint8_t sec; ///< Second (0-59) uint32_t msec; ///< Millisecond(0-999) mip_gnss_utc_time_data_valid_flags valid_flags; - }; typedef struct mip_gnss_utc_time_data mip_gnss_utc_time_data; + void insert_mip_gnss_utc_time_data(microstrain_serializer* serializer, const mip_gnss_utc_time_data* self); void extract_mip_gnss_utc_time_data(microstrain_serializer* serializer, mip_gnss_utc_time_data* self); -bool extract_mip_gnss_utc_time_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self); -void extract_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self); +bool extract_mip_gnss_utc_time_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -400,21 +479,29 @@ static const mip_gnss_gps_time_data_valid_flags MIP_GNSS_GPS_TIME_DATA_VALID_FLA static const mip_gnss_gps_time_data_valid_flags MIP_GNSS_GPS_TIME_DATA_VALID_FLAGS_WEEK_NUMBER = 0x0002; ///< static const mip_gnss_gps_time_data_valid_flags MIP_GNSS_GPS_TIME_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_gps_time_data_valid_flags MIP_GNSS_GPS_TIME_DATA_VALID_FLAGS_ALL = 0x0003; +inline void insert_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_gps_time_data { double tow; ///< GPS Time of week [seconds] uint16_t week_number; ///< GPS Week since 1980 [weeks] mip_gnss_gps_time_data_valid_flags valid_flags; - }; typedef struct mip_gnss_gps_time_data mip_gnss_gps_time_data; + void insert_mip_gnss_gps_time_data(microstrain_serializer* serializer, const mip_gnss_gps_time_data* self); void extract_mip_gnss_gps_time_data(microstrain_serializer* serializer, mip_gnss_gps_time_data* self); -bool extract_mip_gnss_gps_time_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self); -void extract_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self); +bool extract_mip_gnss_gps_time_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -432,6 +519,17 @@ static const mip_gnss_clock_info_data_valid_flags MIP_GNSS_CLOCK_INFO_DATA_VALID static const mip_gnss_clock_info_data_valid_flags MIP_GNSS_CLOCK_INFO_DATA_VALID_FLAGS_ACCURACY_ESTIMATE = 0x0004; ///< static const mip_gnss_clock_info_data_valid_flags MIP_GNSS_CLOCK_INFO_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_clock_info_data_valid_flags MIP_GNSS_CLOCK_INFO_DATA_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_clock_info_data { @@ -439,15 +537,12 @@ struct mip_gnss_clock_info_data double drift; ///< [seconds/second] double accuracy_estimate; ///< [seconds] mip_gnss_clock_info_data_valid_flags valid_flags; - }; typedef struct mip_gnss_clock_info_data mip_gnss_clock_info_data; + void insert_mip_gnss_clock_info_data(microstrain_serializer* serializer, const mip_gnss_clock_info_data* self); void extract_mip_gnss_clock_info_data(microstrain_serializer* serializer, mip_gnss_clock_info_data* self); -bool extract_mip_gnss_clock_info_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self); -void extract_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self); +bool extract_mip_gnss_clock_info_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -458,21 +553,45 @@ void extract_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serial /// ///@{ -typedef uint8_t mip_gnss_fix_info_data_fix_type; -static const mip_gnss_fix_info_data_fix_type MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_3D = 0; ///< -static const mip_gnss_fix_info_data_fix_type MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_2D = 1; ///< -static const mip_gnss_fix_info_data_fix_type MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_TIME_ONLY = 2; ///< -static const mip_gnss_fix_info_data_fix_type MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_NONE = 3; ///< -static const mip_gnss_fix_info_data_fix_type MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_INVALID = 4; ///< -static const mip_gnss_fix_info_data_fix_type MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_RTK_FLOAT = 5; ///< -static const mip_gnss_fix_info_data_fix_type MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_RTK_FIXED = 6; ///< -static const mip_gnss_fix_info_data_fix_type MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_DIFFERENTIAL = 7; ///< +enum mip_gnss_fix_info_data_fix_type +{ + MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_3D = 0, ///< + MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_2D = 1, ///< + MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_TIME_ONLY = 2, ///< + MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_NONE = 3, ///< + MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_INVALID = 4, ///< + MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_RTK_FLOAT = 5, ///< + MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_RTK_FIXED = 6, ///< + MIP_GNSS_FIX_INFO_DATA_FIX_TYPE_FIX_DIFFERENTIAL = 7, ///< +}; +typedef enum mip_gnss_fix_info_data_fix_type mip_gnss_fix_info_data_fix_type; + +inline void insert_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_fix_info_data_fix_flags; static const mip_gnss_fix_info_data_fix_flags MIP_GNSS_FIX_INFO_DATA_FIX_FLAGS_NONE = 0x0000; static const mip_gnss_fix_info_data_fix_flags MIP_GNSS_FIX_INFO_DATA_FIX_FLAGS_SBAS_USED = 0x0001; ///< static const mip_gnss_fix_info_data_fix_flags MIP_GNSS_FIX_INFO_DATA_FIX_FLAGS_DGNSS_USED = 0x0002; ///< static const mip_gnss_fix_info_data_fix_flags MIP_GNSS_FIX_INFO_DATA_FIX_FLAGS_ALL = 0x0003; +inline void insert_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_fix_info_data_valid_flags; static const mip_gnss_fix_info_data_valid_flags MIP_GNSS_FIX_INFO_DATA_VALID_FLAGS_NONE = 0x0000; @@ -481,6 +600,17 @@ static const mip_gnss_fix_info_data_valid_flags MIP_GNSS_FIX_INFO_DATA_VALID_FLA static const mip_gnss_fix_info_data_valid_flags MIP_GNSS_FIX_INFO_DATA_VALID_FLAGS_FIX_FLAGS = 0x0004; ///< static const mip_gnss_fix_info_data_valid_flags MIP_GNSS_FIX_INFO_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_fix_info_data_valid_flags MIP_GNSS_FIX_INFO_DATA_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_fix_info_data { @@ -488,21 +618,12 @@ struct mip_gnss_fix_info_data uint8_t num_sv; mip_gnss_fix_info_data_fix_flags fix_flags; mip_gnss_fix_info_data_valid_flags valid_flags; - }; typedef struct mip_gnss_fix_info_data mip_gnss_fix_info_data; + void insert_mip_gnss_fix_info_data(microstrain_serializer* serializer, const mip_gnss_fix_info_data* self); void extract_mip_gnss_fix_info_data(microstrain_serializer* serializer, mip_gnss_fix_info_data* self); -bool extract_mip_gnss_fix_info_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self); -void extract_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self); - -void insert_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self); -void extract_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self); - -void insert_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self); -void extract_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self); +bool extract_mip_gnss_fix_info_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -520,6 +641,16 @@ static const mip_gnss_sv_info_data_svflags MIP_GNSS_SV_INFO_DATA_SVFLAGS_NONE static const mip_gnss_sv_info_data_svflags MIP_GNSS_SV_INFO_DATA_SVFLAGS_USED_FOR_NAVIGATION = 0x0001; ///< static const mip_gnss_sv_info_data_svflags MIP_GNSS_SV_INFO_DATA_SVFLAGS_HEALTHY = 0x0002; ///< static const mip_gnss_sv_info_data_svflags MIP_GNSS_SV_INFO_DATA_SVFLAGS_ALL = 0x0003; +inline void insert_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_sv_info_data_valid_flags; static const mip_gnss_sv_info_data_valid_flags MIP_GNSS_SV_INFO_DATA_VALID_FLAGS_NONE = 0x0000; @@ -531,6 +662,17 @@ static const mip_gnss_sv_info_data_valid_flags MIP_GNSS_SV_INFO_DATA_VALID_FLAGS static const mip_gnss_sv_info_data_valid_flags MIP_GNSS_SV_INFO_DATA_VALID_FLAGS_SV_FLAGS = 0x0020; ///< static const mip_gnss_sv_info_data_valid_flags MIP_GNSS_SV_INFO_DATA_VALID_FLAGS_FLAGS = 0x003F; ///< static const mip_gnss_sv_info_data_valid_flags MIP_GNSS_SV_INFO_DATA_VALID_FLAGS_ALL = 0x003F; +inline void insert_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_sv_info_data { @@ -541,18 +683,12 @@ struct mip_gnss_sv_info_data int16_t elevation; ///< [deg] mip_gnss_sv_info_data_svflags sv_flags; mip_gnss_sv_info_data_valid_flags valid_flags; - }; typedef struct mip_gnss_sv_info_data mip_gnss_sv_info_data; + void insert_mip_gnss_sv_info_data(microstrain_serializer* serializer, const mip_gnss_sv_info_data* self); void extract_mip_gnss_sv_info_data(microstrain_serializer* serializer, mip_gnss_sv_info_data* self); -bool extract_mip_gnss_sv_info_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self); -void extract_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self); - -void insert_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self); -void extract_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self); +bool extract_mip_gnss_sv_info_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -563,22 +699,64 @@ void extract_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serialize /// ///@{ -typedef uint8_t mip_gnss_hw_status_data_receiver_state; -static const mip_gnss_hw_status_data_receiver_state MIP_GNSS_HW_STATUS_DATA_RECEIVER_STATE_OFF = 0; ///< -static const mip_gnss_hw_status_data_receiver_state MIP_GNSS_HW_STATUS_DATA_RECEIVER_STATE_ON = 1; ///< -static const mip_gnss_hw_status_data_receiver_state MIP_GNSS_HW_STATUS_DATA_RECEIVER_STATE_UNKNOWN = 2; ///< +enum mip_gnss_hw_status_data_receiver_state +{ + MIP_GNSS_HW_STATUS_DATA_RECEIVER_STATE_OFF = 0, ///< + MIP_GNSS_HW_STATUS_DATA_RECEIVER_STATE_ON = 1, ///< + MIP_GNSS_HW_STATUS_DATA_RECEIVER_STATE_UNKNOWN = 2, ///< +}; +typedef enum mip_gnss_hw_status_data_receiver_state mip_gnss_hw_status_data_receiver_state; + +inline void insert_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} -typedef uint8_t mip_gnss_hw_status_data_antenna_state; -static const mip_gnss_hw_status_data_antenna_state MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_INIT = 1; ///< -static const mip_gnss_hw_status_data_antenna_state MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_SHORT = 2; ///< -static const mip_gnss_hw_status_data_antenna_state MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_OPEN = 3; ///< -static const mip_gnss_hw_status_data_antenna_state MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_GOOD = 4; ///< -static const mip_gnss_hw_status_data_antenna_state MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_UNKNOWN = 5; ///< +enum mip_gnss_hw_status_data_antenna_state +{ + MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_INIT = 1, ///< + MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_SHORT = 2, ///< + MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_OPEN = 3, ///< + MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_GOOD = 4, ///< + MIP_GNSS_HW_STATUS_DATA_ANTENNA_STATE_UNKNOWN = 5, ///< +}; +typedef enum mip_gnss_hw_status_data_antenna_state mip_gnss_hw_status_data_antenna_state; -typedef uint8_t mip_gnss_hw_status_data_antenna_power; -static const mip_gnss_hw_status_data_antenna_power MIP_GNSS_HW_STATUS_DATA_ANTENNA_POWER_OFF = 0; ///< -static const mip_gnss_hw_status_data_antenna_power MIP_GNSS_HW_STATUS_DATA_ANTENNA_POWER_ON = 1; ///< -static const mip_gnss_hw_status_data_antenna_power MIP_GNSS_HW_STATUS_DATA_ANTENNA_POWER_UNKNOWN = 2; ///< +inline void insert_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + +enum mip_gnss_hw_status_data_antenna_power +{ + MIP_GNSS_HW_STATUS_DATA_ANTENNA_POWER_OFF = 0, ///< + MIP_GNSS_HW_STATUS_DATA_ANTENNA_POWER_ON = 1, ///< + MIP_GNSS_HW_STATUS_DATA_ANTENNA_POWER_UNKNOWN = 2, ///< +}; +typedef enum mip_gnss_hw_status_data_antenna_power mip_gnss_hw_status_data_antenna_power; + +inline void insert_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_hw_status_data_valid_flags; static const mip_gnss_hw_status_data_valid_flags MIP_GNSS_HW_STATUS_DATA_VALID_FLAGS_NONE = 0x0000; @@ -587,6 +765,17 @@ static const mip_gnss_hw_status_data_valid_flags MIP_GNSS_HW_STATUS_DATA_VALID_F static const mip_gnss_hw_status_data_valid_flags MIP_GNSS_HW_STATUS_DATA_VALID_FLAGS_ANTENNA_POWER = 0x0004; ///< static const mip_gnss_hw_status_data_valid_flags MIP_GNSS_HW_STATUS_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_hw_status_data_valid_flags MIP_GNSS_HW_STATUS_DATA_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_hw_status_data { @@ -594,24 +783,12 @@ struct mip_gnss_hw_status_data mip_gnss_hw_status_data_antenna_state antenna_state; mip_gnss_hw_status_data_antenna_power antenna_power; mip_gnss_hw_status_data_valid_flags valid_flags; - }; typedef struct mip_gnss_hw_status_data mip_gnss_hw_status_data; + void insert_mip_gnss_hw_status_data(microstrain_serializer* serializer, const mip_gnss_hw_status_data* self); void extract_mip_gnss_hw_status_data(microstrain_serializer* serializer, mip_gnss_hw_status_data* self); -bool extract_mip_gnss_hw_status_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self); -void extract_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self); - -void insert_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self); -void extract_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self); - -void insert_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self); -void extract_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self); - -void insert_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self); -void extract_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self); +bool extract_mip_gnss_hw_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -642,6 +819,17 @@ static const mip_gnss_dgps_info_data_valid_flags MIP_GNSS_DGPS_INFO_DATA_VALID_F static const mip_gnss_dgps_info_data_valid_flags MIP_GNSS_DGPS_INFO_DATA_VALID_FLAGS_NUM_CHANNELS = 0x0008; ///< static const mip_gnss_dgps_info_data_valid_flags MIP_GNSS_DGPS_INFO_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_dgps_info_data_valid_flags MIP_GNSS_DGPS_INFO_DATA_VALID_FLAGS_ALL = 0x000F; +inline void insert_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_dgps_info_data { @@ -650,15 +838,12 @@ struct mip_gnss_dgps_info_data float range_correction; float range_rate_correction; mip_gnss_dgps_info_data_valid_flags valid_flags; - }; typedef struct mip_gnss_dgps_info_data mip_gnss_dgps_info_data; + void insert_mip_gnss_dgps_info_data(microstrain_serializer* serializer, const mip_gnss_dgps_info_data* self); void extract_mip_gnss_dgps_info_data(microstrain_serializer* serializer, mip_gnss_dgps_info_data* self); -bool extract_mip_gnss_dgps_info_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self); -void extract_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self); +bool extract_mip_gnss_dgps_info_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -679,6 +864,17 @@ static const mip_gnss_dgps_channel_data_valid_flags MIP_GNSS_DGPS_CHANNEL_DATA_V static const mip_gnss_dgps_channel_data_valid_flags MIP_GNSS_DGPS_CHANNEL_DATA_VALID_FLAGS_RANGE_RATE_CORRECTION = 0x0008; ///< static const mip_gnss_dgps_channel_data_valid_flags MIP_GNSS_DGPS_CHANNEL_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_dgps_channel_data_valid_flags MIP_GNSS_DGPS_CHANNEL_DATA_VALID_FLAGS_ALL = 0x000F; +inline void insert_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_dgps_channel_data { @@ -687,15 +883,12 @@ struct mip_gnss_dgps_channel_data float range_correction; ///< [m] float range_rate_correction; ///< [m/s] mip_gnss_dgps_channel_data_valid_flags valid_flags; - }; typedef struct mip_gnss_dgps_channel_data mip_gnss_dgps_channel_data; + void insert_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data* self); void extract_mip_gnss_dgps_channel_data(microstrain_serializer* serializer, mip_gnss_dgps_channel_data* self); -bool extract_mip_gnss_dgps_channel_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self); -void extract_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self); +bool extract_mip_gnss_dgps_channel_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -716,6 +909,17 @@ static const mip_gnss_clock_info_2_data_valid_flags MIP_GNSS_CLOCK_INFO_2_DATA_V static const mip_gnss_clock_info_2_data_valid_flags MIP_GNSS_CLOCK_INFO_2_DATA_VALID_FLAGS_DRIFT_ACCURACY = 0x0008; ///< static const mip_gnss_clock_info_2_data_valid_flags MIP_GNSS_CLOCK_INFO_2_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_clock_info_2_data_valid_flags MIP_GNSS_CLOCK_INFO_2_DATA_VALID_FLAGS_ALL = 0x000F; +inline void insert_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_clock_info_2_data { @@ -724,15 +928,12 @@ struct mip_gnss_clock_info_2_data double bias_accuracy_estimate; double drift_accuracy_estimate; mip_gnss_clock_info_2_data_valid_flags valid_flags; - }; typedef struct mip_gnss_clock_info_2_data mip_gnss_clock_info_2_data; + void insert_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data* self); void extract_mip_gnss_clock_info_2_data(microstrain_serializer* serializer, mip_gnss_clock_info_2_data* self); -bool extract_mip_gnss_clock_info_2_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self); -void extract_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self); +bool extract_mip_gnss_clock_info_2_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -747,20 +948,28 @@ typedef uint16_t mip_gnss_gps_leap_seconds_data_valid_flags; static const mip_gnss_gps_leap_seconds_data_valid_flags MIP_GNSS_GPS_LEAP_SECONDS_DATA_VALID_FLAGS_NONE = 0x0000; static const mip_gnss_gps_leap_seconds_data_valid_flags MIP_GNSS_GPS_LEAP_SECONDS_DATA_VALID_FLAGS_LEAP_SECONDS = 0x0002; ///< static const mip_gnss_gps_leap_seconds_data_valid_flags MIP_GNSS_GPS_LEAP_SECONDS_DATA_VALID_FLAGS_ALL = 0x0002; +inline void insert_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_gps_leap_seconds_data { uint8_t leap_seconds; ///< [s] mip_gnss_gps_leap_seconds_data_valid_flags valid_flags; - }; typedef struct mip_gnss_gps_leap_seconds_data mip_gnss_gps_leap_seconds_data; + void insert_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data* self); void extract_mip_gnss_gps_leap_seconds_data(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data* self); -bool extract_mip_gnss_gps_leap_seconds_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self); -void extract_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self); +bool extract_mip_gnss_gps_leap_seconds_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -778,6 +987,16 @@ static const mip_gnss_sbas_info_data_sbas_status MIP_GNSS_SBAS_INFO_DATA_SBAS_ST static const mip_gnss_sbas_info_data_sbas_status MIP_GNSS_SBAS_INFO_DATA_SBAS_STATUS_INTEGRITY_AVAILABLE = 0x04; ///< static const mip_gnss_sbas_info_data_sbas_status MIP_GNSS_SBAS_INFO_DATA_SBAS_STATUS_TEST_MODE = 0x08; ///< static const mip_gnss_sbas_info_data_sbas_status MIP_GNSS_SBAS_INFO_DATA_SBAS_STATUS_ALL = 0x0F; +inline void insert_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_sbas_info_data_valid_flags; static const mip_gnss_sbas_info_data_valid_flags MIP_GNSS_SBAS_INFO_DATA_VALID_FLAGS_NONE = 0x0000; @@ -789,6 +1008,17 @@ static const mip_gnss_sbas_info_data_valid_flags MIP_GNSS_SBAS_INFO_DATA_VALID_F static const mip_gnss_sbas_info_data_valid_flags MIP_GNSS_SBAS_INFO_DATA_VALID_FLAGS_SBAS_STATUS = 0x0020; ///< static const mip_gnss_sbas_info_data_valid_flags MIP_GNSS_SBAS_INFO_DATA_VALID_FLAGS_FLAGS = 0x003F; ///< static const mip_gnss_sbas_info_data_valid_flags MIP_GNSS_SBAS_INFO_DATA_VALID_FLAGS_ALL = 0x003F; +inline void insert_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_sbas_info_data { @@ -799,18 +1029,12 @@ struct mip_gnss_sbas_info_data uint8_t count; ///< Number of SBAS corrections mip_gnss_sbas_info_data_sbas_status sbas_status; ///< Status of the SBAS service mip_gnss_sbas_info_data_valid_flags valid_flags; - }; typedef struct mip_gnss_sbas_info_data mip_gnss_sbas_info_data; + void insert_mip_gnss_sbas_info_data(microstrain_serializer* serializer, const mip_gnss_sbas_info_data* self); void extract_mip_gnss_sbas_info_data(microstrain_serializer* serializer, mip_gnss_sbas_info_data* self); -bool extract_mip_gnss_sbas_info_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self); -void extract_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self); - -void insert_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self); -void extract_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self); +bool extract_mip_gnss_sbas_info_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -850,6 +1074,17 @@ static const mip_gnss_sbas_correction_data_valid_flags MIP_GNSS_SBAS_CORRECTION_ static const mip_gnss_sbas_correction_data_valid_flags MIP_GNSS_SBAS_CORRECTION_DATA_VALID_FLAGS_IONO_CORRECTION = 0x0004; ///< static const mip_gnss_sbas_correction_data_valid_flags MIP_GNSS_SBAS_CORRECTION_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_sbas_correction_data_valid_flags MIP_GNSS_SBAS_CORRECTION_DATA_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_sbas_correction_data { @@ -863,15 +1098,12 @@ struct mip_gnss_sbas_correction_data float pseudorange_correction; ///< Pseudo-range correction [meters]. float iono_correction; ///< Ionospheric correction [meters]. mip_gnss_sbas_correction_data_valid_flags valid_flags; - }; typedef struct mip_gnss_sbas_correction_data mip_gnss_sbas_correction_data; + void insert_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data* self); void extract_mip_gnss_sbas_correction_data(microstrain_serializer* serializer, mip_gnss_sbas_correction_data* self); -bool extract_mip_gnss_sbas_correction_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self); -void extract_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self); +bool extract_mip_gnss_sbas_correction_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -882,23 +1114,65 @@ void extract_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* s /// ///@{ -typedef uint8_t mip_gnss_rf_error_detection_data_rfband; -static const mip_gnss_rf_error_detection_data_rfband MIP_GNSS_RF_ERROR_DETECTION_DATA_RFBAND_UNKNOWN = 0; ///< -static const mip_gnss_rf_error_detection_data_rfband MIP_GNSS_RF_ERROR_DETECTION_DATA_RFBAND_L1 = 1; ///< -static const mip_gnss_rf_error_detection_data_rfband MIP_GNSS_RF_ERROR_DETECTION_DATA_RFBAND_L2 = 2; ///< -static const mip_gnss_rf_error_detection_data_rfband MIP_GNSS_RF_ERROR_DETECTION_DATA_RFBAND_L5 = 5; ///< +enum mip_gnss_rf_error_detection_data_rfband +{ + MIP_GNSS_RF_ERROR_DETECTION_DATA_RFBAND_UNKNOWN = 0, ///< + MIP_GNSS_RF_ERROR_DETECTION_DATA_RFBAND_L1 = 1, ///< + MIP_GNSS_RF_ERROR_DETECTION_DATA_RFBAND_L2 = 2, ///< + MIP_GNSS_RF_ERROR_DETECTION_DATA_RFBAND_L5 = 5, ///< +}; +typedef enum mip_gnss_rf_error_detection_data_rfband mip_gnss_rf_error_detection_data_rfband; + +inline void insert_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} -typedef uint8_t mip_gnss_rf_error_detection_data_jamming_state; -static const mip_gnss_rf_error_detection_data_jamming_state MIP_GNSS_RF_ERROR_DETECTION_DATA_JAMMING_STATE_UNKNOWN = 0; ///< -static const mip_gnss_rf_error_detection_data_jamming_state MIP_GNSS_RF_ERROR_DETECTION_DATA_JAMMING_STATE_NONE = 1; ///< -static const mip_gnss_rf_error_detection_data_jamming_state MIP_GNSS_RF_ERROR_DETECTION_DATA_JAMMING_STATE_PARTIAL = 2; ///< -static const mip_gnss_rf_error_detection_data_jamming_state MIP_GNSS_RF_ERROR_DETECTION_DATA_JAMMING_STATE_SIGNIFICANT = 3; ///< +enum mip_gnss_rf_error_detection_data_jamming_state +{ + MIP_GNSS_RF_ERROR_DETECTION_DATA_JAMMING_STATE_UNKNOWN = 0, ///< + MIP_GNSS_RF_ERROR_DETECTION_DATA_JAMMING_STATE_NONE = 1, ///< + MIP_GNSS_RF_ERROR_DETECTION_DATA_JAMMING_STATE_PARTIAL = 2, ///< + MIP_GNSS_RF_ERROR_DETECTION_DATA_JAMMING_STATE_SIGNIFICANT = 3, ///< +}; +typedef enum mip_gnss_rf_error_detection_data_jamming_state mip_gnss_rf_error_detection_data_jamming_state; -typedef uint8_t mip_gnss_rf_error_detection_data_spoofing_state; -static const mip_gnss_rf_error_detection_data_spoofing_state MIP_GNSS_RF_ERROR_DETECTION_DATA_SPOOFING_STATE_UNKNOWN = 0; ///< -static const mip_gnss_rf_error_detection_data_spoofing_state MIP_GNSS_RF_ERROR_DETECTION_DATA_SPOOFING_STATE_NONE = 1; ///< -static const mip_gnss_rf_error_detection_data_spoofing_state MIP_GNSS_RF_ERROR_DETECTION_DATA_SPOOFING_STATE_PARTIAL = 2; ///< -static const mip_gnss_rf_error_detection_data_spoofing_state MIP_GNSS_RF_ERROR_DETECTION_DATA_SPOOFING_STATE_SIGNIFICANT = 3; ///< +inline void insert_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} + +enum mip_gnss_rf_error_detection_data_spoofing_state +{ + MIP_GNSS_RF_ERROR_DETECTION_DATA_SPOOFING_STATE_UNKNOWN = 0, ///< + MIP_GNSS_RF_ERROR_DETECTION_DATA_SPOOFING_STATE_NONE = 1, ///< + MIP_GNSS_RF_ERROR_DETECTION_DATA_SPOOFING_STATE_PARTIAL = 2, ///< + MIP_GNSS_RF_ERROR_DETECTION_DATA_SPOOFING_STATE_SIGNIFICANT = 3, ///< +}; +typedef enum mip_gnss_rf_error_detection_data_spoofing_state mip_gnss_rf_error_detection_data_spoofing_state; + +inline void insert_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_rf_error_detection_data_valid_flags; static const mip_gnss_rf_error_detection_data_valid_flags MIP_GNSS_RF_ERROR_DETECTION_DATA_VALID_FLAGS_NONE = 0x0000; @@ -907,6 +1181,17 @@ static const mip_gnss_rf_error_detection_data_valid_flags MIP_GNSS_RF_ERROR_DETE static const mip_gnss_rf_error_detection_data_valid_flags MIP_GNSS_RF_ERROR_DETECTION_DATA_VALID_FLAGS_SPOOFING_STATE = 0x0004; ///< static const mip_gnss_rf_error_detection_data_valid_flags MIP_GNSS_RF_ERROR_DETECTION_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_rf_error_detection_data_valid_flags MIP_GNSS_RF_ERROR_DETECTION_DATA_VALID_FLAGS_ALL = 0x0007; +inline void insert_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_rf_error_detection_data { @@ -915,24 +1200,12 @@ struct mip_gnss_rf_error_detection_data mip_gnss_rf_error_detection_data_spoofing_state spoofing_state; ///< GNSS Spoofing State (as reported by the GNSS module) uint8_t reserved[4]; ///< Reserved for future use mip_gnss_rf_error_detection_data_valid_flags valid_flags; - }; typedef struct mip_gnss_rf_error_detection_data mip_gnss_rf_error_detection_data; + void insert_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data* self); void extract_mip_gnss_rf_error_detection_data(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data* self); -bool extract_mip_gnss_rf_error_detection_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self); -void extract_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self); - -void insert_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self); -void extract_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self); - -void insert_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self); -void extract_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self); - -void insert_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self); -void extract_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self); +bool extract_mip_gnss_rf_error_detection_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -957,6 +1230,16 @@ static const mip_gnss_base_station_info_data_indicator_flags MIP_GNSS_BASE_STATI static const mip_gnss_base_station_info_data_indicator_flags MIP_GNSS_BASE_STATION_INFO_DATA_INDICATOR_FLAGS_QUARTER_CYCLE_BIT2 = 0x0080; ///< static const mip_gnss_base_station_info_data_indicator_flags MIP_GNSS_BASE_STATION_INFO_DATA_INDICATOR_FLAGS_QUARTER_CYCLE_BITS = 0x00C0; ///< static const mip_gnss_base_station_info_data_indicator_flags MIP_GNSS_BASE_STATION_INFO_DATA_INDICATOR_FLAGS_ALL = 0x00FF; +inline void insert_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_base_station_info_data_valid_flags; static const mip_gnss_base_station_info_data_valid_flags MIP_GNSS_BASE_STATION_INFO_DATA_VALID_FLAGS_NONE = 0x0000; @@ -968,6 +1251,17 @@ static const mip_gnss_base_station_info_data_valid_flags MIP_GNSS_BASE_STATION_I static const mip_gnss_base_station_info_data_valid_flags MIP_GNSS_BASE_STATION_INFO_DATA_VALID_FLAGS_INDICATORS = 0x0020; ///< static const mip_gnss_base_station_info_data_valid_flags MIP_GNSS_BASE_STATION_INFO_DATA_VALID_FLAGS_FLAGS = 0x003F; ///< static const mip_gnss_base_station_info_data_valid_flags MIP_GNSS_BASE_STATION_INFO_DATA_VALID_FLAGS_ALL = 0x003F; +inline void insert_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_base_station_info_data { @@ -978,18 +1272,12 @@ struct mip_gnss_base_station_info_data uint16_t station_id; ///< Range: 0-4095 mip_gnss_base_station_info_data_indicator_flags indicators; ///< Bitfield mip_gnss_base_station_info_data_valid_flags valid_flags; - }; typedef struct mip_gnss_base_station_info_data mip_gnss_base_station_info_data; + void insert_mip_gnss_base_station_info_data(microstrain_serializer* serializer, const mip_gnss_base_station_info_data* self); void extract_mip_gnss_base_station_info_data(microstrain_serializer* serializer, mip_gnss_base_station_info_data* self); -bool extract_mip_gnss_base_station_info_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self); -void extract_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self); - -void insert_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self); -void extract_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self); +bool extract_mip_gnss_base_station_info_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1011,6 +1299,16 @@ static const mip_gnss_rtk_corrections_status_data_valid_flags MIP_GNSS_RTK_CORRE static const mip_gnss_rtk_corrections_status_data_valid_flags MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_VALID_FLAGS_BEIDOU_LATENCY = 0x0080; ///< static const mip_gnss_rtk_corrections_status_data_valid_flags MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_VALID_FLAGS_FLAGS = 0x00FF; ///< static const mip_gnss_rtk_corrections_status_data_valid_flags MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_VALID_FLAGS_ALL = 0x00FF; +inline void insert_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_rtk_corrections_status_data_epoch_status; static const mip_gnss_rtk_corrections_status_data_epoch_status MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_EPOCH_STATUS_NONE = 0x0000; @@ -1024,6 +1322,17 @@ static const mip_gnss_rtk_corrections_status_data_epoch_status MIP_GNSS_RTK_CORR static const mip_gnss_rtk_corrections_status_data_epoch_status MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_EPOCH_STATUS_USING_GLONASS_MSM_MESSAGES = 0x0080; ///< Using MSM messages for GLONASS corrections instead of RTCM messages 1009-1012 static const mip_gnss_rtk_corrections_status_data_epoch_status MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_EPOCH_STATUS_DONGLE_STATUS_READ_FAILED = 0x0100; ///< A read of the dongle status was attempted, but failed static const mip_gnss_rtk_corrections_status_data_epoch_status MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_EPOCH_STATUS_ALL = 0x01FF; +inline void insert_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_rtk_corrections_status_data { @@ -1037,18 +1346,12 @@ struct mip_gnss_rtk_corrections_status_data float beidou_correction_latency; ///< Latency of last Beidou correction [seconds] uint32_t reserved[4]; ///< Reserved for future use mip_gnss_rtk_corrections_status_data_valid_flags valid_flags; - }; typedef struct mip_gnss_rtk_corrections_status_data mip_gnss_rtk_corrections_status_data; + void insert_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data* self); void extract_mip_gnss_rtk_corrections_status_data(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data* self); -bool extract_mip_gnss_rtk_corrections_status_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self); -void extract_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self); - -void insert_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self); -void extract_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self); +bool extract_mip_gnss_rtk_corrections_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1070,6 +1373,17 @@ static const mip_gnss_satellite_status_data_valid_flags MIP_GNSS_SATELLITE_STATU static const mip_gnss_satellite_status_data_valid_flags MIP_GNSS_SATELLITE_STATUS_DATA_VALID_FLAGS_HEALTH = 0x0040; ///< static const mip_gnss_satellite_status_data_valid_flags MIP_GNSS_SATELLITE_STATUS_DATA_VALID_FLAGS_FLAGS = 0x007F; ///< static const mip_gnss_satellite_status_data_valid_flags MIP_GNSS_SATELLITE_STATUS_DATA_VALID_FLAGS_ALL = 0x007F; +inline void insert_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_satellite_status_data { @@ -1083,15 +1397,12 @@ struct mip_gnss_satellite_status_data float azimuth; ///< Azimuth of the satellite relative to the rover [degrees] bool health; ///< True if the satellite is healthy. mip_gnss_satellite_status_data_valid_flags valid_flags; - }; typedef struct mip_gnss_satellite_status_data mip_gnss_satellite_status_data; + void insert_mip_gnss_satellite_status_data(microstrain_serializer* serializer, const mip_gnss_satellite_status_data* self); void extract_mip_gnss_satellite_status_data(microstrain_serializer* serializer, mip_gnss_satellite_status_data* self); -bool extract_mip_gnss_satellite_status_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self); -void extract_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self); +bool extract_mip_gnss_satellite_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1102,13 +1413,27 @@ void extract_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* /// ///@{ -typedef uint8_t mip_gnss_raw_data_gnss_signal_quality; -static const mip_gnss_raw_data_gnss_signal_quality MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_NONE = 0; ///< -static const mip_gnss_raw_data_gnss_signal_quality MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_SEARCHING = 1; ///< -static const mip_gnss_raw_data_gnss_signal_quality MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_ACQUIRED = 2; ///< -static const mip_gnss_raw_data_gnss_signal_quality MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_UNUSABLE = 3; ///< -static const mip_gnss_raw_data_gnss_signal_quality MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_TIME_LOCKED = 4; ///< -static const mip_gnss_raw_data_gnss_signal_quality MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_FULLY_LOCKED = 5; ///< +enum mip_gnss_raw_data_gnss_signal_quality +{ + MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_NONE = 0, ///< + MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_SEARCHING = 1, ///< + MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_ACQUIRED = 2, ///< + MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_UNUSABLE = 3, ///< + MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_TIME_LOCKED = 4, ///< + MIP_GNSS_RAW_DATA_GNSS_SIGNAL_QUALITY_FULLY_LOCKED = 5, ///< +}; +typedef enum mip_gnss_raw_data_gnss_signal_quality mip_gnss_raw_data_gnss_signal_quality; + +inline void insert_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self) +{ + microstrain_insert_u8(serializer, (uint8_t)(self)); +} +inline void extract_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self) +{ + uint8_t tmp = 0; + microstrain_extract_u8(serializer, &tmp); + *self = tmp; +} typedef uint16_t mip_gnss_raw_data_valid_flags; static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_NONE = 0x0000; @@ -1130,6 +1455,17 @@ static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_DOPPLER static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_LOCK_TIME = 0x8000; ///< static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_FLAGS = 0xFFFF; ///< static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_ALL = 0xFFFF; +inline void insert_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_raw_data { @@ -1152,18 +1488,12 @@ struct mip_gnss_raw_data float doppler_uncert; ///< Uncertainty of the measured doppler shift [Hz]. float lock_time; ///< DOC Minimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver. mip_gnss_raw_data_valid_flags valid_flags; - }; typedef struct mip_gnss_raw_data mip_gnss_raw_data; + void insert_mip_gnss_raw_data(microstrain_serializer* serializer, const mip_gnss_raw_data* self); void extract_mip_gnss_raw_data(microstrain_serializer* serializer, mip_gnss_raw_data* self); -bool extract_mip_gnss_raw_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self); -void extract_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self); - -void insert_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self); -void extract_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self); +bool extract_mip_gnss_raw_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1180,6 +1510,17 @@ static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_MODERN_DATA = 0x0002; ///< static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0003; +inline void insert_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_gps_ephemeris_data { @@ -1217,15 +1558,12 @@ struct mip_gnss_gps_ephemeris_data double c_rc; ///< Harmonic Correction Term. double c_rs; ///< Harmonic Correction Term. mip_gnss_gps_ephemeris_data_valid_flags valid_flags; - }; typedef struct mip_gnss_gps_ephemeris_data mip_gnss_gps_ephemeris_data; + void insert_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data* self); void extract_mip_gnss_gps_ephemeris_data(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data* self); -bool extract_mip_gnss_gps_ephemeris_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self); -void extract_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self); +bool extract_mip_gnss_gps_ephemeris_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1242,6 +1580,17 @@ static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEME static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_MODERN_DATA = 0x0002; ///< static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0003; +inline void insert_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_galileo_ephemeris_data { @@ -1279,15 +1628,12 @@ struct mip_gnss_galileo_ephemeris_data double c_rc; ///< Harmonic Correction Term. double c_rs; ///< Harmonic Correction Term. mip_gnss_galileo_ephemeris_data_valid_flags valid_flags; - }; typedef struct mip_gnss_galileo_ephemeris_data mip_gnss_galileo_ephemeris_data; + void insert_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data* self); void extract_mip_gnss_galileo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data* self); -bool extract_mip_gnss_galileo_ephemeris_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self); -void extract_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self); +bool extract_mip_gnss_galileo_ephemeris_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1303,6 +1649,17 @@ static const mip_gnss_glo_ephemeris_data_valid_flags MIP_GNSS_GLO_EPHEMERIS_DATA static const mip_gnss_glo_ephemeris_data_valid_flags MIP_GNSS_GLO_EPHEMERIS_DATA_VALID_FLAGS_EPHEMERIS = 0x0001; ///< static const mip_gnss_glo_ephemeris_data_valid_flags MIP_GNSS_GLO_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0001; ///< static const mip_gnss_glo_ephemeris_data_valid_flags MIP_GNSS_GLO_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0001; +inline void insert_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_glo_ephemeris_data { @@ -1331,15 +1688,12 @@ struct mip_gnss_glo_ephemeris_data uint8_t P3; ///< Number of satellites in almanac for this frame uint8_t P4; ///< Flag indicating ephemeris parameters are present mip_gnss_glo_ephemeris_data_valid_flags valid_flags; - }; typedef struct mip_gnss_glo_ephemeris_data mip_gnss_glo_ephemeris_data; + void insert_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data* self); void extract_mip_gnss_glo_ephemeris_data(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data* self); -bool extract_mip_gnss_glo_ephemeris_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self); -void extract_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self); +bool extract_mip_gnss_glo_ephemeris_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1358,6 +1712,17 @@ static const mip_gnss_gps_iono_corr_data_valid_flags MIP_GNSS_GPS_IONO_CORR_DATA static const mip_gnss_gps_iono_corr_data_valid_flags MIP_GNSS_GPS_IONO_CORR_DATA_VALID_FLAGS_BETA = 0x0008; ///< static const mip_gnss_gps_iono_corr_data_valid_flags MIP_GNSS_GPS_IONO_CORR_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_gps_iono_corr_data_valid_flags MIP_GNSS_GPS_IONO_CORR_DATA_VALID_FLAGS_ALL = 0x000F; +inline void insert_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_gps_iono_corr_data { @@ -1366,15 +1731,12 @@ struct mip_gnss_gps_iono_corr_data double alpha[4]; ///< Ionospheric Correction Terms. double beta[4]; ///< Ionospheric Correction Terms. mip_gnss_gps_iono_corr_data_valid_flags valid_flags; - }; typedef struct mip_gnss_gps_iono_corr_data mip_gnss_gps_iono_corr_data; + void insert_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data* self); void extract_mip_gnss_gps_iono_corr_data(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data* self); -bool extract_mip_gnss_gps_iono_corr_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self); -void extract_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self); +bool extract_mip_gnss_gps_iono_corr_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -1393,6 +1755,17 @@ static const mip_gnss_galileo_iono_corr_data_valid_flags MIP_GNSS_GALILEO_IONO_C static const mip_gnss_galileo_iono_corr_data_valid_flags MIP_GNSS_GALILEO_IONO_CORR_DATA_VALID_FLAGS_DISTURBANCE_FLAGS = 0x0008; ///< static const mip_gnss_galileo_iono_corr_data_valid_flags MIP_GNSS_GALILEO_IONO_CORR_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_galileo_iono_corr_data_valid_flags MIP_GNSS_GALILEO_IONO_CORR_DATA_VALID_FLAGS_ALL = 0x000F; +inline void insert_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_gnss_galileo_iono_corr_data { @@ -1401,15 +1774,12 @@ struct mip_gnss_galileo_iono_corr_data mip_vector3d alpha; ///< Coefficients for the model. uint8_t disturbance_flags; ///< Region disturbance flags (bits 1-5). mip_gnss_galileo_iono_corr_data_valid_flags valid_flags; - }; typedef struct mip_gnss_galileo_iono_corr_data mip_gnss_galileo_iono_corr_data; + void insert_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data* self); void extract_mip_gnss_galileo_iono_corr_data(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data* self); -bool extract_mip_gnss_galileo_iono_corr_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self); -void extract_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self); +bool extract_mip_gnss_galileo_iono_corr_data_from_field(const mip_field_view* field, void* ptr); ///@} diff --git a/src/c/mip/definitions/data_sensor.c b/src/c/mip/definitions/data_sensor.c index cfb5c95c5..15f3c6cb0 100644 --- a/src/c/mip/definitions/data_sensor.c +++ b/src/c/mip/definitions/data_sensor.c @@ -13,14 +13,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; - - -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// @@ -29,21 +21,19 @@ struct mip_field; void insert_mip_sensor_raw_accel_data(microstrain_serializer* serializer, const mip_sensor_raw_accel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->raw_accel[i]); + insert_mip_vector3f(serializer, self->raw_accel); } void extract_mip_sensor_raw_accel_data(microstrain_serializer* serializer, mip_sensor_raw_accel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->raw_accel[i]); + extract_mip_vector3f(serializer, self->raw_accel); } bool extract_mip_sensor_raw_accel_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_raw_accel_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_accel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -51,21 +41,19 @@ bool extract_mip_sensor_raw_accel_data_from_field(const mip_field_view* field, v void insert_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, const mip_sensor_raw_gyro_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->raw_gyro[i]); + insert_mip_vector3f(serializer, self->raw_gyro); } void extract_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, mip_sensor_raw_gyro_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->raw_gyro[i]); + extract_mip_vector3f(serializer, self->raw_gyro); } bool extract_mip_sensor_raw_gyro_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_raw_gyro_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_gyro_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -73,21 +61,19 @@ bool extract_mip_sensor_raw_gyro_data_from_field(const mip_field_view* field, vo void insert_mip_sensor_raw_mag_data(microstrain_serializer* serializer, const mip_sensor_raw_mag_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->raw_mag[i]); + insert_mip_vector3f(serializer, self->raw_mag); } void extract_mip_sensor_raw_mag_data(microstrain_serializer* serializer, mip_sensor_raw_mag_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->raw_mag[i]); + extract_mip_vector3f(serializer, self->raw_mag); } bool extract_mip_sensor_raw_mag_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_raw_mag_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_mag_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -107,7 +93,7 @@ bool extract_mip_sensor_raw_pressure_data_from_field(const mip_field_view* field { assert(ptr); mip_sensor_raw_pressure_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_raw_pressure_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -115,21 +101,19 @@ bool extract_mip_sensor_raw_pressure_data_from_field(const mip_field_view* field void insert_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, const mip_sensor_scaled_accel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->scaled_accel[i]); + insert_mip_vector3f(serializer, self->scaled_accel); } void extract_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, mip_sensor_scaled_accel_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->scaled_accel[i]); + extract_mip_vector3f(serializer, self->scaled_accel); } bool extract_mip_sensor_scaled_accel_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_scaled_accel_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_accel_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -137,21 +121,19 @@ bool extract_mip_sensor_scaled_accel_data_from_field(const mip_field_view* field void insert_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, const mip_sensor_scaled_gyro_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->scaled_gyro[i]); + insert_mip_vector3f(serializer, self->scaled_gyro); } void extract_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, mip_sensor_scaled_gyro_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->scaled_gyro[i]); + extract_mip_vector3f(serializer, self->scaled_gyro); } bool extract_mip_sensor_scaled_gyro_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_scaled_gyro_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_gyro_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -159,21 +141,19 @@ bool extract_mip_sensor_scaled_gyro_data_from_field(const mip_field_view* field, void insert_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, const mip_sensor_scaled_mag_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->scaled_mag[i]); + insert_mip_vector3f(serializer, self->scaled_mag); } void extract_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, mip_sensor_scaled_mag_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->scaled_mag[i]); + extract_mip_vector3f(serializer, self->scaled_mag); } bool extract_mip_sensor_scaled_mag_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_scaled_mag_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_mag_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -193,7 +173,7 @@ bool extract_mip_sensor_scaled_pressure_data_from_field(const mip_field_view* fi { assert(ptr); mip_sensor_scaled_pressure_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_scaled_pressure_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -201,21 +181,19 @@ bool extract_mip_sensor_scaled_pressure_data_from_field(const mip_field_view* fi void insert_mip_sensor_delta_theta_data(microstrain_serializer* serializer, const mip_sensor_delta_theta_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->delta_theta[i]); + insert_mip_vector3f(serializer, self->delta_theta); } void extract_mip_sensor_delta_theta_data(microstrain_serializer* serializer, mip_sensor_delta_theta_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->delta_theta[i]); + extract_mip_vector3f(serializer, self->delta_theta); } bool extract_mip_sensor_delta_theta_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_delta_theta_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_delta_theta_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -223,21 +201,19 @@ bool extract_mip_sensor_delta_theta_data_from_field(const mip_field_view* field, void insert_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, const mip_sensor_delta_velocity_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->delta_velocity[i]); + insert_mip_vector3f(serializer, self->delta_velocity); } void extract_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, mip_sensor_delta_velocity_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->delta_velocity[i]); + extract_mip_vector3f(serializer, self->delta_velocity); } bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_delta_velocity_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_delta_velocity_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -245,21 +221,19 @@ bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field_view* fie void insert_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->m[i]); + insert_mip_matrix3f(serializer, self->m); } void extract_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->m[i]); + extract_mip_matrix3f(serializer, self->m); } bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_comp_orientation_matrix_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_orientation_matrix_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -267,21 +241,19 @@ bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const mip_field_ void insert_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, const mip_sensor_comp_quaternion_data* self) { - for(unsigned int i=0; i < 4; i++) - microstrain_insert_float(serializer, self->q[i]); + insert_mip_quatf(serializer, self->q); } void extract_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, mip_sensor_comp_quaternion_data* self) { - for(unsigned int i=0; i < 4; i++) - microstrain_extract_float(serializer, &self->q[i]); + extract_mip_quatf(serializer, self->q); } bool extract_mip_sensor_comp_quaternion_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_comp_quaternion_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_quaternion_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -290,18 +262,18 @@ bool extract_mip_sensor_comp_quaternion_data_from_field(const mip_field_view* fi void insert_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, const mip_sensor_comp_euler_angles_data* self) { microstrain_insert_float(serializer, self->roll); - + microstrain_insert_float(serializer, self->pitch); - + microstrain_insert_float(serializer, self->yaw); } void extract_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, mip_sensor_comp_euler_angles_data* self) { microstrain_extract_float(serializer, &self->roll); - + microstrain_extract_float(serializer, &self->pitch); - + microstrain_extract_float(serializer, &self->yaw); } @@ -309,7 +281,7 @@ bool extract_mip_sensor_comp_euler_angles_data_from_field(const mip_field_view* { assert(ptr); mip_sensor_comp_euler_angles_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_euler_angles_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -317,21 +289,19 @@ bool extract_mip_sensor_comp_euler_angles_data_from_field(const mip_field_view* void insert_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_insert_float(serializer, self->m[i]); + insert_mip_matrix3f(serializer, self->m); } void extract_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self) { - for(unsigned int i=0; i < 9; i++) - microstrain_extract_float(serializer, &self->m[i]); + extract_mip_matrix3f(serializer, self->m); } bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_comp_orientation_update_matrix_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_comp_orientation_update_matrix_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -353,7 +323,7 @@ bool extract_mip_sensor_orientation_raw_temp_data_from_field(const mip_field_vie { assert(ptr); mip_sensor_orientation_raw_temp_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_orientation_raw_temp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -373,7 +343,7 @@ bool extract_mip_sensor_internal_timestamp_data_from_field(const mip_field_view* { assert(ptr); mip_sensor_internal_timestamp_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_internal_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -382,14 +352,14 @@ bool extract_mip_sensor_internal_timestamp_data_from_field(const mip_field_view* void insert_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_pps_timestamp_data* self) { microstrain_insert_u32(serializer, self->seconds); - + microstrain_insert_u32(serializer, self->useconds); } void extract_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, mip_sensor_pps_timestamp_data* self) { microstrain_extract_u32(serializer, &self->seconds); - + microstrain_extract_u32(serializer, &self->useconds); } @@ -397,7 +367,7 @@ bool extract_mip_sensor_pps_timestamp_data_from_field(const mip_field_view* fiel { assert(ptr); mip_sensor_pps_timestamp_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_pps_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -406,7 +376,7 @@ bool extract_mip_sensor_pps_timestamp_data_from_field(const mip_field_view* fiel void insert_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data* self) { microstrain_insert_double(serializer, self->tow); - + microstrain_insert_u16(serializer, self->week_number); insert_mip_sensor_gps_timestamp_data_valid_flags(serializer, self->valid_flags); @@ -415,7 +385,7 @@ void insert_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, co void extract_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data* self) { microstrain_extract_double(serializer, &self->tow); - + microstrain_extract_u16(serializer, &self->week_number); extract_mip_sensor_gps_timestamp_data_valid_flags(serializer, &self->valid_flags); @@ -425,38 +395,27 @@ bool extract_mip_sensor_gps_timestamp_data_from_field(const mip_field_view* fiel { assert(ptr); mip_sensor_gps_timestamp_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_gps_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, const mip_sensor_temperature_abs_data* self) { microstrain_insert_float(serializer, self->min_temp); - + microstrain_insert_float(serializer, self->max_temp); - + microstrain_insert_float(serializer, self->mean_temp); } void extract_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, mip_sensor_temperature_abs_data* self) { microstrain_extract_float(serializer, &self->min_temp); - + microstrain_extract_float(serializer, &self->max_temp); - + microstrain_extract_float(serializer, &self->mean_temp); } @@ -464,7 +423,7 @@ bool extract_mip_sensor_temperature_abs_data_from_field(const mip_field_view* fi { assert(ptr); mip_sensor_temperature_abs_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_temperature_abs_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -472,21 +431,19 @@ bool extract_mip_sensor_temperature_abs_data_from_field(const mip_field_view* fi void insert_mip_sensor_up_vector_data(microstrain_serializer* serializer, const mip_sensor_up_vector_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->up[i]); + insert_mip_vector3f(serializer, self->up); } void extract_mip_sensor_up_vector_data(microstrain_serializer* serializer, mip_sensor_up_vector_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->up[i]); + extract_mip_vector3f(serializer, self->up); } bool extract_mip_sensor_up_vector_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_up_vector_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_up_vector_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -494,21 +451,19 @@ bool extract_mip_sensor_up_vector_data_from_field(const mip_field_view* field, v void insert_mip_sensor_north_vector_data(microstrain_serializer* serializer, const mip_sensor_north_vector_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_insert_float(serializer, self->north[i]); + insert_mip_vector3f(serializer, self->north); } void extract_mip_sensor_north_vector_data(microstrain_serializer* serializer, mip_sensor_north_vector_data* self) { - for(unsigned int i=0; i < 3; i++) - microstrain_extract_float(serializer, &self->north[i]); + extract_mip_vector3f(serializer, self->north); } bool extract_mip_sensor_north_vector_data_from_field(const mip_field_view* field, void* ptr) { assert(ptr); mip_sensor_north_vector_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_north_vector_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -528,38 +483,27 @@ bool extract_mip_sensor_overrange_status_data_from_field(const mip_field_view* f { assert(ptr); mip_sensor_overrange_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_overrange_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_sensor_odometer_data_data(microstrain_serializer* serializer, const mip_sensor_odometer_data_data* self) { microstrain_insert_float(serializer, self->speed); - + microstrain_insert_float(serializer, self->uncertainty); - + microstrain_insert_u16(serializer, self->valid_flags); } void extract_mip_sensor_odometer_data_data(microstrain_serializer* serializer, mip_sensor_odometer_data_data* self) { microstrain_extract_float(serializer, &self->speed); - + microstrain_extract_float(serializer, &self->uncertainty); - + microstrain_extract_u16(serializer, &self->valid_flags); } @@ -567,7 +511,7 @@ bool extract_mip_sensor_odometer_data_data_from_field(const mip_field_view* fiel { assert(ptr); mip_sensor_odometer_data_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_sensor_odometer_data_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); diff --git a/src/c/mip/definitions/data_sensor.h b/src/c/mip/definitions/data_sensor.h index af5afdea8..127524b54 100644 --- a/src/c/mip/definitions/data_sensor.h +++ b/src/c/mip/definitions/data_sensor.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,9 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipData_c MIP Data [C] @@ -81,12 +79,12 @@ enum struct mip_sensor_raw_accel_data { mip_vector3f raw_accel; ///< Native sensor counts - }; typedef struct mip_sensor_raw_accel_data mip_sensor_raw_accel_data; + void insert_mip_sensor_raw_accel_data(microstrain_serializer* serializer, const mip_sensor_raw_accel_data* self); void extract_mip_sensor_raw_accel_data(microstrain_serializer* serializer, mip_sensor_raw_accel_data* self); -bool extract_mip_sensor_raw_accel_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_raw_accel_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -101,12 +99,12 @@ bool extract_mip_sensor_raw_accel_data_from_field(const struct mip_field_view* f struct mip_sensor_raw_gyro_data { mip_vector3f raw_gyro; ///< Native sensor counts - }; typedef struct mip_sensor_raw_gyro_data mip_sensor_raw_gyro_data; + void insert_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, const mip_sensor_raw_gyro_data* self); void extract_mip_sensor_raw_gyro_data(microstrain_serializer* serializer, mip_sensor_raw_gyro_data* self); -bool extract_mip_sensor_raw_gyro_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_raw_gyro_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -121,12 +119,12 @@ bool extract_mip_sensor_raw_gyro_data_from_field(const struct mip_field_view* fi struct mip_sensor_raw_mag_data { mip_vector3f raw_mag; ///< Native sensor counts - }; typedef struct mip_sensor_raw_mag_data mip_sensor_raw_mag_data; + void insert_mip_sensor_raw_mag_data(microstrain_serializer* serializer, const mip_sensor_raw_mag_data* self); void extract_mip_sensor_raw_mag_data(microstrain_serializer* serializer, mip_sensor_raw_mag_data* self); -bool extract_mip_sensor_raw_mag_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_raw_mag_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -141,12 +139,12 @@ bool extract_mip_sensor_raw_mag_data_from_field(const struct mip_field_view* fie struct mip_sensor_raw_pressure_data { float raw_pressure; ///< Native sensor counts - }; typedef struct mip_sensor_raw_pressure_data mip_sensor_raw_pressure_data; + void insert_mip_sensor_raw_pressure_data(microstrain_serializer* serializer, const mip_sensor_raw_pressure_data* self); void extract_mip_sensor_raw_pressure_data(microstrain_serializer* serializer, mip_sensor_raw_pressure_data* self); -bool extract_mip_sensor_raw_pressure_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_raw_pressure_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -161,12 +159,12 @@ bool extract_mip_sensor_raw_pressure_data_from_field(const struct mip_field_view struct mip_sensor_scaled_accel_data { mip_vector3f scaled_accel; ///< (x, y, z)[g] - }; typedef struct mip_sensor_scaled_accel_data mip_sensor_scaled_accel_data; + void insert_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, const mip_sensor_scaled_accel_data* self); void extract_mip_sensor_scaled_accel_data(microstrain_serializer* serializer, mip_sensor_scaled_accel_data* self); -bool extract_mip_sensor_scaled_accel_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_scaled_accel_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -181,12 +179,12 @@ bool extract_mip_sensor_scaled_accel_data_from_field(const struct mip_field_view struct mip_sensor_scaled_gyro_data { mip_vector3f scaled_gyro; ///< (x, y, z) [radians/second] - }; typedef struct mip_sensor_scaled_gyro_data mip_sensor_scaled_gyro_data; + void insert_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, const mip_sensor_scaled_gyro_data* self); void extract_mip_sensor_scaled_gyro_data(microstrain_serializer* serializer, mip_sensor_scaled_gyro_data* self); -bool extract_mip_sensor_scaled_gyro_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_scaled_gyro_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -201,12 +199,12 @@ bool extract_mip_sensor_scaled_gyro_data_from_field(const struct mip_field_view* struct mip_sensor_scaled_mag_data { mip_vector3f scaled_mag; ///< (x, y, z) [Gauss] - }; typedef struct mip_sensor_scaled_mag_data mip_sensor_scaled_mag_data; + void insert_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, const mip_sensor_scaled_mag_data* self); void extract_mip_sensor_scaled_mag_data(microstrain_serializer* serializer, mip_sensor_scaled_mag_data* self); -bool extract_mip_sensor_scaled_mag_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_scaled_mag_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -220,12 +218,12 @@ bool extract_mip_sensor_scaled_mag_data_from_field(const struct mip_field_view* struct mip_sensor_scaled_pressure_data { float scaled_pressure; ///< [mBar] - }; typedef struct mip_sensor_scaled_pressure_data mip_sensor_scaled_pressure_data; + void insert_mip_sensor_scaled_pressure_data(microstrain_serializer* serializer, const mip_sensor_scaled_pressure_data* self); void extract_mip_sensor_scaled_pressure_data(microstrain_serializer* serializer, mip_sensor_scaled_pressure_data* self); -bool extract_mip_sensor_scaled_pressure_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_scaled_pressure_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -240,12 +238,12 @@ bool extract_mip_sensor_scaled_pressure_data_from_field(const struct mip_field_v struct mip_sensor_delta_theta_data { mip_vector3f delta_theta; ///< (x, y, z) [radians] - }; typedef struct mip_sensor_delta_theta_data mip_sensor_delta_theta_data; + void insert_mip_sensor_delta_theta_data(microstrain_serializer* serializer, const mip_sensor_delta_theta_data* self); void extract_mip_sensor_delta_theta_data(microstrain_serializer* serializer, mip_sensor_delta_theta_data* self); -bool extract_mip_sensor_delta_theta_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_delta_theta_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -260,12 +258,12 @@ bool extract_mip_sensor_delta_theta_data_from_field(const struct mip_field_view* struct mip_sensor_delta_velocity_data { mip_vector3f delta_velocity; ///< (x, y, z) [g*sec] - }; typedef struct mip_sensor_delta_velocity_data mip_sensor_delta_velocity_data; + void insert_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, const mip_sensor_delta_velocity_data* self); void extract_mip_sensor_delta_velocity_data(microstrain_serializer* serializer, mip_sensor_delta_velocity_data* self); -bool extract_mip_sensor_delta_velocity_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -289,12 +287,12 @@ bool extract_mip_sensor_delta_velocity_data_from_field(const struct mip_field_vi struct mip_sensor_comp_orientation_matrix_data { mip_matrix3f m; ///< Matrix elements in row-major order. - }; typedef struct mip_sensor_comp_orientation_matrix_data mip_sensor_comp_orientation_matrix_data; + void insert_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_matrix_data* self); void extract_mip_sensor_comp_orientation_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_matrix_data* self); -bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -316,12 +314,12 @@ bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const struct mip struct mip_sensor_comp_quaternion_data { mip_quatf q; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND - }; typedef struct mip_sensor_comp_quaternion_data mip_sensor_comp_quaternion_data; + void insert_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, const mip_sensor_comp_quaternion_data* self); void extract_mip_sensor_comp_quaternion_data(microstrain_serializer* serializer, mip_sensor_comp_quaternion_data* self); -bool extract_mip_sensor_comp_quaternion_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_comp_quaternion_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -338,12 +336,12 @@ struct mip_sensor_comp_euler_angles_data float roll; ///< [radians] float pitch; ///< [radians] float yaw; ///< [radians] - }; typedef struct mip_sensor_comp_euler_angles_data mip_sensor_comp_euler_angles_data; + void insert_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, const mip_sensor_comp_euler_angles_data* self); void extract_mip_sensor_comp_euler_angles_data(microstrain_serializer* serializer, mip_sensor_comp_euler_angles_data* self); -bool extract_mip_sensor_comp_euler_angles_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_comp_euler_angles_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -357,12 +355,12 @@ bool extract_mip_sensor_comp_euler_angles_data_from_field(const struct mip_field struct mip_sensor_comp_orientation_update_matrix_data { mip_matrix3f m; - }; typedef struct mip_sensor_comp_orientation_update_matrix_data mip_sensor_comp_orientation_update_matrix_data; + void insert_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, const mip_sensor_comp_orientation_update_matrix_data* self); void extract_mip_sensor_comp_orientation_update_matrix_data(microstrain_serializer* serializer, mip_sensor_comp_orientation_update_matrix_data* self); -bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -376,12 +374,12 @@ bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const str struct mip_sensor_orientation_raw_temp_data { uint16_t raw_temp[4]; - }; typedef struct mip_sensor_orientation_raw_temp_data mip_sensor_orientation_raw_temp_data; + void insert_mip_sensor_orientation_raw_temp_data(microstrain_serializer* serializer, const mip_sensor_orientation_raw_temp_data* self); void extract_mip_sensor_orientation_raw_temp_data(microstrain_serializer* serializer, mip_sensor_orientation_raw_temp_data* self); -bool extract_mip_sensor_orientation_raw_temp_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_orientation_raw_temp_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -395,12 +393,12 @@ bool extract_mip_sensor_orientation_raw_temp_data_from_field(const struct mip_fi struct mip_sensor_internal_timestamp_data { uint32_t counts; - }; typedef struct mip_sensor_internal_timestamp_data mip_sensor_internal_timestamp_data; + void insert_mip_sensor_internal_timestamp_data(microstrain_serializer* serializer, const mip_sensor_internal_timestamp_data* self); void extract_mip_sensor_internal_timestamp_data(microstrain_serializer* serializer, mip_sensor_internal_timestamp_data* self); -bool extract_mip_sensor_internal_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_internal_timestamp_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -415,12 +413,12 @@ struct mip_sensor_pps_timestamp_data { uint32_t seconds; uint32_t useconds; - }; typedef struct mip_sensor_pps_timestamp_data mip_sensor_pps_timestamp_data; + void insert_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_pps_timestamp_data* self); void extract_mip_sensor_pps_timestamp_data(microstrain_serializer* serializer, mip_sensor_pps_timestamp_data* self); -bool extract_mip_sensor_pps_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_pps_timestamp_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -445,21 +443,29 @@ static const mip_sensor_gps_timestamp_data_valid_flags MIP_SENSOR_GPS_TIMESTAMP_ static const mip_sensor_gps_timestamp_data_valid_flags MIP_SENSOR_GPS_TIMESTAMP_DATA_VALID_FLAGS_TOW_VALID = 0x0008; ///< True if the time of week is valid. static const mip_sensor_gps_timestamp_data_valid_flags MIP_SENSOR_GPS_TIMESTAMP_DATA_VALID_FLAGS_WEEK_NUMBER_VALID = 0x0010; ///< True if the week number is valid. static const mip_sensor_gps_timestamp_data_valid_flags MIP_SENSOR_GPS_TIMESTAMP_DATA_VALID_FLAGS_ALL = 0x001F; +inline void insert_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_sensor_gps_timestamp_data { double tow; ///< GPS Time of Week [seconds] uint16_t week_number; ///< GPS Week Number since 1980 [weeks] mip_sensor_gps_timestamp_data_valid_flags valid_flags; - }; typedef struct mip_sensor_gps_timestamp_data mip_sensor_gps_timestamp_data; + void insert_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data* self); void extract_mip_sensor_gps_timestamp_data(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data* self); -bool extract_mip_sensor_gps_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self); -void extract_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self); +bool extract_mip_sensor_gps_timestamp_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -479,12 +485,12 @@ struct mip_sensor_temperature_abs_data float min_temp; ///< [degC] float max_temp; ///< [degC] float mean_temp; ///< [degC] - }; typedef struct mip_sensor_temperature_abs_data mip_sensor_temperature_abs_data; + void insert_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, const mip_sensor_temperature_abs_data* self); void extract_mip_sensor_temperature_abs_data(microstrain_serializer* serializer, mip_sensor_temperature_abs_data* self); -bool extract_mip_sensor_temperature_abs_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_temperature_abs_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -504,12 +510,12 @@ bool extract_mip_sensor_temperature_abs_data_from_field(const struct mip_field_v struct mip_sensor_up_vector_data { mip_vector3f up; ///< [Gs] - }; typedef struct mip_sensor_up_vector_data mip_sensor_up_vector_data; + void insert_mip_sensor_up_vector_data(microstrain_serializer* serializer, const mip_sensor_up_vector_data* self); void extract_mip_sensor_up_vector_data(microstrain_serializer* serializer, mip_sensor_up_vector_data* self); -bool extract_mip_sensor_up_vector_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_up_vector_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -526,12 +532,12 @@ bool extract_mip_sensor_up_vector_data_from_field(const struct mip_field_view* f struct mip_sensor_north_vector_data { mip_vector3f north; ///< [Gauss] - }; typedef struct mip_sensor_north_vector_data mip_sensor_north_vector_data; + void insert_mip_sensor_north_vector_data(microstrain_serializer* serializer, const mip_sensor_north_vector_data* self); void extract_mip_sensor_north_vector_data(microstrain_serializer* serializer, mip_sensor_north_vector_data* self); -bool extract_mip_sensor_north_vector_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_north_vector_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -554,19 +560,27 @@ static const mip_sensor_overrange_status_data_status MIP_SENSOR_OVERRANGE_STATUS static const mip_sensor_overrange_status_data_status MIP_SENSOR_OVERRANGE_STATUS_DATA_STATUS_MAG_Z = 0x0400; ///< static const mip_sensor_overrange_status_data_status MIP_SENSOR_OVERRANGE_STATUS_DATA_STATUS_PRESS = 0x1000; ///< static const mip_sensor_overrange_status_data_status MIP_SENSOR_OVERRANGE_STATUS_DATA_STATUS_ALL = 0x1777; +inline void insert_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_sensor_overrange_status_data { mip_sensor_overrange_status_data_status status; - }; typedef struct mip_sensor_overrange_status_data mip_sensor_overrange_status_data; + void insert_mip_sensor_overrange_status_data(microstrain_serializer* serializer, const mip_sensor_overrange_status_data* self); void extract_mip_sensor_overrange_status_data(microstrain_serializer* serializer, mip_sensor_overrange_status_data* self); -bool extract_mip_sensor_overrange_status_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self); -void extract_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self); +bool extract_mip_sensor_overrange_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -581,12 +595,12 @@ struct mip_sensor_odometer_data_data float speed; ///< Average speed over the time interval [m/s]. Can be negative for quadrature encoders. float uncertainty; ///< Uncertainty of velocity [m/s]. uint16_t valid_flags; ///< If odometer is configured, bit 0 will be set to 1. - }; typedef struct mip_sensor_odometer_data_data mip_sensor_odometer_data_data; + void insert_mip_sensor_odometer_data_data(microstrain_serializer* serializer, const mip_sensor_odometer_data_data* self); void extract_mip_sensor_odometer_data_data(microstrain_serializer* serializer, mip_sensor_odometer_data_data* self); -bool extract_mip_sensor_odometer_data_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_sensor_odometer_data_data_from_field(const mip_field_view* field, void* ptr); ///@} diff --git a/src/c/mip/definitions/data_shared.c b/src/c/mip/definitions/data_shared.c index ae8e978ed..6cd1a9faa 100644 --- a/src/c/mip/definitions/data_shared.c +++ b/src/c/mip/definitions/data_shared.c @@ -13,14 +13,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; - - -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// @@ -41,7 +33,7 @@ bool extract_mip_shared_event_source_data_from_field(const mip_field_view* field { assert(ptr); mip_shared_event_source_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_event_source_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -61,7 +53,7 @@ bool extract_mip_shared_ticks_data_from_field(const mip_field_view* field, void* { assert(ptr); mip_shared_ticks_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_ticks_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -81,7 +73,7 @@ bool extract_mip_shared_delta_ticks_data_from_field(const mip_field_view* field, { assert(ptr); mip_shared_delta_ticks_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_delta_ticks_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -90,7 +82,7 @@ bool extract_mip_shared_delta_ticks_data_from_field(const mip_field_view* field, void insert_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data* self) { microstrain_insert_double(serializer, self->tow); - + microstrain_insert_u16(serializer, self->week_number); insert_mip_shared_gps_timestamp_data_valid_flags(serializer, self->valid_flags); @@ -99,7 +91,7 @@ void insert_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, co void extract_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, mip_shared_gps_timestamp_data* self) { microstrain_extract_double(serializer, &self->tow); - + microstrain_extract_u16(serializer, &self->week_number); extract_mip_shared_gps_timestamp_data_valid_flags(serializer, &self->valid_flags); @@ -109,23 +101,12 @@ bool extract_mip_shared_gps_timestamp_data_from_field(const mip_field_view* fiel { assert(ptr); mip_shared_gps_timestamp_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_gps_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_shared_delta_time_data(microstrain_serializer* serializer, const mip_shared_delta_time_data* self) { microstrain_insert_double(serializer, self->seconds); @@ -140,7 +121,7 @@ bool extract_mip_shared_delta_time_data_from_field(const mip_field_view* field, { assert(ptr); mip_shared_delta_time_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_delta_time_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -160,7 +141,7 @@ bool extract_mip_shared_reference_timestamp_data_from_field(const mip_field_view { assert(ptr); mip_shared_reference_timestamp_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_reference_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -180,7 +161,7 @@ bool extract_mip_shared_reference_time_delta_data_from_field(const mip_field_vie { assert(ptr); mip_shared_reference_time_delta_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_reference_time_delta_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -204,23 +185,12 @@ bool extract_mip_shared_external_timestamp_data_from_field(const mip_field_view* { assert(ptr); mip_shared_external_timestamp_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_external_timestamp_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - void insert_mip_shared_external_time_delta_data(microstrain_serializer* serializer, const mip_shared_external_time_delta_data* self) { microstrain_insert_u64(serializer, self->dt_nanos); @@ -239,23 +209,12 @@ bool extract_mip_shared_external_time_delta_data_from_field(const mip_field_view { assert(ptr); mip_shared_external_time_delta_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_shared_external_time_delta_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); } -void insert_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self) -{ - microstrain_insert_u16(serializer, (uint16_t) (self)); -} -void extract_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self) -{ - uint16_t tmp = 0; - microstrain_extract_u16(serializer, &tmp); - *self = tmp; -} - #ifdef __cplusplus } // namespace C diff --git a/src/c/mip/definitions/data_shared.h b/src/c/mip/definitions/data_shared.h index 70f6ef6d3..fef1f95b0 100644 --- a/src/c/mip/definitions/data_shared.h +++ b/src/c/mip/definitions/data_shared.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,9 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipData_c MIP Data [C] @@ -68,12 +66,12 @@ enum { MIP_DATA_DESC_SHARED_START = 0xD0 }; struct mip_shared_event_source_data { uint8_t trigger_id; ///< Trigger ID number. If 0, this message was emitted due to being scheduled in the 3DM Message Format Command (0x0C,0x0F). - }; typedef struct mip_shared_event_source_data mip_shared_event_source_data; + void insert_mip_shared_event_source_data(microstrain_serializer* serializer, const mip_shared_event_source_data* self); void extract_mip_shared_event_source_data(microstrain_serializer* serializer, mip_shared_event_source_data* self); -bool extract_mip_shared_event_source_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_shared_event_source_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -90,12 +88,12 @@ bool extract_mip_shared_event_source_data_from_field(const struct mip_field_view struct mip_shared_ticks_data { uint32_t ticks; ///< Ticks since powerup. - }; typedef struct mip_shared_ticks_data mip_shared_ticks_data; + void insert_mip_shared_ticks_data(microstrain_serializer* serializer, const mip_shared_ticks_data* self); void extract_mip_shared_ticks_data(microstrain_serializer* serializer, mip_shared_ticks_data* self); -bool extract_mip_shared_ticks_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_shared_ticks_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -113,12 +111,12 @@ bool extract_mip_shared_ticks_data_from_field(const struct mip_field_view* field struct mip_shared_delta_ticks_data { uint32_t ticks; ///< Ticks since last output. - }; typedef struct mip_shared_delta_ticks_data mip_shared_delta_ticks_data; + void insert_mip_shared_delta_ticks_data(microstrain_serializer* serializer, const mip_shared_delta_ticks_data* self); void extract_mip_shared_delta_ticks_data(microstrain_serializer* serializer, mip_shared_delta_ticks_data* self); -bool extract_mip_shared_delta_ticks_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_shared_delta_ticks_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -138,21 +136,29 @@ static const mip_shared_gps_timestamp_data_valid_flags MIP_SHARED_GPS_TIMESTAMP_ static const mip_shared_gps_timestamp_data_valid_flags MIP_SHARED_GPS_TIMESTAMP_DATA_VALID_FLAGS_WEEK_NUMBER = 0x0002; ///< Week number has been set static const mip_shared_gps_timestamp_data_valid_flags MIP_SHARED_GPS_TIMESTAMP_DATA_VALID_FLAGS_TIME_VALID = 0x0003; ///< Both TOW and Week Number have been set static const mip_shared_gps_timestamp_data_valid_flags MIP_SHARED_GPS_TIMESTAMP_DATA_VALID_FLAGS_ALL = 0x0003; +inline void insert_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_shared_gps_timestamp_data { double tow; ///< GPS Time of Week [seconds] uint16_t week_number; ///< GPS Week Number since 1980 [weeks] mip_shared_gps_timestamp_data_valid_flags valid_flags; - }; typedef struct mip_shared_gps_timestamp_data mip_shared_gps_timestamp_data; + void insert_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data* self); void extract_mip_shared_gps_timestamp_data(microstrain_serializer* serializer, mip_shared_gps_timestamp_data* self); -bool extract_mip_shared_gps_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self); -void extract_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self); +bool extract_mip_shared_gps_timestamp_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -175,12 +181,12 @@ void extract_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* s struct mip_shared_delta_time_data { double seconds; ///< Seconds since last output. - }; typedef struct mip_shared_delta_time_data mip_shared_delta_time_data; + void insert_mip_shared_delta_time_data(microstrain_serializer* serializer, const mip_shared_delta_time_data* self); void extract_mip_shared_delta_time_data(microstrain_serializer* serializer, mip_shared_delta_time_data* self); -bool extract_mip_shared_delta_time_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_shared_delta_time_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -201,12 +207,12 @@ bool extract_mip_shared_delta_time_data_from_field(const struct mip_field_view* struct mip_shared_reference_timestamp_data { uint64_t nanoseconds; ///< Nanoseconds since initialization. - }; typedef struct mip_shared_reference_timestamp_data mip_shared_reference_timestamp_data; + void insert_mip_shared_reference_timestamp_data(microstrain_serializer* serializer, const mip_shared_reference_timestamp_data* self); void extract_mip_shared_reference_timestamp_data(microstrain_serializer* serializer, mip_shared_reference_timestamp_data* self); -bool extract_mip_shared_reference_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_shared_reference_timestamp_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -229,12 +235,12 @@ bool extract_mip_shared_reference_timestamp_data_from_field(const struct mip_fie struct mip_shared_reference_time_delta_data { uint64_t dt_nanos; ///< Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source. - }; typedef struct mip_shared_reference_time_delta_data mip_shared_reference_time_delta_data; + void insert_mip_shared_reference_time_delta_data(microstrain_serializer* serializer, const mip_shared_reference_time_delta_data* self); void extract_mip_shared_reference_time_delta_data(microstrain_serializer* serializer, mip_shared_reference_time_delta_data* self); -bool extract_mip_shared_reference_time_delta_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_shared_reference_time_delta_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -257,20 +263,28 @@ typedef uint16_t mip_shared_external_timestamp_data_valid_flags; static const mip_shared_external_timestamp_data_valid_flags MIP_SHARED_EXTERNAL_TIMESTAMP_DATA_VALID_FLAGS_NONE = 0x0000; static const mip_shared_external_timestamp_data_valid_flags MIP_SHARED_EXTERNAL_TIMESTAMP_DATA_VALID_FLAGS_NANOSECONDS = 0x0001; ///< static const mip_shared_external_timestamp_data_valid_flags MIP_SHARED_EXTERNAL_TIMESTAMP_DATA_VALID_FLAGS_ALL = 0x0001; +inline void insert_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_shared_external_timestamp_data { uint64_t nanoseconds; mip_shared_external_timestamp_data_valid_flags valid_flags; - }; typedef struct mip_shared_external_timestamp_data mip_shared_external_timestamp_data; + void insert_mip_shared_external_timestamp_data(microstrain_serializer* serializer, const mip_shared_external_timestamp_data* self); void extract_mip_shared_external_timestamp_data(microstrain_serializer* serializer, mip_shared_external_timestamp_data* self); -bool extract_mip_shared_external_timestamp_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self); -void extract_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self); +bool extract_mip_shared_external_timestamp_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -297,20 +311,28 @@ typedef uint16_t mip_shared_external_time_delta_data_valid_flags; static const mip_shared_external_time_delta_data_valid_flags MIP_SHARED_EXTERNAL_TIME_DELTA_DATA_VALID_FLAGS_NONE = 0x0000; static const mip_shared_external_time_delta_data_valid_flags MIP_SHARED_EXTERNAL_TIME_DELTA_DATA_VALID_FLAGS_DT_NANOS = 0x0001; ///< static const mip_shared_external_time_delta_data_valid_flags MIP_SHARED_EXTERNAL_TIME_DELTA_DATA_VALID_FLAGS_ALL = 0x0001; +inline void insert_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self) +{ + microstrain_insert_u16(serializer, (uint16_t)(self)); +} +inline void extract_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self) +{ + uint16_t tmp = 0; + microstrain_extract_u16(serializer, &tmp); + *self = tmp; +} + struct mip_shared_external_time_delta_data { uint64_t dt_nanos; ///< Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source. mip_shared_external_time_delta_data_valid_flags valid_flags; - }; typedef struct mip_shared_external_time_delta_data mip_shared_external_time_delta_data; + void insert_mip_shared_external_time_delta_data(microstrain_serializer* serializer, const mip_shared_external_time_delta_data* self); void extract_mip_shared_external_time_delta_data(microstrain_serializer* serializer, mip_shared_external_time_delta_data* self); -bool extract_mip_shared_external_time_delta_data_from_field(const struct mip_field_view* field, void* ptr); - -void insert_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self); -void extract_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self); +bool extract_mip_shared_external_time_delta_data_from_field(const mip_field_view* field, void* ptr); ///@} diff --git a/src/c/mip/definitions/data_system.c b/src/c/mip/definitions/data_system.c index 7f1ee5cc0..8099d63ce 100644 --- a/src/c/mip/definitions/data_system.c +++ b/src/c/mip/definitions/data_system.c @@ -13,14 +13,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; - - -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// @@ -43,7 +35,7 @@ bool extract_mip_system_built_in_test_data_from_field(const mip_field_view* fiel { assert(ptr); mip_system_built_in_test_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_system_built_in_test_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -52,14 +44,14 @@ bool extract_mip_system_built_in_test_data_from_field(const mip_field_view* fiel void insert_mip_system_time_sync_status_data(microstrain_serializer* serializer, const mip_system_time_sync_status_data* self) { microstrain_insert_bool(serializer, self->time_sync); - + microstrain_insert_u8(serializer, self->last_pps_rcvd); } void extract_mip_system_time_sync_status_data(microstrain_serializer* serializer, mip_system_time_sync_status_data* self) { microstrain_extract_bool(serializer, &self->time_sync); - + microstrain_extract_u8(serializer, &self->last_pps_rcvd); } @@ -67,7 +59,7 @@ bool extract_mip_system_time_sync_status_data_from_field(const mip_field_view* f { assert(ptr); mip_system_time_sync_status_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_system_time_sync_status_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -87,7 +79,7 @@ bool extract_mip_system_gpio_state_data_from_field(const mip_field_view* field, { assert(ptr); mip_system_gpio_state_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_system_gpio_state_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); @@ -96,14 +88,14 @@ bool extract_mip_system_gpio_state_data_from_field(const mip_field_view* field, void insert_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, const mip_system_gpio_analog_value_data* self) { microstrain_insert_u8(serializer, self->gpio_id); - + microstrain_insert_float(serializer, self->value); } void extract_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, mip_system_gpio_analog_value_data* self) { microstrain_extract_u8(serializer, &self->gpio_id); - + microstrain_extract_float(serializer, &self->value); } @@ -111,7 +103,7 @@ bool extract_mip_system_gpio_analog_value_data_from_field(const mip_field_view* { assert(ptr); mip_system_gpio_analog_value_data* self = ptr; - struct microstrain_serializer serializer; + microstrain_serializer serializer; microstrain_serializer_init_from_field(&serializer, field); extract_mip_system_gpio_analog_value_data(&serializer, self); return microstrain_serializer_is_complete(&serializer); diff --git a/src/c/mip/definitions/data_system.h b/src/c/mip/definitions/data_system.h index 2edc33f8e..54b4905f5 100644 --- a/src/c/mip/definitions/data_system.h +++ b/src/c/mip/definitions/data_system.h @@ -1,8 +1,9 @@ #pragma once #include "common.h" -#include "mip/mip_descriptors.h" -#include "../mip_result.h" +#include +#include +#include #include #include @@ -14,9 +15,6 @@ namespace C { extern "C" { #endif // __cplusplus -struct mip_interface; -struct microstrain_serializer; -struct mip_field; //////////////////////////////////////////////////////////////////////////////// ///@addtogroup MipData_c MIP Data [C] @@ -76,12 +74,12 @@ enum struct mip_system_built_in_test_data { uint8_t result[16]; ///< Device-specific bitfield (128 bits). See device user manual. Bits are least-significant-byte first. For example, bit 0 is located at bit 0 of result[0], bit 1 is located at bit 1 of result[0], bit 8 is located at bit 0 of result[1], and bit 127 is located at bit 7 of result[15]. - }; typedef struct mip_system_built_in_test_data mip_system_built_in_test_data; + void insert_mip_system_built_in_test_data(microstrain_serializer* serializer, const mip_system_built_in_test_data* self); void extract_mip_system_built_in_test_data(microstrain_serializer* serializer, mip_system_built_in_test_data* self); -bool extract_mip_system_built_in_test_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_system_built_in_test_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -96,12 +94,12 @@ struct mip_system_time_sync_status_data { bool time_sync; ///< True if sync with the PPS signal is currently valid. False if PPS feature is disabled or a PPS signal is not detected. uint8_t last_pps_rcvd; ///< Elapsed time in seconds since last PPS was received, with a maximum value of 255. - }; typedef struct mip_system_time_sync_status_data mip_system_time_sync_status_data; + void insert_mip_system_time_sync_status_data(microstrain_serializer* serializer, const mip_system_time_sync_status_data* self); void extract_mip_system_time_sync_status_data(microstrain_serializer* serializer, mip_system_time_sync_status_data* self); -bool extract_mip_system_time_sync_status_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_system_time_sync_status_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -133,12 +131,12 @@ bool extract_mip_system_time_sync_status_data_from_field(const struct mip_field_ struct mip_system_gpio_state_data { uint8_t states; ///< Bitfield containing the states for each GPIO pin.
Bit 0 (0x01): pin 1
Bit 1 (0x02): pin 2
Bit 2 (0x04): pin 3
Bit 3 (0x08): pin 4
Bits for pins that don't exist will read as 0. - }; typedef struct mip_system_gpio_state_data mip_system_gpio_state_data; + void insert_mip_system_gpio_state_data(microstrain_serializer* serializer, const mip_system_gpio_state_data* self); void extract_mip_system_gpio_state_data(microstrain_serializer* serializer, mip_system_gpio_state_data* self); -bool extract_mip_system_gpio_state_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_system_gpio_state_data_from_field(const mip_field_view* field, void* ptr); ///@} @@ -154,12 +152,12 @@ struct mip_system_gpio_analog_value_data { uint8_t gpio_id; ///< GPIO pin number starting with 1. float value; ///< Value of the GPIO line in scaled volts. - }; typedef struct mip_system_gpio_analog_value_data mip_system_gpio_analog_value_data; + void insert_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, const mip_system_gpio_analog_value_data* self); void extract_mip_system_gpio_analog_value_data(microstrain_serializer* serializer, mip_system_gpio_analog_value_data* self); -bool extract_mip_system_gpio_analog_value_data_from_field(const struct mip_field_view* field, void* ptr); +bool extract_mip_system_gpio_analog_value_data_from_field(const mip_field_view* field, void* ptr); ///@} diff --git a/src/c/mip/mip_interface.h b/src/c/mip/mip_interface.h index 2a2eec7fb..5f469af19 100644 --- a/src/c/mip/mip_interface.h +++ b/src/c/mip/mip_interface.h @@ -1,12 +1,12 @@ #pragma once -#include -#include - #include "mip_parser.h" #include "mip_cmdqueue.h" #include "mip_dispatch.h" +#include +#include + #ifdef __cplusplus namespace mip{ namespace C { diff --git a/src/cpp/microstrain/common/platform.hpp b/src/cpp/microstrain/common/platform.hpp index 7afede680..9b3ddd85e 100644 --- a/src/cpp/microstrain/common/platform.hpp +++ b/src/cpp/microstrain/common/platform.hpp @@ -2,6 +2,12 @@ #include +#ifdef __has_include +# if __has_include() +# include +# endif +#endif + #if __cpp_inline_variables >= 201606L #define INLINE_VAR inline #else diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index b12f57e97..0c3a900ae 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -1,388 +1,15 @@ #pragma once +#include "serialization/serializer.hpp" + #include #include -#include - +#include #include #include -#ifdef HAS_OPTIONAL -#include -#endif -#ifdef HAS_SPAN -#include -#endif - namespace microstrain { - -// -// Basic Insertion -// - -template -typename std::enable_if::value && sizeof(T)==1, size_t>::type -/*size_t*/ write(uint8_t* buffer, T value) -{ - buffer[0] = reinterpret_cast(&value)[0]; - return sizeof(T); -} - -template -typename std::enable_if::value && sizeof(T)==2, size_t>::type -/*size_t*/ write(uint8_t* buffer, T value) -{ - buffer[0] = reinterpret_cast(&value)[1]; - buffer[1] = reinterpret_cast(&value)[0]; - return sizeof(T); -} - -template -typename std::enable_if::value && sizeof(T)==4, size_t>::type -/*size_t*/ write(uint8_t* buffer, T value) -{ - buffer[0] = reinterpret_cast(&value)[3]; - buffer[1] = reinterpret_cast(&value)[2]; - buffer[2] = reinterpret_cast(&value)[1]; - buffer[3] = reinterpret_cast(&value)[0]; - return sizeof(T); -} - -template -typename std::enable_if::value && sizeof(T)==8, size_t>::type -/*size_t*/ write(uint8_t* buffer, T value) -{ - buffer[0] = reinterpret_cast(&value)[7]; - buffer[1] = reinterpret_cast(&value)[6]; - buffer[2] = reinterpret_cast(&value)[5]; - buffer[3] = reinterpret_cast(&value)[4]; - buffer[4] = reinterpret_cast(&value)[3]; - buffer[5] = reinterpret_cast(&value)[2]; - buffer[6] = reinterpret_cast(&value)[1]; - buffer[7] = reinterpret_cast(&value)[0]; - return sizeof(T); -} - -// -// Basic Extraction -// - -template -typename std::enable_if::value && sizeof(T)==1, size_t>::type -/*size_t*/ read(const uint8_t* buffer, T& value) -{ - reinterpret_cast(&value)[0] = buffer[0]; - return sizeof(T); -} - -template -typename std::enable_if::value && sizeof(T)==2, size_t>::type -/*size_t*/ read(const uint8_t* buffer, T& value) -{ - reinterpret_cast(&value)[0] = buffer[1]; - reinterpret_cast(&value)[1] = buffer[0]; - return sizeof(T); -} - -template -typename std::enable_if::value && sizeof(T)==4, size_t>::type -/*size_t*/ read(const uint8_t* buffer, T& value) -{ - reinterpret_cast(&value)[0] = buffer[3]; - reinterpret_cast(&value)[1] = buffer[2]; - reinterpret_cast(&value)[2] = buffer[1]; - reinterpret_cast(&value)[3] = buffer[0]; - return sizeof(T); -} - -template -typename std::enable_if::value && sizeof(T)==8, size_t>::type -/*size_t*/ read(const uint8_t* buffer, T& value) -{ - reinterpret_cast(&value)[0] = buffer[7]; - reinterpret_cast(&value)[1] = buffer[6]; - reinterpret_cast(&value)[2] = buffer[5]; - reinterpret_cast(&value)[3] = buffer[4]; - reinterpret_cast(&value)[4] = buffer[3]; - reinterpret_cast(&value)[5] = buffer[2]; - reinterpret_cast(&value)[6] = buffer[1]; - reinterpret_cast(&value)[7] = buffer[0]; - return sizeof(T); -} - -template -T read(const uint8_t* buffer) -{ - T value; - read(buffer, value); - return value; -} - - -class Serializer -{ -public: - Serializer() = default; - Serializer(uint8_t* ptr, size_t capacity, size_t offset=0) : m_ptr(ptr), m_size(capacity), m_offset(offset) {} - Serializer(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} -#ifdef HAS_SPAN - Serializer(std::span buffer, size_t offset=0) : m_ptr(const_cast(buffer.data())), m_size(buffer.size()), m_offset(offset) {} -#endif - - size_t capacity() const { return m_size; } - size_t length() const { return m_size; } - size_t offset() const { return m_offset; } - int remaining() const { return int(m_size - m_offset); } - - bool noRemaining() const { return m_offset == m_size; } - bool isOverrun() const { return m_offset > m_size; } - bool isOk() const { return !isOverrun(); } - bool hasRemaining(size_t count) const { return m_offset+count <= m_size; } - - const uint8_t* basePointer() const { return m_ptr; } - uint8_t* basePointer() { return m_ptr; } - - const uint8_t* pointer(size_t required_size) const { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } - uint8_t* pointer(size_t required_size) { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } - - uint8_t* getPtrAndAdvance(size_t size) { uint8_t* ptr = hasRemaining(size) ? (m_ptr+m_offset) : nullptr; m_offset += size; return ptr; } - - void invalidate() { m_offset = size_t(-1); } - - template - bool insert(const Ts&... values); - - template - bool extract(Ts&... values); - - // Sets a new offset and returns the old value. - size_t setOffset(size_t offset) { std::swap(m_offset, offset); return offset; } - - //template - //struct Counter - //{ - // T& count; - // size_t max_count = 0; - //}; - -private: - uint8_t* m_ptr = nullptr; - size_t m_size = 0; - size_t m_offset = 0; -}; - - -// -// General Insertion -// - -// Built-in types (bool, int, float, ...) -template -typename std::enable_if::value, size_t>::type -/*size_t*/ insert(Serializer& buffer, T value) -{ - if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) - write(ptr, value); - - return sizeof(T); -} - -// Enums -template -typename std::enable_if::value, size_t>::type -/*size_t*/ insert(Serializer& buffer, T value) -{ - using BaseType = typename std::underlying_type::type; - - if(auto ptr = buffer.getPtrAndAdvance(sizeof(BaseType))) - write(ptr, static_cast(value)); - - return sizeof(BaseType); -} - -// std::tuple -template -size_t insert(Serializer& serializer, const std::tuple& values) -{ - auto lambda = [&serializer](const Ts&... args) { - return insert(serializer, args...); - }; - - return std::apply(lambda, values); -} - -// Raw buffer -template -bool insert(const T& value, uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=true) -{ - Serializer serializer(buffer, buffer_length, offset); - serializer.insert(value); - return exact_size ? serializer.noRemaining() : serializer.isOk(); -} - -// Multiple values at once -#if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L -template -typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type -/*size_t*/ insert(Serializer& buffer, Ts... values) -{ - if constexpr( (std::is_arithmetic::value && ...) ) - { - const size_t size = ( ... + sizeof(Ts) ); - - if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) - { - size_t offset = 0; - ( ..., (offset += write(ptr+offset, values)) ); - return offset; - } - - return size; - } - else - return ( ... + insert(buffer, values) ); -} -#else -template -size_t insert(Serializer& serializer, T0 value0, Ts... values) -{ - return insert(serializer, value0) + insert(serializer, values...); -} -#endif - - - -// -// General Extraction -// - -// Built-in types (bool, int, float, ...) -template -typename std::enable_if::value, size_t>::type -/*size_t*/ extract(Serializer& buffer, T& value) -{ - if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) - read(ptr, value); - - return sizeof(T); -} - -// Enums -template -typename std::enable_if::value, size_t>::type -/*size_t*/ extract(Serializer& buffer, T& value) -{ - using BaseType = typename std::underlying_type::type; - - if(auto ptr = buffer.getPtrAndAdvance(sizeof(BaseType))) - { - BaseType base; - read(ptr, base); - value = static_cast(base); - } - - return sizeof(BaseType); -} - -// std::tuple of references -template -size_t extract(Serializer& serializer, const std::tuple...>& values) -{ - auto lambda = [&serializer](auto&... args) { - return extract(serializer, args...); - }; - - return std::apply(lambda, values); -} - -// Raw buffer -template -bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=false) -{ - Serializer serializer(buffer, buffer_length, offset); - extract(serializer, value); - return exact_size ? serializer.noRemaining() : serializer.isOk(); -} - -// Returning by value (use read instead if length is guaranteed to be in range) -#ifdef HAS_OPTIONAL -template -std::optional extract(Serializer& serializer) -{ - T value; - if(extract(serializer, value)) - return value; - else - return std::nullopt; -} - -template -std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bool exact_size=false) -{ - T value; - if(extract(value, buffer, length, offset, exact_size)) - return value; - else - return std::nullopt; -} -#endif - -#if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L -template -typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type -/*size_t*/ extract(Serializer& buffer, Ts&... values) -{ - if constexpr( (std::is_arithmetic::value && ...) ) - { - const size_t size = ( ... + sizeof(Ts) ); - - if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) - { - size_t offset = 0; - ( ..., (offset += read(ptr+offset, values)) ); - return offset; - } - - return size; - } - else - return ( ... + extract(buffer, values) ); -} -#else -template -size_t extract(Serializer& serializer, T0 value0, Ts... values) -{ - return extract(serializer, value0) + extract(serializer, values...); -} -#endif - - -template -size_t extract_count(Serializer& buffer, T& count, size_t max_count) -{ - T tmp; - size_t size = extract(buffer, tmp); - - if(tmp <= max_count) - count = tmp; - else - buffer.invalidate(); - - return size; -} -template -size_t extract_count(Serializer& buffer, T* count, size_t max_count) { return extract_count(buffer, *count, max_count); } - - - -template -bool Serializer::insert(const Ts&... values) { microstrain::insert(*this, values...); return isOk(); } - -template -bool Serializer::extract(Ts&... values) { microstrain::extract(*this, values...); return isOk(); } - - } // namespace microstrain diff --git a/src/cpp/microstrain/common/serialization/readwrite.hpp b/src/cpp/microstrain/common/serialization/readwrite.hpp new file mode 100644 index 000000000..ceee74b4d --- /dev/null +++ b/src/cpp/microstrain/common/serialization/readwrite.hpp @@ -0,0 +1,181 @@ +#pragma once + +#include "../platform.hpp" + +#include +#include +#include +#include + +#if __cpp_lib_endian >= 201907L +#include +#endif + +namespace microstrain +{ +namespace serialization +{ + +#if __cpp_lib_endian >= 201907L +using Endian = std::endian; +#else +enum class Endian +{ + little, + big, + //native = little, // Todo +}; +#endif + +// +// Write to buffer +// + +namespace big_endian +{ + +template +typename std::enable_if::value && sizeof(T) == 1, size_t>::type +/*size_t*/ write(uint8_t *buffer, T value) +{ + buffer[0] = reinterpret_cast(&value)[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T) == 2, size_t>::type +/*size_t*/ write(uint8_t *buffer, T value) +{ + buffer[0] = reinterpret_cast(&value)[1]; + buffer[1] = reinterpret_cast(&value)[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T) == 4, size_t>::type +/*size_t*/ write(uint8_t *buffer, T value) +{ + buffer[0] = reinterpret_cast(&value)[3]; + buffer[1] = reinterpret_cast(&value)[2]; + buffer[2] = reinterpret_cast(&value)[1]; + buffer[3] = reinterpret_cast(&value)[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T) == 8, size_t>::type +/*size_t*/ write(uint8_t *buffer, T value) +{ + buffer[0] = reinterpret_cast(&value)[7]; + buffer[1] = reinterpret_cast(&value)[6]; + buffer[2] = reinterpret_cast(&value)[5]; + buffer[3] = reinterpret_cast(&value)[4]; + buffer[4] = reinterpret_cast(&value)[3]; + buffer[5] = reinterpret_cast(&value)[2]; + buffer[6] = reinterpret_cast(&value)[1]; + buffer[7] = reinterpret_cast(&value)[0]; + return sizeof(T); +} + +} // namespace big_endian +namespace little_endian +{ + +template +typename std::enable_if::value, size_t>::type +/*size_t*/ write(uint8_t *buffer, T value) +{ + std::memcpy(buffer, &value, sizeof(value)); + return sizeof(value); +} + +} // namespace little_endian + + +template +typename std::enable_if::value, size_t>::type +/*size_t*/ write(uint8_t* buffer, T value) { return E==Endian::little ? little_endian::write(buffer,value) : big_endian::write(buffer,value); } + + +// +// Read from buffer +// + +namespace big_endian +{ + +template +typename std::enable_if::value && sizeof(T)==1, size_t>::type +/*size_t*/ read(const uint8_t* buffer, T& value) +{ + reinterpret_cast(&value)[0] = buffer[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T)==2, size_t>::type +/*size_t*/ read(const uint8_t* buffer, T& value) +{ + reinterpret_cast(&value)[0] = buffer[1]; + reinterpret_cast(&value)[1] = buffer[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T)==4, size_t>::type +/*size_t*/ read(const uint8_t* buffer, T& value) +{ + reinterpret_cast(&value)[0] = buffer[3]; + reinterpret_cast(&value)[1] = buffer[2]; + reinterpret_cast(&value)[2] = buffer[1]; + reinterpret_cast(&value)[3] = buffer[0]; + return sizeof(T); +} + +template +typename std::enable_if::value && sizeof(T)==8, size_t>::type +/*size_t*/ read(const uint8_t* buffer, T& value) +{ + reinterpret_cast(&value)[0] = buffer[7]; + reinterpret_cast(&value)[1] = buffer[6]; + reinterpret_cast(&value)[2] = buffer[5]; + reinterpret_cast(&value)[3] = buffer[4]; + reinterpret_cast(&value)[4] = buffer[3]; + reinterpret_cast(&value)[5] = buffer[2]; + reinterpret_cast(&value)[6] = buffer[1]; + reinterpret_cast(&value)[7] = buffer[0]; + return sizeof(T); +} + +} // namespace big_endian +namespace little_endian +{ + +template +typename std::enable_if::value, size_t>::type +/*size_t*/ read(const uint8_t* buffer, T& value) +{ + std::memcpy(&value, buffer, sizeof(T)); + return sizeof(T); +} + +} // namespace little_endian + + +template +size_t read(const uint8_t* buffer, T& value) +{ + return (E==Endian::little) ? little_endian::read(buffer, value) : big_endian::read(buffer, value); +} + +// Read T and return by value +template +T read(const uint8_t* buffer) +{ + T value; + read(buffer, value); + return value; +} + +} // namespace serialization +} // namespace microstrain diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp new file mode 100644 index 000000000..21b349bbd --- /dev/null +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -0,0 +1,462 @@ +#pragma once + +#include "readwrite.hpp" + +#include +#include + +#ifdef HAS_OPTIONAL +#include +#endif +#ifdef HAS_SPAN +#include +#endif + +#if __cpp_lib_apply >= 201603L +#include +#endif + + + +namespace microstrain +{ + + +class BaseSerializer +{ +public: + BaseSerializer() = default; + BaseSerializer(uint8_t* ptr, size_t capacity, size_t offset=0) : m_ptr(ptr), m_size(capacity), m_offset(offset) {} + BaseSerializer(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} +#ifdef HAS_SPAN + BaseSerializer(std::span buffer, size_t offset=0) : m_ptr(const_cast(buffer.data())), m_size(buffer.size()), m_offset(offset) {} +#endif + + size_t capacity() const { return m_size; } + size_t length() const { return m_size; } + size_t offset() const { return m_offset; } + int remaining() const { return int(m_size - m_offset); } + + bool noRemaining() const { return m_offset == m_size; } + bool isOverrun() const { return m_offset > m_size; } + bool isOk() const { return !isOverrun(); } + bool hasRemaining(size_t count) const { return m_offset+count <= m_size; } + + const uint8_t* basePointer() const { return m_ptr; } + uint8_t* basePointer() { return m_ptr; } + + const uint8_t* pointer(size_t required_size) const { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } + uint8_t* pointer(size_t required_size) { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } + + uint8_t* getPtrAndAdvance(size_t size) { uint8_t* ptr = hasRemaining(size) ? (m_ptr+m_offset) : nullptr; m_offset += size; return ptr; } + + void invalidate() { m_offset = size_t(-1); } + + template + bool insert(const Ts&... values); + + template + bool extract(Ts&... values); + + template + size_t extract_count(T& count, S max_count); + + template + size_t extract_count(T* count, S max_count) { return extract_count(*count, max_count); } + + // Sets a new offset and returns the old value. + size_t setOffset(size_t offset) { std::swap(m_offset, offset); return offset; } + +private: + uint8_t* m_ptr = nullptr; + size_t m_size = 0; + size_t m_offset = 0; +}; + + +// Serializer that has the endianness built-in +template +class Serializer : public BaseSerializer +{ +public: + using BaseSerializer::BaseSerializer; + + template bool insert (const Ts&... values) { return BaseSerializer::insert(values...); } + template bool extract(Ts&... values) { return BaseSerializer::extract(values...); } + + template bool extract_count(T& value, S max_value) { return BaseSerializer::extract_count(value, max_value); } + template bool extract_count(T* value, S max_value) { return BaseSerializer::extract_count(value, max_value); } +}; + +using BigEndianSerializer = Serializer; +using LittleEndianSerializer = Serializer; + + +//template +//size_t insert(BaseSerializer&, Ts...); +//template +//size_t extract(BaseSerializer&, Ts...); + + +// +// +// Non-member functions which the user may overload +// +// + +// +// Built-in types (bool, int, float, ...) +// + +template +typename std::enable_if::value, size_t>::type +/*size_t*/ insert(Serializer& buffer, T value) +{ + if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) + serialization::write(ptr, value); + + return sizeof(T); +} + +template +typename std::enable_if::value, size_t>::type +/*size_t*/ extract(Serializer& buffer, T& value) +{ + if(auto ptr = buffer.getPtrAndAdvance(sizeof(T))) + serialization::read(ptr, value); + + return sizeof(T); +} + + +// +// Enums +// + +template +typename std::enable_if::value, size_t>::type +/*size_t*/ insert(Serializer& buffer, T value) +{ + using BaseType = typename std::underlying_type::type; + + if(auto ptr = buffer.getPtrAndAdvance(sizeof(BaseType))) + serialization::write(ptr, static_cast(value)); + + return sizeof(BaseType); +} + +template +typename std::enable_if::value, size_t>::type +/*size_t*/ extract(Serializer& buffer, T& value) +{ + using BaseType = typename std::underlying_type::type; + + if(auto ptr = buffer.getPtrAndAdvance(sizeof(BaseType))) + { + BaseType base; + serialization::read(ptr, base); + value = static_cast(base); + } + + return sizeof(BaseType); +} + + +// +// std::tuple - only supported if std::apply can be used +// +#if __cpp_lib_apply >= 201603L + +template +size_t insert(Serializer& serializer, const std::tuple& values) +{ + auto lambda = [&serializer](const Ts&... args) { + return insert(serializer, args...); + }; + + return std::apply(lambda, values); +} + +// std::tuple of references +template +size_t extract(Serializer& serializer, const std::tuple...>& values) +{ + auto lambda = [&serializer](auto&... args) { + return extract(serializer, args...); + }; + + return std::apply(lambda, values); +} + +#endif + + +// +// Classes - if they have member functions "serialize" and "deserialize" +// + +// Generic classes which have an "serialize" method. +template +typename std::enable_if::value , size_t>::type +/*size_t*/ insert(microstrain::Serializer& serializer, const T& object) +{ + size_t offset = serializer.offset(); + object.serialize(serializer); + return serializer.offset() - offset; +} + +// Generic classes which have an "deserialize" method. +template +typename std::enable_if::value , size_t>::type +/*size_t*/ extract(microstrain::Serializer& serializer, T& object) +{ + size_t offset = serializer.offset(); + object.deserialize(serializer); + return serializer.offset() - offset; +} + +// +// Arrays +// + +template +size_t insert(Serializer& serializer, const T* values, size_t count) +{ + // For arithmetic types the size is fixed so it can be optimized. + IF_CONSTEXPR(std::is_arithmetic::value) + { + const size_t size = sizeof(T)*count; + if(auto ptr = serializer.getPtrAndAdvance(size)) + { + for(size_t i=0; i(ptr+i*sizeof(T), values[i]); + } + } + else // Unknown size, have to check length every time. + { + size_t offset = serializer.offset(); + for(size_t i=0; i +size_t extract(Serializer& serializer, T* values, size_t count) +{ + // For arithmetic types the size is fixed so it can be optimized. + IF_CONSTEXPR(std::is_arithmetic::value) + { + const size_t size = sizeof(T)*count; + if(auto ptr = serializer.getPtrAndAdvance(size)) + { + for(size_t i=0; i(ptr+i*sizeof(T), values[i]); + } + } + else // Unknown size, have to check length every time. + { + size_t offset = serializer.offset(); + for(size_t i=0; i +size_t insert(Serializer& serializer, std::span values) +{ + return insert(serializer, values.data(), values.size()); +} +template +size_t extract(Serializer& serializer, std::span values) +{ + return extract(serializer, values.data(), values.size()); +} +#endif + +// +// Arrays of fixed size +// + +template +size_t insert(Serializer& serializer, const T(&values)[N]) +{ + return insert(serializer, values, N); +} +template +size_t extract(Serializer& serializer, T(&values)[N]) +{ + return extract(serializer, values, N); +} + +template +size_t insert(Serializer& serializer, const std::array& values) +{ + return insert(serializer, values.data(), values.size()); +} +template +size_t extract(Serializer& serializer, const std::array& values) +{ + return extract(serializer, values.data(), values.size()); +} + +// +// Multiple values at once - more efficient since it avoids multiple size checks +// + +#if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L +template +typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type +/*size_t*/ insert(Serializer& buffer, Ts... values) +{ + if constexpr( (std::is_arithmetic::value && ...) ) + { + const size_t size = ( ... + sizeof(Ts) ); + + if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) + { + size_t offset = 0; + ( ..., (offset += write(ptr+offset, values)) ); + return offset; + } + + return size; + } + else // Class types may not have fixed sizes, can't optimize them + return ( ... + insert(buffer, values) ); +} +#else +template +size_t insert(Serializer& serializer, T0 value0, Ts... values) +{ + return insert(serializer, value0) + insert(serializer, values...); +} +#endif + + +#if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L +template +typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type +/*size_t*/ extract(Serializer& buffer, Ts&... values) +{ + if constexpr( (std::is_arithmetic::value && ...) ) + { + const size_t size = ( ... + sizeof(Ts) ); + + if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) + { + size_t offset = 0; + ( ..., (offset += read(ptr+offset, values)) ); + return offset; + } + + return size; + } + else // Class types may not have fixed sizes, can't optimize them + return ( ... + extract(buffer, values) ); +} +#else +template +size_t extract(Serializer& serializer, T0 value0, Ts... values) +{ + return extract(serializer, value0) + extract(serializer, values...); +} +#endif + + +// +// Raw buffer - avoids the need to create a serializer yourself. +// + +template +bool insert(const T& value, uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=true) +{ + Serializer serializer(buffer, buffer_length, offset); + serializer.insert(value); + return exact_size ? serializer.noRemaining() : serializer.isOk(); +} + +template +bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=false) +{ + Serializer serializer(buffer, buffer_length, offset); + extract(serializer, value); + return exact_size ? serializer.noRemaining() : serializer.isOk(); +} + + + + + + + +// +// Special Deserialization +// + + +// Deserialize and return by value + +#ifdef HAS_OPTIONAL +template +std::optional extract(Serializer& serializer) +{ + T value; + if(extract(serializer, value)) + return value; + else + return std::nullopt; +} + +template +std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bool exact_size=false) +{ + T value; + if(extract(value, buffer, length, offset, exact_size)) + return value; + else + return std::nullopt; +} +#endif + + +// +// +// Serializer member functions which depend on the above overloads. +// +// + +template +bool BaseSerializer::insert(const Ts&... values) +{ + microstrain::insert(*this, values...); + return isOk(); +} + +template +bool BaseSerializer::extract(Ts&... values) +{ + microstrain::extract(*this, values...); + return isOk(); +} + +// Extract a counter with maximum value. +template +size_t BaseSerializer::extract_count(T& count, S max_count) +{ + size_t size = extract(count); + + if(count > max_count) + { + count = 0; + invalidate(); + } + + return size; +} + + + +} // namespace microstrain diff --git a/src/cpp/mip/definitions/commands_3dm.cpp b/src/cpp/mip/definitions/commands_3dm.cpp index 3a5e883d6..ff42001e5 100644 --- a/src/cpp/mip/definitions/commands_3dm.cpp +++ b/src/cpp/mip/definitions/commands_3dm.cpp @@ -1,8 +1,8 @@ #include "commands_3dm.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include @@ -14,205 +14,183 @@ struct mip_interface; namespace commands_3dm { -using ::microstrain::insert; -using ::microstrain::extract; +using namespace ::mip::C; //////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions +// Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const NmeaMessage& self) +void NmeaMessage::insert(Serializer& serializer) const { - insert(serializer, self.message_id); + serializer.insert(message_id); - insert(serializer, self.talker_id); + serializer.insert(talker_id); - insert(serializer, self.source_desc_set); + serializer.insert(source_desc_set); - insert(serializer, self.decimation); + serializer.insert(decimation); } -void extract(::microstrain::Serializer& serializer, NmeaMessage& self) +void NmeaMessage::extract(Serializer& serializer) { - extract(serializer, self.message_id); + serializer.extract(message_id); - extract(serializer, self.talker_id); + serializer.extract(talker_id); - extract(serializer, self.source_desc_set); + serializer.extract(source_desc_set); - extract(serializer, self.decimation); + serializer.extract(decimation); } - -//////////////////////////////////////////////////////////////////////////////// -// Mip Fields -//////////////////////////////////////////////////////////////////////////////// - -void insert(::microstrain::Serializer& serializer, const PollImuMessage& self) +void PollImuMessage::insert(Serializer& serializer) const { - insert(serializer, self.suppress_ack); + serializer.insert(suppress_ack); - insert(serializer, self.num_descriptors); + serializer.insert(num_descriptors); - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); } -void extract(::microstrain::Serializer& serializer, PollImuMessage& self) +void PollImuMessage::extract(Serializer& serializer) { - extract(serializer, self.suppress_ack); + serializer.extract(suppress_ack); - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); } TypedResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, suppressAck); + serializer.insert(suppressAck); - insert(serializer, numDescriptors); + serializer.insert(numDescriptors); assert(descriptors || (numDescriptors == 0)); for(unsigned int i=0; i < numDescriptors; i++) - insert(serializer, descriptors[i]); + serializer.insert(descriptors[i]); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_IMU_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const PollGnssMessage& self) +void PollGnssMessage::insert(Serializer& serializer) const { - insert(serializer, self.suppress_ack); + serializer.insert(suppress_ack); - insert(serializer, self.num_descriptors); + serializer.insert(num_descriptors); - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); } -void extract(::microstrain::Serializer& serializer, PollGnssMessage& self) +void PollGnssMessage::extract(Serializer& serializer) { - extract(serializer, self.suppress_ack); + serializer.extract(suppress_ack); - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); } TypedResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, suppressAck); + serializer.insert(suppressAck); - insert(serializer, numDescriptors); + serializer.insert(numDescriptors); assert(descriptors || (numDescriptors == 0)); for(unsigned int i=0; i < numDescriptors; i++) - insert(serializer, descriptors[i]); + serializer.insert(descriptors[i]); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_GNSS_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const PollFilterMessage& self) +void PollFilterMessage::insert(Serializer& serializer) const { - insert(serializer, self.suppress_ack); + serializer.insert(suppress_ack); - insert(serializer, self.num_descriptors); + serializer.insert(num_descriptors); - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); } -void extract(::microstrain::Serializer& serializer, PollFilterMessage& self) +void PollFilterMessage::extract(Serializer& serializer) { - extract(serializer, self.suppress_ack); + serializer.extract(suppress_ack); - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); } TypedResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, suppressAck); + serializer.insert(suppressAck); - insert(serializer, numDescriptors); + serializer.insert(numDescriptors); assert(descriptors || (numDescriptors == 0)); for(unsigned int i=0; i < numDescriptors; i++) - insert(serializer, descriptors[i]); + serializer.insert(descriptors[i]); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_FILTER_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ImuMessageFormat& self) +void ImuMessageFormat::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.num_descriptors); + serializer.insert(num_descriptors); - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); } } -void extract(::microstrain::Serializer& serializer, ImuMessageFormat& self) +void ImuMessageFormat::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); } } -void insert(::microstrain::Serializer& serializer, const ImuMessageFormat::Response& self) -{ - insert(serializer, self.num_descriptors); - - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); - -} -void extract(::microstrain::Serializer& serializer, ImuMessageFormat::Response& self) -{ - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); - -} - TypedResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, numDescriptors); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(numDescriptors); assert(descriptors || (numDescriptors == 0)); for(unsigned int i=0; i < numDescriptors; i++) - insert(serializer, descriptors[i]); + serializer.insert(descriptors[i]); assert(serializer.isOk()); @@ -220,112 +198,96 @@ TypedResult writeImuMessageFormat(C::mip_interface& device, ui } TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_IMU_MESSAGE_FORMAT, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); + deserializer.extract_count(*numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); for(unsigned int i=0; i < *numDescriptorsOut; i++) - extract(deserializer, descriptorsOut[i]); + deserializer.extract(descriptorsOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveImuMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult loadImuMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultImuMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GpsMessageFormat& self) +void GpsMessageFormat::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.num_descriptors); + serializer.insert(num_descriptors); - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); } } -void extract(::microstrain::Serializer& serializer, GpsMessageFormat& self) +void GpsMessageFormat::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); } } -void insert(::microstrain::Serializer& serializer, const GpsMessageFormat::Response& self) -{ - insert(serializer, self.num_descriptors); - - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); - -} -void extract(::microstrain::Serializer& serializer, GpsMessageFormat::Response& self) -{ - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); - -} - TypedResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, numDescriptors); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(numDescriptors); assert(descriptors || (numDescriptors == 0)); for(unsigned int i=0; i < numDescriptors; i++) - insert(serializer, descriptors[i]); + serializer.insert(descriptors[i]); assert(serializer.isOk()); @@ -333,112 +295,96 @@ TypedResult writeGpsMessageFormat(C::mip_interface& device, ui } TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_GNSS_MESSAGE_FORMAT, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); + deserializer.extract_count(*numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); for(unsigned int i=0; i < *numDescriptorsOut; i++) - extract(deserializer, descriptorsOut[i]); + deserializer.extract(descriptorsOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGpsMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult loadGpsMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultGpsMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const FilterMessageFormat& self) +void FilterMessageFormat::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.num_descriptors); + serializer.insert(num_descriptors); - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); } } -void extract(::microstrain::Serializer& serializer, FilterMessageFormat& self) +void FilterMessageFormat::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); } } -void insert(::microstrain::Serializer& serializer, const FilterMessageFormat::Response& self) -{ - insert(serializer, self.num_descriptors); - - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); - -} -void extract(::microstrain::Serializer& serializer, FilterMessageFormat::Response& self) -{ - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); - -} - TypedResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, numDescriptors); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(numDescriptors); assert(descriptors || (numDescriptors == 0)); for(unsigned int i=0; i < numDescriptors; i++) - insert(serializer, descriptors[i]); + serializer.insert(descriptors[i]); assert(serializer.isOk()); @@ -446,340 +392,266 @@ TypedResult writeFilterMessageFormat(C::mip_interface& devi } TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_FILTER_MESSAGE_FORMAT, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); + deserializer.extract_count(*numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); for(unsigned int i=0; i < *numDescriptorsOut; i++) - extract(deserializer, descriptorsOut[i]); + deserializer.extract(descriptorsOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveFilterMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult loadFilterMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultFilterMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ImuGetBaseRate& self) +void ImuGetBaseRate::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, ImuGetBaseRate& self) +void ImuGetBaseRate::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const ImuGetBaseRate::Response& self) -{ - insert(serializer, self.rate); - -} -void extract(::microstrain::Serializer& serializer, ImuGetBaseRate::Response& self) -{ - extract(serializer, self.rate); - } TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_IMU_BASE_RATE, NULL, 0, REPLY_IMU_BASE_RATE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(rateOut); - extract(deserializer, *rateOut); + deserializer.extract(*rateOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const GpsGetBaseRate& self) +void GpsGetBaseRate::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GpsGetBaseRate& self) +void GpsGetBaseRate::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GpsGetBaseRate::Response& self) -{ - insert(serializer, self.rate); - -} -void extract(::microstrain::Serializer& serializer, GpsGetBaseRate::Response& self) -{ - extract(serializer, self.rate); - } TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_GNSS_BASE_RATE, NULL, 0, REPLY_GNSS_BASE_RATE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(rateOut); - extract(deserializer, *rateOut); + deserializer.extract(*rateOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const FilterGetBaseRate& self) +void FilterGetBaseRate::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, FilterGetBaseRate& self) +void FilterGetBaseRate::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const FilterGetBaseRate::Response& self) -{ - insert(serializer, self.rate); - -} -void extract(::microstrain::Serializer& serializer, FilterGetBaseRate::Response& self) -{ - extract(serializer, self.rate); - } TypedResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_FILTER_BASE_RATE, NULL, 0, REPLY_FILTER_BASE_RATE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(rateOut); - extract(deserializer, *rateOut); + deserializer.extract(*rateOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const PollData& self) +void PollData::insert(Serializer& serializer) const { - insert(serializer, self.desc_set); + serializer.insert(desc_set); - insert(serializer, self.suppress_ack); + serializer.insert(suppress_ack); - insert(serializer, self.num_descriptors); + serializer.insert(num_descriptors); - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); } -void extract(::microstrain::Serializer& serializer, PollData& self) +void PollData::extract(Serializer& serializer) { - extract(serializer, self.desc_set); + serializer.extract(desc_set); - extract(serializer, self.suppress_ack); + serializer.extract(suppress_ack); - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); } TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, descSet); + serializer.insert(descSet); - insert(serializer, suppressAck); + serializer.insert(suppressAck); - insert(serializer, numDescriptors); + serializer.insert(numDescriptors); assert(descriptors || (numDescriptors == 0)); for(unsigned int i=0; i < numDescriptors; i++) - insert(serializer, descriptors[i]); + serializer.insert(descriptors[i]); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_DATA, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GetBaseRate& self) -{ - insert(serializer, self.desc_set); - -} -void extract(::microstrain::Serializer& serializer, GetBaseRate& self) -{ - extract(serializer, self.desc_set); - -} - -void insert(::microstrain::Serializer& serializer, const GetBaseRate::Response& self) +void GetBaseRate::insert(Serializer& serializer) const { - insert(serializer, self.desc_set); - - insert(serializer, self.rate); + serializer.insert(desc_set); } -void extract(::microstrain::Serializer& serializer, GetBaseRate::Response& self) +void GetBaseRate::extract(Serializer& serializer) { - extract(serializer, self.desc_set); - - extract(serializer, self.rate); + serializer.extract(desc_set); } TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, descSet); + serializer.insert(descSet); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_BASE_RATE, buffer, (uint8_t)serializer.length(), REPLY_BASE_RATE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, descSet); + deserializer.extract(descSet); assert(rateOut); - extract(deserializer, *rateOut); + deserializer.extract(*rateOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const MessageFormat& self) +void MessageFormat::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.desc_set); + serializer.insert(desc_set); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.num_descriptors); + serializer.insert(num_descriptors); - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); } } -void extract(::microstrain::Serializer& serializer, MessageFormat& self) +void MessageFormat::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.desc_set); + serializer.extract(desc_set); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); } } -void insert(::microstrain::Serializer& serializer, const MessageFormat::Response& self) -{ - insert(serializer, self.desc_set); - - insert(serializer, self.num_descriptors); - - for(unsigned int i=0; i < self.num_descriptors; i++) - insert(serializer, self.descriptors[i]); - -} -void extract(::microstrain::Serializer& serializer, MessageFormat::Response& self) -{ - extract(serializer, self.desc_set); - - extract_count(serializer, &self.num_descriptors, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_descriptors; i++) - extract(serializer, self.descriptors[i]); - -} - TypedResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, descSet); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(descSet); - insert(serializer, numDescriptors); + serializer.insert(numDescriptors); assert(descriptors || (numDescriptors == 0)); for(unsigned int i=0; i < numDescriptors; i++) - insert(serializer, descriptors[i]); + serializer.insert(descriptors[i]); assert(serializer.isOk()); @@ -787,40 +659,40 @@ TypedResult writeMessageFormat(C::mip_interface& device, uint8_t } TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, descSet); + serializer.insert(FunctionSelector::READ); + serializer.insert(descSet); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_MESSAGE_FORMAT, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, descSet); + deserializer.extract(descSet); - extract_count(deserializer, numDescriptorsOut, numDescriptorsOutMax); + deserializer.extract_count(*numDescriptorsOut, numDescriptorsOutMax); assert(descriptorsOut || (numDescriptorsOut == 0)); for(unsigned int i=0; i < *numDescriptorsOut; i++) - extract(deserializer, descriptorsOut[i]); + deserializer.extract(descriptorsOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveMessageFormat(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, descSet); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(descSet); assert(serializer.isOk()); @@ -828,11 +700,11 @@ TypedResult saveMessageFormat(C::mip_interface& device, uint8_t d } TypedResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, descSet); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(descSet); assert(serializer.isOk()); @@ -840,106 +712,90 @@ TypedResult loadMessageFormat(C::mip_interface& device, uint8_t d } TypedResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, descSet); + serializer.insert(FunctionSelector::RESET); + serializer.insert(descSet); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const NmeaPollData& self) +void NmeaPollData::insert(Serializer& serializer) const { - insert(serializer, self.suppress_ack); + serializer.insert(suppress_ack); - insert(serializer, self.count); + serializer.insert(count); - for(unsigned int i=0; i < self.count; i++) - insert(serializer, self.format_entries[i]); + for(unsigned int i=0; i < count; i++) + serializer.insert(format_entries[i]); } -void extract(::microstrain::Serializer& serializer, NmeaPollData& self) +void NmeaPollData::extract(Serializer& serializer) { - extract(serializer, self.suppress_ack); + serializer.extract(suppress_ack); - extract_count(serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); - for(unsigned int i=0; i < self.count; i++) - extract(serializer, self.format_entries[i]); + serializer.extract_count(count, sizeof(format_entries)/sizeof(format_entries[0])); + for(unsigned int i=0; i < count; i++) + serializer.extract(format_entries[i]); } TypedResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, suppressAck); + serializer.insert(suppressAck); - insert(serializer, count); + serializer.insert(count); assert(formatEntries || (count == 0)); for(unsigned int i=0; i < count; i++) - insert(serializer, formatEntries[i]); + serializer.insert(formatEntries[i]); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_NMEA_MESSAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const NmeaMessageFormat& self) +void NmeaMessageFormat::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.count); + serializer.insert(count); - for(unsigned int i=0; i < self.count; i++) - insert(serializer, self.format_entries[i]); + for(unsigned int i=0; i < count; i++) + serializer.insert(format_entries[i]); } } -void extract(::microstrain::Serializer& serializer, NmeaMessageFormat& self) +void NmeaMessageFormat::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract_count(serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); - for(unsigned int i=0; i < self.count; i++) - extract(serializer, self.format_entries[i]); + serializer.extract_count(count, sizeof(format_entries)/sizeof(format_entries[0])); + for(unsigned int i=0; i < count; i++) + serializer.extract(format_entries[i]); } } -void insert(::microstrain::Serializer& serializer, const NmeaMessageFormat::Response& self) -{ - insert(serializer, self.count); - - for(unsigned int i=0; i < self.count; i++) - insert(serializer, self.format_entries[i]); - -} -void extract(::microstrain::Serializer& serializer, NmeaMessageFormat::Response& self) -{ - extract_count(serializer, &self.count, sizeof(self.format_entries)/sizeof(self.format_entries[0])); - for(unsigned int i=0; i < self.count; i++) - extract(serializer, self.format_entries[i]); - -} - TypedResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, count); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(count); assert(formatEntries || (count == 0)); for(unsigned int i=0; i < count; i++) - insert(serializer, formatEntries[i]); + serializer.insert(formatEntries[i]); assert(serializer.isOk()); @@ -947,139 +803,128 @@ TypedResult writeNmeaMessageFormat(C::mip_interface& device, } TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_NMEA_MESSAGE_FORMAT, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract_count(deserializer, countOut, countOutMax); + deserializer.extract_count(*countOut, countOutMax); assert(formatEntriesOut || (countOut == 0)); for(unsigned int i=0; i < *countOut; i++) - extract(deserializer, formatEntriesOut[i]); + deserializer.extract(formatEntriesOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveNmeaMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult loadNmeaMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultNmeaMessageFormat(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const DeviceSettings& self) +void DeviceSettings::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); } -void extract(::microstrain::Serializer& serializer, DeviceSettings& self) +void DeviceSettings::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); } TypedResult saveDeviceSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult loadDeviceSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultDeviceSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const UartBaudrate& self) +void UartBaudrate::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.baud); + serializer.insert(baud); } } -void extract(::microstrain::Serializer& serializer, UartBaudrate& self) +void UartBaudrate::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.baud); + serializer.extract(baud); } } -void insert(::microstrain::Serializer& serializer, const UartBaudrate::Response& self) -{ - insert(serializer, self.baud); - -} -void extract(::microstrain::Serializer& serializer, UartBaudrate::Response& self) -{ - extract(serializer, self.baud); - -} - TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, baud); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(baud); assert(serializer.isOk()); @@ -1087,134 +932,119 @@ TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t b } TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length(), REPLY_UART_BAUDRATE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(baudOut); - extract(deserializer, *baudOut); + deserializer.extract(*baudOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveUartBaudrate(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); } TypedResult loadUartBaudrate(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); } TypedResult defaultUartBaudrate(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const FactoryStreaming& self) +void FactoryStreaming::insert(Serializer& serializer) const { - insert(serializer, self.action); + serializer.insert(action); - insert(serializer, self.reserved); + serializer.insert(reserved); } -void extract(::microstrain::Serializer& serializer, FactoryStreaming& self) +void FactoryStreaming::extract(Serializer& serializer) { - extract(serializer, self.action); + serializer.extract(action); - extract(serializer, self.reserved); + serializer.extract(reserved); } TypedResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, action); + serializer.insert(action); - insert(serializer, reserved); + serializer.insert(reserved); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const DatastreamControl& self) +void DatastreamControl::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.desc_set); + serializer.insert(desc_set); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); } } -void extract(::microstrain::Serializer& serializer, DatastreamControl& self) +void DatastreamControl::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.desc_set); + serializer.extract(desc_set); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); } } -void insert(::microstrain::Serializer& serializer, const DatastreamControl::Response& self) -{ - insert(serializer, self.desc_set); - - insert(serializer, self.enabled); - -} -void extract(::microstrain::Serializer& serializer, DatastreamControl::Response& self) -{ - extract(serializer, self.desc_set); - - extract(serializer, self.enabled); - -} - TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, descSet); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(descSet); - insert(serializer, enable); + serializer.insert(enable); assert(serializer.isOk()); @@ -1222,38 +1052,38 @@ TypedResult writeDatastreamControl(C::mip_interface& device, } TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, descSet); + serializer.insert(FunctionSelector::READ); + serializer.insert(descSet); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length(), REPLY_DATASTREAM_ENABLE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, descSet); + deserializer.extract(descSet); assert(enabledOut); - extract(deserializer, *enabledOut); + deserializer.extract(*enabledOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, descSet); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(descSet); assert(serializer.isOk()); @@ -1261,11 +1091,11 @@ TypedResult saveDatastreamControl(C::mip_interface& device, u } TypedResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, descSet); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(descSet); assert(serializer.isOk()); @@ -1273,110 +1103,59 @@ TypedResult loadDatastreamControl(C::mip_interface& device, u } TypedResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, descSet); + serializer.insert(FunctionSelector::RESET); + serializer.insert(descSet); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ConstellationSettings& self) +void ConstellationSettings::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.max_channels); + serializer.insert(max_channels); - insert(serializer, self.config_count); + serializer.insert(config_count); - for(unsigned int i=0; i < self.config_count; i++) - insert(serializer, self.settings[i]); + for(unsigned int i=0; i < config_count; i++) + serializer.insert(settings[i]); } } -void extract(::microstrain::Serializer& serializer, ConstellationSettings& self) +void ConstellationSettings::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.max_channels); + serializer.extract(max_channels); - extract_count(serializer, &self.config_count, sizeof(self.settings)/sizeof(self.settings[0])); - for(unsigned int i=0; i < self.config_count; i++) - extract(serializer, self.settings[i]); + serializer.extract_count(config_count, sizeof(settings)/sizeof(settings[0])); + for(unsigned int i=0; i < config_count; i++) + serializer.extract(settings[i]); } } -void insert(::microstrain::Serializer& serializer, const ConstellationSettings::Response& self) -{ - insert(serializer, self.max_channels_available); - - insert(serializer, self.max_channels_use); - - insert(serializer, self.config_count); - - for(unsigned int i=0; i < self.config_count; i++) - insert(serializer, self.settings[i]); - -} -void extract(::microstrain::Serializer& serializer, ConstellationSettings::Response& self) -{ - extract(serializer, self.max_channels_available); - - extract(serializer, self.max_channels_use); - - extract_count(serializer, &self.config_count, sizeof(self.settings)/sizeof(self.settings[0])); - for(unsigned int i=0; i < self.config_count; i++) - extract(serializer, self.settings[i]); - -} - -void insert(::microstrain::Serializer& serializer, const ConstellationSettings::Settings& self) -{ - insert(serializer, self.constellation_id); - - insert(serializer, self.enable); - - insert(serializer, self.reserved_channels); - - insert(serializer, self.max_channels); - - insert(serializer, self.option_flags); - -} -void extract(::microstrain::Serializer& serializer, ConstellationSettings::Settings& self) -{ - extract(serializer, self.constellation_id); - - extract(serializer, self.enable); - - extract(serializer, self.reserved_channels); - - extract(serializer, self.max_channels); - - extract(serializer, self.option_flags); - -} - TypedResult writeConstellationSettings(C::mip_interface& device, uint16_t maxChannels, uint8_t configCount, const ConstellationSettings::Settings* settings) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, maxChannels); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(maxChannels); - insert(serializer, configCount); + serializer.insert(configCount); assert(settings || (configCount == 0)); for(unsigned int i=0; i < configCount; i++) - insert(serializer, settings[i]); + serializer.insert(settings[i]); assert(serializer.isOk()); @@ -1384,138 +1163,114 @@ TypedResult writeConstellationSettings(C::mip_interface& } TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(maxChannelsAvailableOut); - extract(deserializer, *maxChannelsAvailableOut); + deserializer.extract(*maxChannelsAvailableOut); assert(maxChannelsUseOut); - extract(deserializer, *maxChannelsUseOut); + deserializer.extract(*maxChannelsUseOut); - extract_count(deserializer, configCountOut, configCountOutMax); + deserializer.extract_count(*configCountOut, configCountOutMax); assert(settingsOut || (configCountOut == 0)); for(unsigned int i=0; i < *configCountOut; i++) - extract(deserializer, settingsOut[i]); + deserializer.extract(settingsOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveConstellationSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult loadConstellationSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultConstellationSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GnssSbasSettings& self) +void GnssSbasSettings::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable_sbas); + serializer.insert(enable_sbas); - insert(serializer, self.sbas_options); + serializer.insert(sbas_options); - insert(serializer, self.num_included_prns); + serializer.insert(num_included_prns); - for(unsigned int i=0; i < self.num_included_prns; i++) - insert(serializer, self.included_prns[i]); + for(unsigned int i=0; i < num_included_prns; i++) + serializer.insert(included_prns[i]); } } -void extract(::microstrain::Serializer& serializer, GnssSbasSettings& self) +void GnssSbasSettings::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable_sbas); + serializer.extract(enable_sbas); - extract(serializer, self.sbas_options); + serializer.extract(sbas_options); - extract_count(serializer, &self.num_included_prns, sizeof(self.included_prns)/sizeof(self.included_prns[0])); - for(unsigned int i=0; i < self.num_included_prns; i++) - extract(serializer, self.included_prns[i]); + serializer.extract_count(num_included_prns, sizeof(included_prns)/sizeof(included_prns[0])); + for(unsigned int i=0; i < num_included_prns; i++) + serializer.extract(included_prns[i]); } } -void insert(::microstrain::Serializer& serializer, const GnssSbasSettings::Response& self) -{ - insert(serializer, self.enable_sbas); - - insert(serializer, self.sbas_options); - - insert(serializer, self.num_included_prns); - - for(unsigned int i=0; i < self.num_included_prns; i++) - insert(serializer, self.included_prns[i]); - -} -void extract(::microstrain::Serializer& serializer, GnssSbasSettings::Response& self) -{ - extract(serializer, self.enable_sbas); - - extract(serializer, self.sbas_options); - - extract_count(serializer, &self.num_included_prns, sizeof(self.included_prns)/sizeof(self.included_prns[0])); - for(unsigned int i=0; i < self.num_included_prns; i++) - extract(serializer, self.included_prns[i]); - -} - TypedResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enableSbas); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enableSbas); - insert(serializer, sbasOptions); + serializer.insert(sbasOptions); - insert(serializer, numIncludedPrns); + serializer.insert(numIncludedPrns); assert(includedPrns || (numIncludedPrns == 0)); for(unsigned int i=0; i < numIncludedPrns; i++) - insert(serializer, includedPrns[i]); + serializer.insert(includedPrns[i]); assert(serializer.isOk()); @@ -1523,114 +1278,99 @@ TypedResult writeGnssSbasSettings(C::mip_interface& device, ui } TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_SBAS_SETTINGS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableSbasOut); - extract(deserializer, *enableSbasOut); + deserializer.extract(*enableSbasOut); assert(sbasOptionsOut); - extract(deserializer, *sbasOptionsOut); + deserializer.extract(*sbasOptionsOut); - extract_count(deserializer, numIncludedPrnsOut, numIncludedPrnsOutMax); + deserializer.extract_count(*numIncludedPrnsOut, numIncludedPrnsOutMax); assert(includedPrnsOut || (numIncludedPrnsOut == 0)); for(unsigned int i=0; i < *numIncludedPrnsOut; i++) - extract(deserializer, includedPrnsOut[i]); + deserializer.extract(includedPrnsOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGnssSbasSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult loadGnssSbasSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultGnssSbasSettings(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GnssAssistedFix& self) +void GnssAssistedFix::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.option); + serializer.insert(option); - insert(serializer, self.flags); + serializer.insert(flags); } } -void extract(::microstrain::Serializer& serializer, GnssAssistedFix& self) +void GnssAssistedFix::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.option); + serializer.extract(option); - extract(serializer, self.flags); + serializer.extract(flags); } } -void insert(::microstrain::Serializer& serializer, const GnssAssistedFix::Response& self) -{ - insert(serializer, self.option); - - insert(serializer, self.flags); - -} -void extract(::microstrain::Serializer& serializer, GnssAssistedFix::Response& self) -{ - extract(serializer, self.option); - - extract(serializer, self.flags); - -} - TypedResult writeGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption option, uint8_t flags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, option); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(option); - insert(serializer, flags); + serializer.insert(flags); assert(serializer.isOk()); @@ -1638,119 +1378,100 @@ TypedResult writeGnssAssistedFix(C::mip_interface& device, Gnss } TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(optionOut); - extract(deserializer, *optionOut); + deserializer.extract(*optionOut); assert(flagsOut); - extract(deserializer, *flagsOut); + deserializer.extract(*flagsOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGnssAssistedFix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult loadGnssAssistedFix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultGnssAssistedFix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GnssTimeAssistance& self) +void GnssTimeAssistance::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.tow); + serializer.insert(tow); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.accuracy); + serializer.insert(accuracy); } } -void extract(::microstrain::Serializer& serializer, GnssTimeAssistance& self) +void GnssTimeAssistance::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.tow); + serializer.extract(tow); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.accuracy); + serializer.extract(accuracy); } } -void insert(::microstrain::Serializer& serializer, const GnssTimeAssistance::Response& self) -{ - insert(serializer, self.tow); - - insert(serializer, self.week_number); - - insert(serializer, self.accuracy); - -} -void extract(::microstrain::Serializer& serializer, GnssTimeAssistance::Response& self) -{ - extract(serializer, self.tow); - - extract(serializer, self.week_number); - - extract(serializer, self.accuracy); - -} - TypedResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, tow); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(tow); - insert(serializer, weekNumber); + serializer.insert(weekNumber); - insert(serializer, accuracy); + serializer.insert(accuracy); assert(serializer.isOk()); @@ -1758,112 +1479,85 @@ TypedResult writeGnssTimeAssistance(C::mip_interface& device } TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)serializer.length(), REPLY_GNSS_TIME_ASSISTANCE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(towOut); - extract(deserializer, *towOut); + deserializer.extract(*towOut); assert(weekNumberOut); - extract(deserializer, *weekNumberOut); + deserializer.extract(*weekNumberOut); assert(accuracyOut); - extract(deserializer, *accuracyOut); + deserializer.extract(*accuracyOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const ImuLowpassFilter& self) +void ImuLowpassFilter::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.target_descriptor); + serializer.insert(target_descriptor); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); - insert(serializer, self.manual); + serializer.insert(manual); - insert(serializer, self.frequency); + serializer.insert(frequency); - insert(serializer, self.reserved); + serializer.insert(reserved); } } -void extract(::microstrain::Serializer& serializer, ImuLowpassFilter& self) +void ImuLowpassFilter::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.target_descriptor); + serializer.extract(target_descriptor); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); - extract(serializer, self.manual); + serializer.extract(manual); - extract(serializer, self.frequency); + serializer.extract(frequency); - extract(serializer, self.reserved); + serializer.extract(reserved); } } -void insert(::microstrain::Serializer& serializer, const ImuLowpassFilter::Response& self) -{ - insert(serializer, self.target_descriptor); - - insert(serializer, self.enable); - - insert(serializer, self.manual); - - insert(serializer, self.frequency); - - insert(serializer, self.reserved); - -} -void extract(::microstrain::Serializer& serializer, ImuLowpassFilter::Response& self) -{ - extract(serializer, self.target_descriptor); - - extract(serializer, self.enable); - - extract(serializer, self.manual); - - extract(serializer, self.frequency); - - extract(serializer, self.reserved); - -} - TypedResult writeImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, targetDescriptor); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(targetDescriptor); - insert(serializer, enable); + serializer.insert(enable); - insert(serializer, manual); + serializer.insert(manual); - insert(serializer, frequency); + serializer.insert(frequency); - insert(serializer, reserved); + serializer.insert(reserved); assert(serializer.isOk()); @@ -1871,47 +1565,47 @@ TypedResult writeImuLowpassFilter(C::mip_interface& device, ui } TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, targetDescriptor); + serializer.insert(FunctionSelector::READ); + serializer.insert(targetDescriptor); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length(), REPLY_ADVANCED_DATA_FILTER, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, targetDescriptor); + deserializer.extract(targetDescriptor); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); assert(manualOut); - extract(deserializer, *manualOut); + deserializer.extract(*manualOut); assert(frequencyOut); - extract(deserializer, *frequencyOut); + deserializer.extract(*frequencyOut); assert(reservedOut); - extract(deserializer, *reservedOut); + deserializer.extract(*reservedOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, targetDescriptor); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(targetDescriptor); assert(serializer.isOk()); @@ -1919,11 +1613,11 @@ TypedResult saveImuLowpassFilter(C::mip_interface& device, uin } TypedResult loadImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, targetDescriptor); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(targetDescriptor); assert(serializer.isOk()); @@ -1931,55 +1625,44 @@ TypedResult loadImuLowpassFilter(C::mip_interface& device, uin } TypedResult defaultImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, targetDescriptor); + serializer.insert(FunctionSelector::RESET); + serializer.insert(targetDescriptor); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const PpsSource& self) +void PpsSource::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.source); + serializer.insert(source); } } -void extract(::microstrain::Serializer& serializer, PpsSource& self) +void PpsSource::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.source); + serializer.extract(source); } } -void insert(::microstrain::Serializer& serializer, const PpsSource::Response& self) -{ - insert(serializer, self.source); - -} -void extract(::microstrain::Serializer& serializer, PpsSource::Response& self) -{ - extract(serializer, self.source); - -} - TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(source); assert(serializer.isOk()); @@ -1987,126 +1670,103 @@ TypedResult writePpsSource(C::mip_interface& device, PpsSource::Sourc } TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_PPS_SOURCE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(sourceOut); - extract(deserializer, *sourceOut); + deserializer.extract(*sourceOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult savePpsSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult loadPpsSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult defaultPpsSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GpioConfig& self) +void GpioConfig::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.pin); + serializer.insert(pin); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.feature); + serializer.insert(feature); - insert(serializer, self.behavior); + serializer.insert(behavior); - insert(serializer, self.pin_mode); + serializer.insert(pin_mode); } } -void extract(::microstrain::Serializer& serializer, GpioConfig& self) +void GpioConfig::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.pin); + serializer.extract(pin); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.feature); + serializer.extract(feature); - extract(serializer, self.behavior); + serializer.extract(behavior); - extract(serializer, self.pin_mode); + serializer.extract(pin_mode); } } -void insert(::microstrain::Serializer& serializer, const GpioConfig::Response& self) -{ - insert(serializer, self.pin); - - insert(serializer, self.feature); - - insert(serializer, self.behavior); - - insert(serializer, self.pin_mode); - -} -void extract(::microstrain::Serializer& serializer, GpioConfig::Response& self) -{ - extract(serializer, self.pin); - - extract(serializer, self.feature); - - extract(serializer, self.behavior); - - extract(serializer, self.pin_mode); - -} - TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, pin); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(pin); - insert(serializer, feature); + serializer.insert(feature); - insert(serializer, behavior); + serializer.insert(behavior); - insert(serializer, pinMode); + serializer.insert(pinMode); assert(serializer.isOk()); @@ -2114,44 +1774,44 @@ TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, G } TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, pin); + serializer.insert(FunctionSelector::READ); + serializer.insert(pin); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_GPIO_CONFIG, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, pin); + deserializer.extract(pin); assert(featureOut); - extract(deserializer, *featureOut); + deserializer.extract(*featureOut); assert(behaviorOut); - extract(deserializer, *behaviorOut); + deserializer.extract(*behaviorOut); assert(pinModeOut); - extract(deserializer, *pinModeOut); + deserializer.extract(*pinModeOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, pin); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(pin); assert(serializer.isOk()); @@ -2159,11 +1819,11 @@ TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) } TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, pin); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(pin); assert(serializer.isOk()); @@ -2171,71 +1831,56 @@ TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) } TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, pin); + serializer.insert(FunctionSelector::RESET); + serializer.insert(pin); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GpioState& self) +void GpioState::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE || self.function == FunctionSelector::READ ) + if( function == FunctionSelector::WRITE || function == FunctionSelector::READ ) { - insert(serializer, self.pin); + serializer.insert(pin); } - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.state); + serializer.insert(state); } } -void extract(::microstrain::Serializer& serializer, GpioState& self) +void GpioState::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE || self.function == FunctionSelector::READ ) + if( function == FunctionSelector::WRITE || function == FunctionSelector::READ ) { - extract(serializer, self.pin); + serializer.extract(pin); } - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.state); + serializer.extract(state); } } -void insert(::microstrain::Serializer& serializer, const GpioState::Response& self) -{ - insert(serializer, self.pin); - - insert(serializer, self.state); - -} -void extract(::microstrain::Serializer& serializer, GpioState::Response& self) -{ - extract(serializer, self.pin); - - extract(serializer, self.state); - -} - TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, pin); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(pin); - insert(serializer, state); + serializer.insert(state); assert(serializer.isOk()); @@ -2243,90 +1888,71 @@ TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, boo } TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, pin); + serializer.insert(FunctionSelector::READ); + serializer.insert(pin); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)serializer.length(), REPLY_GPIO_STATE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, pin); + deserializer.extract(pin); assert(stateOut); - extract(deserializer, *stateOut); + deserializer.extract(*stateOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const Odometer& self) +void Odometer::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.mode); + serializer.insert(mode); - insert(serializer, self.scaling); + serializer.insert(scaling); - insert(serializer, self.uncertainty); + serializer.insert(uncertainty); } } -void extract(::microstrain::Serializer& serializer, Odometer& self) +void Odometer::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.mode); + serializer.extract(mode); - extract(serializer, self.scaling); + serializer.extract(scaling); - extract(serializer, self.uncertainty); + serializer.extract(uncertainty); } } -void insert(::microstrain::Serializer& serializer, const Odometer::Response& self) -{ - insert(serializer, self.mode); - - insert(serializer, self.scaling); - - insert(serializer, self.uncertainty); - -} -void extract(::microstrain::Serializer& serializer, Odometer::Response& self) -{ - extract(serializer, self.mode); - - extract(serializer, self.scaling); - - extract(serializer, self.uncertainty); - -} - TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, mode); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(mode); - insert(serializer, scaling); + serializer.insert(scaling); - insert(serializer, uncertainty); + serializer.insert(uncertainty); assert(serializer.isOk()); @@ -2334,193 +1960,139 @@ TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mod } TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_ODOMETER_CONFIG, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(modeOut); - extract(deserializer, *modeOut); + deserializer.extract(*modeOut); assert(scalingOut); - extract(deserializer, *scalingOut); + deserializer.extract(*scalingOut); assert(uncertaintyOut); - extract(deserializer, *uncertaintyOut); + deserializer.extract(*uncertaintyOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveOdometer(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult loadOdometer(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); } TypedResult defaultOdometer(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GetEventSupport& self) -{ - insert(serializer, self.query); - -} -void extract(::microstrain::Serializer& serializer, GetEventSupport& self) -{ - extract(serializer, self.query); - -} - -void insert(::microstrain::Serializer& serializer, const GetEventSupport::Response& self) -{ - insert(serializer, self.query); - - insert(serializer, self.max_instances); - - insert(serializer, self.num_entries); - - for(unsigned int i=0; i < self.num_entries; i++) - insert(serializer, self.entries[i]); - -} -void extract(::microstrain::Serializer& serializer, GetEventSupport::Response& self) -{ - extract(serializer, self.query); - - extract(serializer, self.max_instances); - - extract_count(serializer, &self.num_entries, sizeof(self.entries)/sizeof(self.entries[0])); - for(unsigned int i=0; i < self.num_entries; i++) - extract(serializer, self.entries[i]); - -} - -void insert(::microstrain::Serializer& serializer, const GetEventSupport::Info& self) +void GetEventSupport::insert(Serializer& serializer) const { - insert(serializer, self.type); - - insert(serializer, self.count); + serializer.insert(query); } -void extract(::microstrain::Serializer& serializer, GetEventSupport::Info& self) +void GetEventSupport::extract(Serializer& serializer) { - extract(serializer, self.type); - - extract(serializer, self.count); + serializer.extract(query); } TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, query); + serializer.insert(query); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_SUPPORT, buffer, (uint8_t)serializer.length(), REPLY_EVENT_SUPPORT, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, query); + deserializer.extract(query); assert(maxInstancesOut); - extract(deserializer, *maxInstancesOut); + deserializer.extract(*maxInstancesOut); - extract_count(deserializer, numEntriesOut, numEntriesOutMax); + deserializer.extract_count(*numEntriesOut, numEntriesOutMax); assert(entriesOut || (numEntriesOut == 0)); for(unsigned int i=0; i < *numEntriesOut; i++) - extract(deserializer, entriesOut[i]); + deserializer.extract(entriesOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const EventControl& self) +void EventControl::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.instance); + serializer.insert(instance); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.mode); + serializer.insert(mode); } } -void extract(::microstrain::Serializer& serializer, EventControl& self) +void EventControl::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.instance); + serializer.extract(instance); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.mode); + serializer.extract(mode); } } -void insert(::microstrain::Serializer& serializer, const EventControl::Response& self) -{ - insert(serializer, self.instance); - - insert(serializer, self.mode); - -} -void extract(::microstrain::Serializer& serializer, EventControl::Response& self) -{ - extract(serializer, self.instance); - - extract(serializer, self.mode); - -} - TypedResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, instance); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(instance); - insert(serializer, mode); + serializer.insert(mode); assert(serializer.isOk()); @@ -2528,38 +2100,38 @@ TypedResult writeEventControl(C::mip_interface& device, uint8_t in } TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, instance); + serializer.insert(FunctionSelector::READ); + serializer.insert(instance); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_EVENT_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, instance); + deserializer.extract(instance); assert(modeOut); - extract(deserializer, *modeOut); + deserializer.extract(*modeOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveEventControl(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, instance); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(instance); assert(serializer.isOk()); @@ -2567,11 +2139,11 @@ TypedResult saveEventControl(C::mip_interface& device, uint8_t ins } TypedResult loadEventControl(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, instance); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(instance); assert(serializer.isOk()); @@ -2579,388 +2151,186 @@ TypedResult loadEventControl(C::mip_interface& device, uint8_t ins } TypedResult defaultEventControl(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, instance); + serializer.insert(FunctionSelector::RESET); + serializer.insert(instance); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus& self) +void GetEventTriggerStatus::insert(Serializer& serializer) const { - insert(serializer, self.requested_count); + serializer.insert(requested_count); - for(unsigned int i=0; i < self.requested_count; i++) - insert(serializer, self.requested_instances[i]); + for(unsigned int i=0; i < requested_count; i++) + serializer.insert(requested_instances[i]); } -void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus& self) +void GetEventTriggerStatus::extract(Serializer& serializer) { - extract_count(serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); - for(unsigned int i=0; i < self.requested_count; i++) - extract(serializer, self.requested_instances[i]); + serializer.extract_count(requested_count, sizeof(requested_instances)/sizeof(requested_instances[0])); + for(unsigned int i=0; i < requested_count; i++) + serializer.extract(requested_instances[i]); } -void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus::Response& self) -{ - insert(serializer, self.count); - - for(unsigned int i=0; i < self.count; i++) - insert(serializer, self.triggers[i]); - -} -void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus::Response& self) +TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut) { - extract_count(serializer, &self.count, sizeof(self.triggers)/sizeof(self.triggers[0])); - for(unsigned int i=0; i < self.count; i++) - extract(serializer, self.triggers[i]); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); -} - -void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus::Entry& self) -{ - insert(serializer, self.type); + serializer.insert(requestedCount); - insert(serializer, self.status); + assert(requestedInstances || (requestedCount == 0)); + for(unsigned int i=0; i < requestedCount; i++) + serializer.insert(requestedInstances[i]); -} -void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus::Entry& self) -{ - extract(serializer, self.type); + assert(serializer.isOk()); - extract(serializer, self.status); + uint8_t responseLength = sizeof(buffer); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_STATUS, buffer, (uint8_t)serializer.length(), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); -} - -TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut) -{ - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); - - insert(serializer, requestedCount); - - assert(requestedInstances || (requestedCount == 0)); - for(unsigned int i=0; i < requestedCount; i++) - insert(serializer, requestedInstances[i]); - - assert(serializer.isOk()); - - uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_STATUS, buffer, (uint8_t)serializer.length(), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); - - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract_count(deserializer, countOut, countOutMax); + deserializer.extract_count(*countOut, countOutMax); assert(triggersOut || (countOut == 0)); for(unsigned int i=0; i < *countOut; i++) - extract(deserializer, triggersOut[i]); + deserializer.extract(triggersOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const GetEventActionStatus& self) +void GetEventActionStatus::insert(Serializer& serializer) const { - insert(serializer, self.requested_count); + serializer.insert(requested_count); - for(unsigned int i=0; i < self.requested_count; i++) - insert(serializer, self.requested_instances[i]); + for(unsigned int i=0; i < requested_count; i++) + serializer.insert(requested_instances[i]); } -void extract(::microstrain::Serializer& serializer, GetEventActionStatus& self) +void GetEventActionStatus::extract(Serializer& serializer) { - extract_count(serializer, &self.requested_count, sizeof(self.requested_instances)/sizeof(self.requested_instances[0])); - for(unsigned int i=0; i < self.requested_count; i++) - extract(serializer, self.requested_instances[i]); - -} - -void insert(::microstrain::Serializer& serializer, const GetEventActionStatus::Response& self) -{ - insert(serializer, self.count); - - for(unsigned int i=0; i < self.count; i++) - insert(serializer, self.actions[i]); - -} -void extract(::microstrain::Serializer& serializer, GetEventActionStatus::Response& self) -{ - extract_count(serializer, &self.count, sizeof(self.actions)/sizeof(self.actions[0])); - for(unsigned int i=0; i < self.count; i++) - extract(serializer, self.actions[i]); - -} - -void insert(::microstrain::Serializer& serializer, const GetEventActionStatus::Entry& self) -{ - insert(serializer, self.action_type); - - insert(serializer, self.trigger_id); - -} -void extract(::microstrain::Serializer& serializer, GetEventActionStatus::Entry& self) -{ - extract(serializer, self.action_type); - - extract(serializer, self.trigger_id); + serializer.extract_count(requested_count, sizeof(requested_instances)/sizeof(requested_instances[0])); + for(unsigned int i=0; i < requested_count; i++) + serializer.extract(requested_instances[i]); } TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, requestedCount); + serializer.insert(requestedCount); assert(requestedInstances || (requestedCount == 0)); for(unsigned int i=0; i < requestedCount; i++) - insert(serializer, requestedInstances[i]); + serializer.insert(requestedInstances[i]); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_STATUS, buffer, (uint8_t)serializer.length(), REPLY_EVENT_ACTION_STATUS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract_count(deserializer, countOut, countOutMax); + deserializer.extract_count(*countOut, countOutMax); assert(actionsOut || (countOut == 0)); for(unsigned int i=0; i < *countOut; i++) - extract(deserializer, actionsOut[i]); + deserializer.extract(actionsOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const EventTrigger& self) +void EventTrigger::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.instance); + serializer.insert(instance); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.type); + serializer.insert(type); - if( self.type == EventTrigger::Type::GPIO ) + if( type == EventTrigger::Type::GPIO ) { - insert(serializer, self.parameters.gpio); + serializer.insert(parameters.gpio); } - if( self.type == EventTrigger::Type::THRESHOLD ) + if( type == EventTrigger::Type::THRESHOLD ) { - insert(serializer, self.parameters.threshold); + serializer.insert(parameters.threshold); } - if( self.type == EventTrigger::Type::COMBINATION ) + if( type == EventTrigger::Type::COMBINATION ) { - insert(serializer, self.parameters.combination); + serializer.insert(parameters.combination); } } } -void extract(::microstrain::Serializer& serializer, EventTrigger& self) +void EventTrigger::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.instance); + serializer.extract(instance); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.type); + serializer.extract(type); - if( self.type == EventTrigger::Type::GPIO ) + if( type == EventTrigger::Type::GPIO ) { - extract(serializer, self.parameters.gpio); + serializer.extract(parameters.gpio); } - if( self.type == EventTrigger::Type::THRESHOLD ) + if( type == EventTrigger::Type::THRESHOLD ) { - extract(serializer, self.parameters.threshold); + serializer.extract(parameters.threshold); } - if( self.type == EventTrigger::Type::COMBINATION ) + if( type == EventTrigger::Type::COMBINATION ) { - extract(serializer, self.parameters.combination); + serializer.extract(parameters.combination); } } } -void insert(::microstrain::Serializer& serializer, const EventTrigger::Response& self) -{ - insert(serializer, self.instance); - - insert(serializer, self.type); - - if( self.type == EventTrigger::Type::GPIO ) - { - insert(serializer, self.parameters.gpio); - - } - if( self.type == EventTrigger::Type::THRESHOLD ) - { - insert(serializer, self.parameters.threshold); - - } - if( self.type == EventTrigger::Type::COMBINATION ) - { - insert(serializer, self.parameters.combination); - - } -} -void extract(::microstrain::Serializer& serializer, EventTrigger::Response& self) -{ - extract(serializer, self.instance); - - extract(serializer, self.type); - - if( self.type == EventTrigger::Type::GPIO ) - { - extract(serializer, self.parameters.gpio); - - } - if( self.type == EventTrigger::Type::THRESHOLD ) - { - extract(serializer, self.parameters.threshold); - - } - if( self.type == EventTrigger::Type::COMBINATION ) - { - extract(serializer, self.parameters.combination); - - } -} - -void insert(::microstrain::Serializer& serializer, const EventTrigger::GpioParams& self) -{ - insert(serializer, self.pin); - - insert(serializer, self.mode); - -} -void extract(::microstrain::Serializer& serializer, EventTrigger::GpioParams& self) -{ - extract(serializer, self.pin); - - extract(serializer, self.mode); - -} - -void insert(::microstrain::Serializer& serializer, const EventTrigger::ThresholdParams& self) -{ - insert(serializer, self.desc_set); - - insert(serializer, self.field_desc); - - insert(serializer, self.param_id); - - insert(serializer, self.type); - - if( self.type == EventTrigger::ThresholdParams::Type::WINDOW ) - { - insert(serializer, self.low_thres); - - } - if( self.type == EventTrigger::ThresholdParams::Type::INTERVAL ) - { - insert(serializer, self.int_thres); - - } - if( self.type == EventTrigger::ThresholdParams::Type::WINDOW ) - { - insert(serializer, self.high_thres); - - } - if( self.type == EventTrigger::ThresholdParams::Type::INTERVAL ) - { - insert(serializer, self.interval); - - } -} -void extract(::microstrain::Serializer& serializer, EventTrigger::ThresholdParams& self) -{ - extract(serializer, self.desc_set); - - extract(serializer, self.field_desc); - - extract(serializer, self.param_id); - - extract(serializer, self.type); - - if( self.type == EventTrigger::ThresholdParams::Type::WINDOW ) - { - extract(serializer, self.low_thres); - - } - if( self.type == EventTrigger::ThresholdParams::Type::INTERVAL ) - { - extract(serializer, self.int_thres); - - } - if( self.type == EventTrigger::ThresholdParams::Type::WINDOW ) - { - extract(serializer, self.high_thres); - - } - if( self.type == EventTrigger::ThresholdParams::Type::INTERVAL ) - { - extract(serializer, self.interval); - - } -} - -void insert(::microstrain::Serializer& serializer, const EventTrigger::CombinationParams& self) -{ - insert(serializer, self.logic_table); - - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.input_triggers[i]); - -} -void extract(::microstrain::Serializer& serializer, EventTrigger::CombinationParams& self) -{ - extract(serializer, self.logic_table); - - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.input_triggers[i]); - -} - TypedResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, instance); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(instance); - insert(serializer, type); + serializer.insert(type); if( type == EventTrigger::Type::GPIO ) { - insert(serializer, parameters.gpio); + serializer.insert(parameters.gpio); } if( type == EventTrigger::Type::THRESHOLD ) { - insert(serializer, parameters.threshold); + serializer.insert(parameters.threshold); } if( type == EventTrigger::Type::COMBINATION ) { - insert(serializer, parameters.combination); + serializer.insert(parameters.combination); } assert(serializer.isOk()); @@ -2969,53 +2339,53 @@ TypedResult writeEventTrigger(C::mip_interface& device, uint8_t in } TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, instance); + serializer.insert(FunctionSelector::READ); + serializer.insert(instance); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_EVENT_TRIGGER_CONFIG, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, instance); + deserializer.extract(instance); assert(typeOut); - extract(deserializer, *typeOut); + deserializer.extract(*typeOut); if( *typeOut == EventTrigger::Type::GPIO ) { - extract(deserializer, parametersOut->gpio); + deserializer.extract(parametersOut->gpio); } if( *typeOut == EventTrigger::Type::THRESHOLD ) { - extract(deserializer, parametersOut->threshold); + deserializer.extract(parametersOut->threshold); } if( *typeOut == EventTrigger::Type::COMBINATION ) { - extract(deserializer, parametersOut->combination); + deserializer.extract(parametersOut->combination); } if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveEventTrigger(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, instance); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(instance); assert(serializer.isOk()); @@ -3023,11 +2393,11 @@ TypedResult saveEventTrigger(C::mip_interface& device, uint8_t ins } TypedResult loadEventTrigger(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, instance); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(instance); assert(serializer.isOk()); @@ -3035,163 +2405,85 @@ TypedResult loadEventTrigger(C::mip_interface& device, uint8_t ins } TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, instance); + serializer.insert(FunctionSelector::RESET); + serializer.insert(instance); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const EventAction& self) +void EventAction::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.instance); + serializer.insert(instance); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.trigger); + serializer.insert(trigger); - insert(serializer, self.type); + serializer.insert(type); - if( self.type == EventAction::Type::GPIO ) + if( type == EventAction::Type::GPIO ) { - insert(serializer, self.parameters.gpio); + serializer.insert(parameters.gpio); } - if( self.type == EventAction::Type::MESSAGE ) + if( type == EventAction::Type::MESSAGE ) { - insert(serializer, self.parameters.message); + serializer.insert(parameters.message); } } } -void extract(::microstrain::Serializer& serializer, EventAction& self) +void EventAction::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.instance); + serializer.extract(instance); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.trigger); + serializer.extract(trigger); - extract(serializer, self.type); + serializer.extract(type); - if( self.type == EventAction::Type::GPIO ) + if( type == EventAction::Type::GPIO ) { - extract(serializer, self.parameters.gpio); + serializer.extract(parameters.gpio); } - if( self.type == EventAction::Type::MESSAGE ) + if( type == EventAction::Type::MESSAGE ) { - extract(serializer, self.parameters.message); + serializer.extract(parameters.message); } } } -void insert(::microstrain::Serializer& serializer, const EventAction::Response& self) -{ - insert(serializer, self.instance); - - insert(serializer, self.trigger); - - insert(serializer, self.type); - - if( self.type == EventAction::Type::GPIO ) - { - insert(serializer, self.parameters.gpio); - - } - if( self.type == EventAction::Type::MESSAGE ) - { - insert(serializer, self.parameters.message); - - } -} -void extract(::microstrain::Serializer& serializer, EventAction::Response& self) -{ - extract(serializer, self.instance); - - extract(serializer, self.trigger); - - extract(serializer, self.type); - - if( self.type == EventAction::Type::GPIO ) - { - extract(serializer, self.parameters.gpio); - - } - if( self.type == EventAction::Type::MESSAGE ) - { - extract(serializer, self.parameters.message); - - } -} - -void insert(::microstrain::Serializer& serializer, const EventAction::GpioParams& self) -{ - insert(serializer, self.pin); - - insert(serializer, self.mode); - -} -void extract(::microstrain::Serializer& serializer, EventAction::GpioParams& self) -{ - extract(serializer, self.pin); - - extract(serializer, self.mode); - -} - -void insert(::microstrain::Serializer& serializer, const EventAction::MessageParams& self) -{ - insert(serializer, self.desc_set); - - insert(serializer, self.decimation); - - insert(serializer, self.num_fields); - - for(unsigned int i=0; i < self.num_fields; i++) - insert(serializer, self.descriptors[i]); - -} -void extract(::microstrain::Serializer& serializer, EventAction::MessageParams& self) -{ - extract(serializer, self.desc_set); - - extract(serializer, self.decimation); - - extract_count(serializer, &self.num_fields, sizeof(self.descriptors)/sizeof(self.descriptors[0])); - for(unsigned int i=0; i < self.num_fields; i++) - extract(serializer, self.descriptors[i]); - -} - TypedResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, instance); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(instance); - insert(serializer, trigger); + serializer.insert(trigger); - insert(serializer, type); + serializer.insert(type); if( type == EventAction::Type::GPIO ) { - insert(serializer, parameters.gpio); + serializer.insert(parameters.gpio); } if( type == EventAction::Type::MESSAGE ) { - insert(serializer, parameters.message); + serializer.insert(parameters.message); } assert(serializer.isOk()); @@ -3200,51 +2492,51 @@ TypedResult writeEventAction(C::mip_interface& device, uint8_t inst } TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, instance); + serializer.insert(FunctionSelector::READ); + serializer.insert(instance); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_EVENT_ACTION_CONFIG, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, instance); + deserializer.extract(instance); assert(triggerOut); - extract(deserializer, *triggerOut); + deserializer.extract(*triggerOut); assert(typeOut); - extract(deserializer, *typeOut); + deserializer.extract(*typeOut); if( *typeOut == EventAction::Type::GPIO ) { - extract(deserializer, parametersOut->gpio); + deserializer.extract(parametersOut->gpio); } if( *typeOut == EventAction::Type::MESSAGE ) { - extract(deserializer, parametersOut->message); + deserializer.extract(parametersOut->message); } if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveEventAction(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, instance); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(instance); assert(serializer.isOk()); @@ -3252,11 +2544,11 @@ TypedResult saveEventAction(C::mip_interface& device, uint8_t insta } TypedResult loadEventAction(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, instance); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(instance); assert(serializer.isOk()); @@ -3264,61 +2556,46 @@ TypedResult loadEventAction(C::mip_interface& device, uint8_t insta } TypedResult defaultEventAction(C::mip_interface& device, uint8_t instance) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, instance); + serializer.insert(FunctionSelector::RESET); + serializer.insert(instance); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AccelBias& self) +void AccelBias::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias[i]); + serializer.insert(bias); } } -void extract(::microstrain::Serializer& serializer, AccelBias& self) +void AccelBias::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias[i]); + serializer.extract(bias); } } -void insert(::microstrain::Serializer& serializer, const AccelBias::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias[i]); - -} -void extract(::microstrain::Serializer& serializer, AccelBias::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias[i]); - -} - TypedResult writeAccelBias(C::mip_interface& device, const float* bias) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(bias || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(bias); for(unsigned int i=0; i < 3; i++) - insert(serializer, bias[i]); + serializer.insert(bias[i]); assert(serializer.isOk()); @@ -3326,103 +2603,88 @@ TypedResult writeAccelBias(C::mip_interface& device, const float* bia } TypedResult readAccelBias(C::mip_interface& device, float* biasOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_BIAS_VECTOR, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(biasOut || (3 == 0)); + assert(biasOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, biasOut[i]); + deserializer.extract(biasOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAccelBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult loadAccelBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult defaultAccelBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GyroBias& self) +void GyroBias::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias[i]); + serializer.insert(bias); } } -void extract(::microstrain::Serializer& serializer, GyroBias& self) +void GyroBias::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias[i]); + serializer.extract(bias); } } -void insert(::microstrain::Serializer& serializer, const GyroBias::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias[i]); - -} -void extract(::microstrain::Serializer& serializer, GyroBias::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias[i]); - -} - TypedResult writeGyroBias(C::mip_interface& device, const float* bias) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(bias || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(bias); for(unsigned int i=0; i < 3; i++) - insert(serializer, bias[i]); + serializer.insert(bias[i]); assert(serializer.isOk()); @@ -3430,152 +2692,124 @@ TypedResult writeGyroBias(C::mip_interface& device, const float* bias) } TypedResult readGyroBias(C::mip_interface& device, float* biasOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(biasOut || (3 == 0)); + assert(biasOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, biasOut[i]); + deserializer.extract(biasOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGyroBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult loadGyroBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); } TypedResult defaultGyroBias(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const CaptureGyroBias& self) +void CaptureGyroBias::insert(Serializer& serializer) const { - insert(serializer, self.averaging_time_ms); + serializer.insert(averaging_time_ms); } -void extract(::microstrain::Serializer& serializer, CaptureGyroBias& self) +void CaptureGyroBias::extract(Serializer& serializer) { - extract(serializer, self.averaging_time_ms); - -} - -void insert(::microstrain::Serializer& serializer, const CaptureGyroBias::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias[i]); - -} -void extract(::microstrain::Serializer& serializer, CaptureGyroBias::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias[i]); + serializer.extract(averaging_time_ms); } TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, averagingTimeMs); + serializer.insert(averagingTimeMs); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CAPTURE_GYRO_BIAS, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(biasOut || (3 == 0)); + assert(biasOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, biasOut[i]); + deserializer.extract(biasOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const MagHardIronOffset& self) +void MagHardIronOffset::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset[i]); + serializer.insert(offset); } } -void extract(::microstrain::Serializer& serializer, MagHardIronOffset& self) +void MagHardIronOffset::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset[i]); + serializer.extract(offset); } } -void insert(::microstrain::Serializer& serializer, const MagHardIronOffset::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset[i]); - -} -void extract(::microstrain::Serializer& serializer, MagHardIronOffset::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset[i]); - -} - TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(offset || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(offset); for(unsigned int i=0; i < 3; i++) - insert(serializer, offset[i]); + serializer.insert(offset[i]); assert(serializer.isOk()); @@ -3583,103 +2817,88 @@ TypedResult writeMagHardIronOffset(C::mip_interface& device, } TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(offsetOut || (3 == 0)); + assert(offsetOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, offsetOut[i]); + deserializer.extract(offsetOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveMagHardIronOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult loadMagHardIronOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagHardIronOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const MagSoftIronMatrix& self) +void MagSoftIronMatrix::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.offset[i]); + serializer.insert(offset); } } -void extract(::microstrain::Serializer& serializer, MagSoftIronMatrix& self) +void MagSoftIronMatrix::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.offset[i]); + serializer.extract(offset); } } -void insert(::microstrain::Serializer& serializer, const MagSoftIronMatrix::Response& self) -{ - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.offset[i]); - -} -void extract(::microstrain::Serializer& serializer, MagSoftIronMatrix::Response& self) -{ - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.offset[i]); - -} - TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(offset || (9 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(offset); for(unsigned int i=0; i < 9; i++) - insert(serializer, offset[i]); + serializer.insert(offset[i]); assert(serializer.isOk()); @@ -3687,97 +2906,86 @@ TypedResult writeMagSoftIronMatrix(C::mip_interface& device, } TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length(), REPLY_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(offsetOut || (9 == 0)); + assert(offsetOut); for(unsigned int i=0; i < 9; i++) - extract(deserializer, offsetOut[i]); + deserializer.extract(offsetOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveMagSoftIronMatrix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); } TypedResult loadMagSoftIronMatrix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagSoftIronMatrix(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ConingScullingEnable& self) +void ConingScullingEnable::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); } } -void extract(::microstrain::Serializer& serializer, ConingScullingEnable& self) +void ConingScullingEnable::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); } } -void insert(::microstrain::Serializer& serializer, const ConingScullingEnable::Response& self) -{ - insert(serializer, self.enable); - -} -void extract(::microstrain::Serializer& serializer, ConingScullingEnable::Response& self) -{ - extract(serializer, self.enable); - -} - TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); assert(serializer.isOk()); @@ -3785,116 +2993,97 @@ TypedResult writeConingScullingEnable(C::mip_interface& de } TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length(), REPLY_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveConingScullingEnable(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); } TypedResult loadConingScullingEnable(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); } TypedResult defaultConingScullingEnable(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformEuler& self) +void Sensor2VehicleTransformEuler::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.roll); + serializer.insert(roll); - insert(serializer, self.pitch); + serializer.insert(pitch); - insert(serializer, self.yaw); + serializer.insert(yaw); } } -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformEuler& self) +void Sensor2VehicleTransformEuler::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.roll); + serializer.extract(roll); - extract(serializer, self.pitch); + serializer.extract(pitch); - extract(serializer, self.yaw); + serializer.extract(yaw); } } -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformEuler::Response& self) -{ - insert(serializer, self.roll); - - insert(serializer, self.pitch); - - insert(serializer, self.yaw); - -} -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformEuler::Response& self) -{ - extract(serializer, self.roll); - - extract(serializer, self.pitch); - - extract(serializer, self.yaw); - -} - TypedResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, roll); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(roll); - insert(serializer, pitch); + serializer.insert(pitch); - insert(serializer, yaw); + serializer.insert(yaw); assert(serializer.isOk()); @@ -3902,108 +3091,93 @@ TypedResult writeSensor2VehicleTransformEuler(C::m } TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(rollOut); - extract(deserializer, *rollOut); + deserializer.extract(*rollOut); assert(pitchOut); - extract(deserializer, *pitchOut); + deserializer.extract(*pitchOut); assert(yawOut); - extract(deserializer, *yawOut); + deserializer.extract(*yawOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSensor2VehicleTransformEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); } TypedResult loadSensor2VehicleTransformEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensor2VehicleTransformEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformQuaternion& self) +void Sensor2VehicleTransformQuaternion::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.q[i]); + serializer.insert(q); } } -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformQuaternion& self) +void Sensor2VehicleTransformQuaternion::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.q[i]); + serializer.extract(q); } } -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformQuaternion::Response& self) -{ - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.q[i]); - -} -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformQuaternion::Response& self) -{ - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.q[i]); - -} - TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(q || (4 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(q); for(unsigned int i=0; i < 4; i++) - insert(serializer, q[i]); + serializer.insert(q[i]); assert(serializer.isOk()); @@ -4011,103 +3185,88 @@ TypedResult writeSensor2VehicleTransformQuate } TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(qOut || (4 == 0)); + assert(qOut); for(unsigned int i=0; i < 4; i++) - extract(deserializer, qOut[i]); + deserializer.extract(qOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); } TypedResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformDcm& self) +void Sensor2VehicleTransformDcm::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.dcm[i]); + serializer.insert(dcm); } } -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformDcm& self) +void Sensor2VehicleTransformDcm::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.dcm[i]); + serializer.extract(dcm); } } -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformDcm::Response& self) -{ - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.dcm[i]); - -} -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformDcm::Response& self) -{ - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.dcm[i]); - -} - TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(dcm || (9 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(dcm); for(unsigned int i=0; i < 9; i++) - insert(serializer, dcm[i]); + serializer.insert(dcm[i]); assert(serializer.isOk()); @@ -4115,127 +3274,104 @@ TypedResult writeSensor2VehicleTransformDcm(C::mip_i } TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(dcmOut || (9 == 0)); + assert(dcmOut); for(unsigned int i=0; i < 9; i++) - extract(deserializer, dcmOut[i]); + deserializer.extract(dcmOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSensor2VehicleTransformDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); } TypedResult loadSensor2VehicleTransformDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensor2VehicleTransformDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ComplementaryFilter& self) +void ComplementaryFilter::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.pitch_roll_enable); + serializer.insert(pitch_roll_enable); - insert(serializer, self.heading_enable); + serializer.insert(heading_enable); - insert(serializer, self.pitch_roll_time_constant); + serializer.insert(pitch_roll_time_constant); - insert(serializer, self.heading_time_constant); + serializer.insert(heading_time_constant); } } -void extract(::microstrain::Serializer& serializer, ComplementaryFilter& self) +void ComplementaryFilter::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.pitch_roll_enable); + serializer.extract(pitch_roll_enable); - extract(serializer, self.heading_enable); + serializer.extract(heading_enable); - extract(serializer, self.pitch_roll_time_constant); + serializer.extract(pitch_roll_time_constant); - extract(serializer, self.heading_time_constant); + serializer.extract(heading_time_constant); } } -void insert(::microstrain::Serializer& serializer, const ComplementaryFilter::Response& self) -{ - insert(serializer, self.pitch_roll_enable); - - insert(serializer, self.heading_enable); - - insert(serializer, self.pitch_roll_time_constant); - - insert(serializer, self.heading_time_constant); - -} -void extract(::microstrain::Serializer& serializer, ComplementaryFilter::Response& self) -{ - extract(serializer, self.pitch_roll_enable); - - extract(serializer, self.heading_enable); - - extract(serializer, self.pitch_roll_time_constant); - - extract(serializer, self.heading_time_constant); - -} - TypedResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, pitchRollEnable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(pitchRollEnable); - insert(serializer, headingEnable); + serializer.insert(headingEnable); - insert(serializer, pitchRollTimeConstant); + serializer.insert(pitchRollTimeConstant); - insert(serializer, headingTimeConstant); + serializer.insert(headingTimeConstant); assert(serializer.isOk()); @@ -4243,115 +3379,100 @@ TypedResult writeComplementaryFilter(C::mip_interface& devi } TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length(), REPLY_LEGACY_COMP_FILTER, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(pitchRollEnableOut); - extract(deserializer, *pitchRollEnableOut); + deserializer.extract(*pitchRollEnableOut); assert(headingEnableOut); - extract(deserializer, *headingEnableOut); + deserializer.extract(*headingEnableOut); assert(pitchRollTimeConstantOut); - extract(deserializer, *pitchRollTimeConstantOut); + deserializer.extract(*pitchRollTimeConstantOut); assert(headingTimeConstantOut); - extract(deserializer, *headingTimeConstantOut); + deserializer.extract(*headingTimeConstantOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveComplementaryFilter(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult loadComplementaryFilter(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); } TypedResult defaultComplementaryFilter(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SensorRange& self) +void SensorRange::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.sensor); + serializer.insert(sensor); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.setting); + serializer.insert(setting); } } -void extract(::microstrain::Serializer& serializer, SensorRange& self) +void SensorRange::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.sensor); + serializer.extract(sensor); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.setting); + serializer.extract(setting); } } -void insert(::microstrain::Serializer& serializer, const SensorRange::Response& self) -{ - insert(serializer, self.sensor); - - insert(serializer, self.setting); - -} -void extract(::microstrain::Serializer& serializer, SensorRange::Response& self) -{ - extract(serializer, self.sensor); - - extract(serializer, self.setting); - -} - TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, sensor); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(sensor); - insert(serializer, setting); + serializer.insert(setting); assert(serializer.isOk()); @@ -4359,38 +3480,38 @@ TypedResult writeSensorRange(C::mip_interface& device, SensorRangeT } TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, sensor); + serializer.insert(FunctionSelector::READ); + serializer.insert(sensor); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length(), REPLY_SENSOR_RANGE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, sensor); + deserializer.extract(sensor); assert(settingOut); - extract(deserializer, *settingOut); + deserializer.extract(*settingOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, sensor); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(sensor); assert(serializer.isOk()); @@ -4398,11 +3519,11 @@ TypedResult saveSensorRange(C::mip_interface& device, SensorRangeTy } TypedResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, sensor); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(sensor); assert(serializer.isOk()); @@ -4410,169 +3531,107 @@ TypedResult loadSensorRange(C::mip_interface& device, SensorRangeTy } TypedResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, sensor); + serializer.insert(FunctionSelector::RESET); + serializer.insert(sensor); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges& self) -{ - insert(serializer, self.sensor); - -} -void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges& self) -{ - extract(serializer, self.sensor); - -} - -void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges::Response& self) -{ - insert(serializer, self.sensor); - - insert(serializer, self.num_ranges); - - for(unsigned int i=0; i < self.num_ranges; i++) - insert(serializer, self.ranges[i]); - -} -void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges::Response& self) -{ - extract(serializer, self.sensor); - - extract_count(serializer, &self.num_ranges, sizeof(self.ranges)/sizeof(self.ranges[0])); - for(unsigned int i=0; i < self.num_ranges; i++) - extract(serializer, self.ranges[i]); - -} - -void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges::Entry& self) +void CalibratedSensorRanges::insert(Serializer& serializer) const { - insert(serializer, self.setting); - - insert(serializer, self.range); + serializer.insert(sensor); } -void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges::Entry& self) +void CalibratedSensorRanges::extract(Serializer& serializer) { - extract(serializer, self.setting); - - extract(serializer, self.range); + serializer.extract(sensor); } TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, sensor); + serializer.insert(sensor); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CALIBRATED_RANGES, buffer, (uint8_t)serializer.length(), REPLY_CALIBRATED_RANGES, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, sensor); + deserializer.extract(sensor); - extract_count(deserializer, numRangesOut, numRangesOutMax); + deserializer.extract_count(*numRangesOut, numRangesOutMax); assert(rangesOut || (numRangesOut == 0)); for(unsigned int i=0; i < *numRangesOut; i++) - extract(deserializer, rangesOut[i]); + deserializer.extract(rangesOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const LowpassFilter& self) +void LowpassFilter::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.desc_set); + serializer.insert(desc_set); - insert(serializer, self.field_desc); + serializer.insert(field_desc); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); - insert(serializer, self.manual); + serializer.insert(manual); - insert(serializer, self.frequency); + serializer.insert(frequency); } } -void extract(::microstrain::Serializer& serializer, LowpassFilter& self) +void LowpassFilter::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.desc_set); + serializer.extract(desc_set); - extract(serializer, self.field_desc); + serializer.extract(field_desc); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); - extract(serializer, self.manual); + serializer.extract(manual); - extract(serializer, self.frequency); + serializer.extract(frequency); } } -void insert(::microstrain::Serializer& serializer, const LowpassFilter::Response& self) -{ - insert(serializer, self.desc_set); - - insert(serializer, self.field_desc); - - insert(serializer, self.enable); - - insert(serializer, self.manual); - - insert(serializer, self.frequency); - -} -void extract(::microstrain::Serializer& serializer, LowpassFilter::Response& self) -{ - extract(serializer, self.desc_set); - - extract(serializer, self.field_desc); - - extract(serializer, self.enable); - - extract(serializer, self.manual); - - extract(serializer, self.frequency); - -} - TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool enable, bool manual, float frequency) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, descSet); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(descSet); - insert(serializer, fieldDesc); + serializer.insert(fieldDesc); - insert(serializer, enable); + serializer.insert(enable); - insert(serializer, manual); + serializer.insert(manual); - insert(serializer, frequency); + serializer.insert(frequency); assert(serializer.isOk()); @@ -4580,50 +3639,50 @@ TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t } TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, descSet); + serializer.insert(FunctionSelector::READ); + serializer.insert(descSet); - insert(serializer, fieldDesc); + serializer.insert(fieldDesc); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length(), REPLY_LOWPASS_FILTER, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, descSet); + deserializer.extract(descSet); - extract(deserializer, fieldDesc); + deserializer.extract(fieldDesc); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); assert(manualOut); - extract(deserializer, *manualOut); + deserializer.extract(*manualOut); assert(frequencyOut); - extract(deserializer, *frequencyOut); + deserializer.extract(*frequencyOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, descSet); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(descSet); - insert(serializer, fieldDesc); + serializer.insert(fieldDesc); assert(serializer.isOk()); @@ -4631,13 +3690,13 @@ TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t d } TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, descSet); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(descSet); - insert(serializer, fieldDesc); + serializer.insert(fieldDesc); assert(serializer.isOk()); @@ -4645,13 +3704,13 @@ TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t d } TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, descSet); + serializer.insert(FunctionSelector::RESET); + serializer.insert(descSet); - insert(serializer, fieldDesc); + serializer.insert(fieldDesc); assert(serializer.isOk()); diff --git a/src/cpp/mip/definitions/commands_3dm.hpp b/src/cpp/mip/definitions/commands_3dm.hpp index 82c92dd48..8d8f17fa9 100644 --- a/src/cpp/mip/definitions/commands_3dm.hpp +++ b/src/cpp/mip/definitions/commands_3dm.hpp @@ -1,12 +1,12 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { namespace C { @@ -166,15 +166,17 @@ struct NmeaMessage GLONASS = 4, ///< NMEA message will be produced with talker id "GL". }; + /// Parameters MessageID message_id = static_cast(0); ///< NMEA sentence type. TalkerID talker_id = static_cast(0); ///< NMEA talker ID. Ignored for proprietary sentences. uint8_t source_desc_set = 0; ///< Data descriptor set where the data will be sourced. Available options depend on the sentence. uint16_t decimation = 0; ///< Decimation from the base rate for source_desc_set. Frequency is limited to 10 Hz or the base rate, whichever is lower. Must be 0 when polling. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const NmeaMessage& self); -void extract(::microstrain::Serializer& serializer, NmeaMessage& self); - enum class SensorRangeType : uint8_t { ALL = 0, ///< Only allowed for SAVE, LOAD, and DEFAULT function selectors. @@ -204,33 +206,35 @@ enum class SensorRangeType : uint8_t struct PollImuMessage { + /// Parameters bool suppress_ack = 0; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors = 0; ///< Number of descriptors in the descriptor list. DescriptorRate descriptors[83]; ///< Descriptor list. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_IMU_MESSAGE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PollImuMessage"; static constexpr const char* DOC_NAME = "PollImuMessage"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000030; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(suppress_ack,num_descriptors,descriptors); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(suppress_ack),std::ref(num_descriptors),std::ref(descriptors)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const PollImuMessage& self); -void extract(::microstrain::Serializer& serializer, PollImuMessage& self); - TypedResult pollImuMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); ///@} @@ -250,33 +254,35 @@ TypedResult pollImuMessage(C::mip_interface& device, bool suppre struct PollGnssMessage { + /// Parameters bool suppress_ack = 0; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors = 0; ///< Number of descriptors in the descriptor list. DescriptorRate descriptors[83]; ///< Descriptor list. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_GNSS_MESSAGE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PollGnssMessage"; static constexpr const char* DOC_NAME = "PollGnssMessage"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000030; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(suppress_ack,num_descriptors,descriptors); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(suppress_ack),std::ref(num_descriptors),std::ref(descriptors)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const PollGnssMessage& self); -void extract(::microstrain::Serializer& serializer, PollGnssMessage& self); - TypedResult pollGnssMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); ///@} @@ -296,33 +302,35 @@ TypedResult pollGnssMessage(C::mip_interface& device, bool supp struct PollFilterMessage { + /// Parameters bool suppress_ack = 0; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors = 0; ///< Number of descriptors in the format list. DescriptorRate descriptors[83]; ///< Descriptor format list. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_FILTER_MESSAGE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PollFilterMessage"; static constexpr const char* DOC_NAME = "PollFilterMessage"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000030; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(suppress_ack,num_descriptors,descriptors); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(suppress_ack),std::ref(num_descriptors),std::ref(descriptors)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const PollFilterMessage& self); -void extract(::microstrain::Serializer& serializer, PollFilterMessage& self); - TypedResult pollFilterMessage(C::mip_interface& device, bool suppressAck, uint8_t numDescriptors, const DescriptorRate* descriptors); ///@} @@ -337,31 +345,25 @@ TypedResult pollFilterMessage(C::mip_interface& device, bool struct ImuMessageFormat { + /// Parameters FunctionSelector function = static_cast(0); uint8_t num_descriptors = 0; ///< Number of descriptors DescriptorRate descriptors[82]; ///< Descriptor format list. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_IMU_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ImuMessageFormat"; static constexpr const char* DOC_NAME = "ImuMessageFormat"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(num_descriptors,descriptors); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); } @@ -373,32 +375,40 @@ struct ImuMessageFormat return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t num_descriptors = 0; ///< Number of descriptors + DescriptorRate descriptors[82]; ///< Descriptor format list. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_IMU_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ImuMessageFormat::Response"; static constexpr const char* DOC_NAME = "ImuMessageFormat Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - uint8_t num_descriptors = 0; ///< Number of descriptors - DescriptorRate descriptors[82]; ///< Descriptor format list. - + auto asTuple() const + { + return std::make_tuple(num_descriptors,descriptors); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ImuMessageFormat& self); -void extract(::microstrain::Serializer& serializer, ImuMessageFormat& self); - -void insert(::microstrain::Serializer& serializer, const ImuMessageFormat::Response& self); -void extract(::microstrain::Serializer& serializer, ImuMessageFormat::Response& self); - TypedResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); TypedResult saveImuMessageFormat(C::mip_interface& device); @@ -417,31 +427,25 @@ TypedResult defaultImuMessageFormat(C::mip_interface& device); struct GpsMessageFormat { + /// Parameters FunctionSelector function = static_cast(0); uint8_t num_descriptors = 0; ///< Number of descriptors DescriptorRate descriptors[82]; ///< Descriptor format list. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GNSS_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsMessageFormat"; static constexpr const char* DOC_NAME = "GpsMessageFormat"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(num_descriptors,descriptors); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); } @@ -453,32 +457,40 @@ struct GpsMessageFormat return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t num_descriptors = 0; ///< Number of descriptors + DescriptorRate descriptors[82]; ///< Descriptor format list. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsMessageFormat::Response"; static constexpr const char* DOC_NAME = "GpsMessageFormat Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - uint8_t num_descriptors = 0; ///< Number of descriptors - DescriptorRate descriptors[82]; ///< Descriptor format list. - + auto asTuple() const + { + return std::make_tuple(num_descriptors,descriptors); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GpsMessageFormat& self); -void extract(::microstrain::Serializer& serializer, GpsMessageFormat& self); - -void insert(::microstrain::Serializer& serializer, const GpsMessageFormat::Response& self); -void extract(::microstrain::Serializer& serializer, GpsMessageFormat::Response& self); - TypedResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); TypedResult saveGpsMessageFormat(C::mip_interface& device); @@ -497,31 +509,25 @@ TypedResult defaultGpsMessageFormat(C::mip_interface& device); struct FilterMessageFormat { + /// Parameters FunctionSelector function = static_cast(0); uint8_t num_descriptors = 0; ///< Number of descriptors (limited by payload size) DescriptorRate descriptors[82]; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_FILTER_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "FilterMessageFormat"; static constexpr const char* DOC_NAME = "FilterMessageFormat"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - auto as_tuple() const + auto asTuple() const { - return std::make_tuple(num_descriptors, descriptors); + return std::make_tuple(num_descriptors,descriptors); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); } @@ -533,34 +539,40 @@ struct FilterMessageFormat return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t num_descriptors = 0; ///< Number of descriptors (limited by payload size) + DescriptorRate descriptors[82]; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_FILTER_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "FilterMessageFormat::Response"; static constexpr const char* DOC_NAME = "FilterMessageFormat Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - uint8_t num_descriptors = 0; ///< Number of descriptors (limited by payload size) - DescriptorRate descriptors[82]; - //Counter num_descriptors = 0; - //Array descriptors; - + auto asTuple() const + { + return std::make_tuple(num_descriptors,descriptors); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(num_descriptors),std::ref(descriptors)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const FilterMessageFormat& self); -void extract(::microstrain::Serializer& serializer, FilterMessageFormat& self); - -void insert(::microstrain::Serializer& serializer, const FilterMessageFormat::Response& self); -void extract(::microstrain::Serializer& serializer, FilterMessageFormat::Response& self); - TypedResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); TypedResult saveFilterMessageFormat(C::mip_interface& device); @@ -580,51 +592,57 @@ TypedResult defaultFilterMessageFormat(C::mip_interface& de struct ImuGetBaseRate { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GET_IMU_BASE_RATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ImuGetBaseRate"; static constexpr const char* DOC_NAME = "Get IMU Data Base Rate"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint16_t rate = 0; ///< [hz] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_IMU_BASE_RATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ImuGetBaseRate::Response"; static constexpr const char* DOC_NAME = "Get IMU Data Base Rate Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint16_t rate = 0; ///< [hz] - + auto asTuple() const + { + return std::make_tuple(rate); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(rate)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ImuGetBaseRate& self); -void extract(::microstrain::Serializer& serializer, ImuGetBaseRate& self); - -void insert(::microstrain::Serializer& serializer, const ImuGetBaseRate::Response& self); -void extract(::microstrain::Serializer& serializer, ImuGetBaseRate::Response& self); - TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut); ///@} @@ -640,51 +658,57 @@ TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* r struct GpsGetBaseRate { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GET_GNSS_BASE_RATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsGetBaseRate"; static constexpr const char* DOC_NAME = "Get GNSS Data Base Rate"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint16_t rate = 0; ///< [hz] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_BASE_RATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsGetBaseRate::Response"; static constexpr const char* DOC_NAME = "Get GNSS Data Base Rate Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint16_t rate = 0; ///< [hz] - + auto asTuple() const + { + return std::make_tuple(rate); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(rate)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GpsGetBaseRate& self); -void extract(::microstrain::Serializer& serializer, GpsGetBaseRate& self); - -void insert(::microstrain::Serializer& serializer, const GpsGetBaseRate::Response& self); -void extract(::microstrain::Serializer& serializer, GpsGetBaseRate::Response& self); - TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut); ///@} @@ -700,51 +724,57 @@ TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* r struct FilterGetBaseRate { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GET_FILTER_BASE_RATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "FilterGetBaseRate"; static constexpr const char* DOC_NAME = "Get Estimation Filter Data Base Rate"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint16_t rate = 0; ///< [hz] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_FILTER_BASE_RATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "FilterGetBaseRate::Response"; static constexpr const char* DOC_NAME = "Get Estimation Filter Data Base Rate Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint16_t rate = 0; ///< [hz] - + auto asTuple() const + { + return std::make_tuple(rate); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(rate)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const FilterGetBaseRate& self); -void extract(::microstrain::Serializer& serializer, FilterGetBaseRate& self); - -void insert(::microstrain::Serializer& serializer, const FilterGetBaseRate::Response& self); -void extract(::microstrain::Serializer& serializer, FilterGetBaseRate::Response& self); - TypedResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut); ///@} @@ -764,34 +794,36 @@ TypedResult filterGetBaseRate(C::mip_interface& device, uint1 struct PollData { + /// Parameters uint8_t desc_set = 0; ///< Data descriptor set. Must be supported. bool suppress_ack = 0; ///< Suppress the usual ACK/NACK reply. uint8_t num_descriptors = 0; ///< Number of descriptors in the format list. uint8_t descriptors[82] = {0}; ///< Descriptor format list. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_DATA; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PollData"; static constexpr const char* DOC_NAME = "PollData"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x000000C0; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(desc_set,suppress_ack,num_descriptors,descriptors); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(desc_set),std::ref(suppress_ack),std::ref(num_descriptors),std::ref(descriptors)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const PollData& self); -void extract(::microstrain::Serializer& serializer, PollData& self); - TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool suppressAck, uint8_t numDescriptors, const uint8_t* descriptors); ///@} @@ -804,53 +836,61 @@ TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool s struct GetBaseRate { + /// Parameters uint8_t desc_set = 0; ///< This is the data descriptor set. It must be a supported descriptor. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GET_BASE_RATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetBaseRate"; static constexpr const char* DOC_NAME = "Get Data Base Rate"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(desc_set); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(desc_set)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t desc_set = 0; ///< Echoes the parameter in the command. + uint16_t rate = 0; ///< Base rate in Hz (0 = variable, unknown, or user-defined rate. Data will be sent when received). + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_BASE_RATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetBaseRate::Response"; static constexpr const char* DOC_NAME = "Get Data Base Rate Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t desc_set = 0; ///< Echoes the parameter in the command. - uint16_t rate = 0; ///< Base rate in Hz (0 = variable, unknown, or user-defined rate. Data will be sent when received). - + auto asTuple() const + { + return std::make_tuple(desc_set,rate); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(desc_set),std::ref(rate)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetBaseRate& self); -void extract(::microstrain::Serializer& serializer, GetBaseRate& self); - -void insert(::microstrain::Serializer& serializer, const GetBaseRate::Response& self); -void extract(::microstrain::Serializer& serializer, GetBaseRate::Response& self); - TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut); ///@} @@ -865,32 +905,26 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, struct MessageFormat { + /// Parameters FunctionSelector function = static_cast(0); uint8_t desc_set = 0; ///< Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets. uint8_t num_descriptors = 0; ///< Number of descriptors (limited by payload size) DescriptorRate descriptors[82]; ///< List of descriptors and decimations. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MessageFormat"; static constexpr const char* DOC_NAME = "MessageFormat"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8007; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000030; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(desc_set,num_descriptors,descriptors); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(desc_set),std::ref(num_descriptors),std::ref(descriptors)); } @@ -903,33 +937,41 @@ struct MessageFormat return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t desc_set = 0; ///< Echoes the descriptor set from the command. + uint8_t num_descriptors = 0; ///< Number of descriptors in the list. + DescriptorRate descriptors[82]; ///< List of descriptors and decimations. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MessageFormat::Response"; static constexpr const char* DOC_NAME = "MessageFormat Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000030; - uint8_t desc_set = 0; ///< Echoes the descriptor set from the command. - uint8_t num_descriptors = 0; ///< Number of descriptors in the list. - DescriptorRate descriptors[82]; ///< List of descriptors and decimations. - + auto asTuple() const + { + return std::make_tuple(desc_set,num_descriptors,descriptors); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(desc_set),std::ref(num_descriptors),std::ref(descriptors)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const MessageFormat& self); -void extract(::microstrain::Serializer& serializer, MessageFormat& self); - -void insert(::microstrain::Serializer& serializer, const MessageFormat::Response& self); -void extract(::microstrain::Serializer& serializer, MessageFormat::Response& self); - TypedResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors); TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut); TypedResult saveMessageFormat(C::mip_interface& device, uint8_t descSet); @@ -952,33 +994,35 @@ TypedResult defaultMessageFormat(C::mip_interface& device, uint8_ struct NmeaPollData { + /// Parameters bool suppress_ack = 0; ///< Suppress the usual ACK/NACK reply. uint8_t count = 0; ///< Number of format entries (limited by payload size) NmeaMessage format_entries[40]; ///< List of format entries. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_POLL_NMEA_MESSAGE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "NmeaPollData"; static constexpr const char* DOC_NAME = "NmeaPollData"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000030; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(suppress_ack,count,format_entries); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(suppress_ack),std::ref(count),std::ref(format_entries)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const NmeaPollData& self); -void extract(::microstrain::Serializer& serializer, NmeaPollData& self); - TypedResult nmeaPollData(C::mip_interface& device, bool suppressAck, uint8_t count, const NmeaMessage* formatEntries); ///@} @@ -991,31 +1035,25 @@ TypedResult nmeaPollData(C::mip_interface& device, bool suppressAc struct NmeaMessageFormat { + /// Parameters FunctionSelector function = static_cast(0); uint8_t count = 0; ///< Number of format entries (limited by payload size) NmeaMessage format_entries[40]; ///< List of format entries. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_NMEA_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "NmeaMessageFormat"; static constexpr const char* DOC_NAME = "NmeaMessageFormat"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(count,format_entries); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(count),std::ref(format_entries)); } @@ -1027,32 +1065,40 @@ struct NmeaMessageFormat return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t count = 0; ///< Number of format entries (limited by payload size) + NmeaMessage format_entries[40]; ///< List of format entries. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_NMEA_MESSAGE_FORMAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "NmeaMessageFormat::Response"; static constexpr const char* DOC_NAME = "NmeaMessageFormat Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - uint8_t count = 0; ///< Number of format entries (limited by payload size) - NmeaMessage format_entries[40]; ///< List of format entries. - + auto asTuple() const + { + return std::make_tuple(count,format_entries); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(count),std::ref(format_entries)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const NmeaMessageFormat& self); -void extract(::microstrain::Serializer& serializer, NmeaMessageFormat& self); - -void insert(::microstrain::Serializer& serializer, const NmeaMessageFormat::Response& self); -void extract(::microstrain::Serializer& serializer, NmeaMessageFormat::Response& self); - TypedResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries); TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut); TypedResult saveNmeaMessageFormat(C::mip_interface& device); @@ -1073,28 +1119,23 @@ TypedResult defaultNmeaMessageFormat(C::mip_interface& device struct DeviceSettings { + /// Parameters FunctionSelector function = static_cast(0); + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_DEVICE_STARTUP_SETTINGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DeviceSettings"; static constexpr const char* DOC_NAME = "DeviceSettings"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x0000; - static constexpr const uint32_t READ_PARAMS = 0x0000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } @@ -1106,11 +1147,12 @@ struct DeviceSettings return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const DeviceSettings& self); -void extract(::microstrain::Serializer& serializer, DeviceSettings& self); - TypedResult saveDeviceSettings(C::mip_interface& device); TypedResult loadDeviceSettings(C::mip_interface& device); TypedResult defaultDeviceSettings(C::mip_interface& device); @@ -1139,30 +1181,24 @@ TypedResult defaultDeviceSettings(C::mip_interface& device); struct UartBaudrate { + /// Parameters FunctionSelector function = static_cast(0); uint32_t baud = 0; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_UART_BAUDRATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "UartBaudrate"; static constexpr const char* DOC_NAME = "UartBaudrate"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(baud); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(baud)); } @@ -1174,31 +1210,39 @@ struct UartBaudrate return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint32_t baud = 0; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_UART_BAUDRATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "UartBaudrate::Response"; static constexpr const char* DOC_NAME = "UartBaudrate Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint32_t baud = 0; - + auto asTuple() const + { + return std::make_tuple(baud); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(baud)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const UartBaudrate& self); -void extract(::microstrain::Serializer& serializer, UartBaudrate& self); - -void insert(::microstrain::Serializer& serializer, const UartBaudrate::Response& self); -void extract(::microstrain::Serializer& serializer, UartBaudrate::Response& self); - TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud); TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut); TypedResult saveUartBaudrate(C::mip_interface& device); @@ -1225,32 +1269,34 @@ struct FactoryStreaming ADD = 2, ///< Adds descriptors to the current message format(s) without changing existing descriptors. May result in duplicates. }; + /// Parameters Action action = static_cast(0); uint8_t reserved = 0; ///< Reserved. Set to 0x00. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_CONFIGURE_FACTORY_STREAMING; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "FactoryStreaming"; static constexpr const char* DOC_NAME = "FactoryStreaming"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(action,reserved); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(action),std::ref(reserved)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const FactoryStreaming& self); -void extract(::microstrain::Serializer& serializer, FactoryStreaming& self); - TypedResult factoryStreaming(C::mip_interface& device, FactoryStreaming::Action action, uint8_t reserved); ///@} @@ -1272,31 +1318,25 @@ struct DatastreamControl static constexpr const uint8_t LEGACY_GNSS_STREAM = 0x02; static constexpr const uint8_t LEGACY_FILTER_STREAM = 0x03; static constexpr const uint8_t ALL_STREAMS = 0x00; + /// Parameters FunctionSelector function = static_cast(0); uint8_t desc_set = 0; ///< The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets. On Generation 5 products, this must be one of the above legacy constants. bool enable = 0; ///< True or false to enable or disable the stream. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_CONTROL_DATA_STREAM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DatastreamControl"; static constexpr const char* DOC_NAME = "DatastreamControl"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(desc_set,enable); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(desc_set),std::ref(enable)); } @@ -1309,32 +1349,40 @@ struct DatastreamControl return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t desc_set = 0; + bool enabled = 0; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_DATASTREAM_ENABLE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DatastreamControl::Response"; static constexpr const char* DOC_NAME = "DatastreamControl Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t desc_set = 0; - bool enabled = 0; - + auto asTuple() const + { + return std::make_tuple(desc_set,enabled); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(desc_set),std::ref(enabled)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const DatastreamControl& self); -void extract(::microstrain::Serializer& serializer, DatastreamControl& self); - -void insert(::microstrain::Serializer& serializer, const DatastreamControl::Response& self); -void extract(::microstrain::Serializer& serializer, DatastreamControl::Response& self); - TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable); TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut); TypedResult saveDatastreamControl(C::mip_interface& device, uint8_t descSet); @@ -1380,6 +1428,7 @@ struct ConstellationSettings struct OptionFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1396,48 +1445,43 @@ struct ConstellationSettings OptionFlags& operator|=(uint16_t val) { return *this = value | val; } OptionFlags& operator&=(uint16_t val) { return *this = value & val; } - bool l1saif() const { return (value & L1SAIF) > 0; } - void l1saif(bool val) { if(val) value |= L1SAIF; else value &= ~L1SAIF; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - struct Settings { + /// Parameters ConstellationId constellation_id = static_cast(0); ///< Constellation ID uint8_t enable = 0; ///< Enable/Disable constellation uint8_t reserved_channels = 0; ///< Minimum number of channels reserved for this constellation uint8_t max_channels = 0; ///< Maximum number of channels to use for this constallation OptionFlags option_flags; ///< Constellation option Flags + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; + /// Parameters FunctionSelector function = static_cast(0); uint16_t max_channels = 0; uint8_t config_count = 0; Settings settings[42]; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GNSS_CONSTELLATION_SETTINGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ConstellationSettings"; static constexpr const char* DOC_NAME = "ConstellationSettings"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8007; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000030; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(max_channels,config_count,settings); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(max_channels),std::ref(config_count),std::ref(settings)); } @@ -1449,37 +1493,42 @@ struct ConstellationSettings return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint16_t max_channels_available = 0; ///< Maximum channels available + uint16_t max_channels_use = 0; ///< Maximum channels to use + uint8_t config_count = 0; ///< Number of constellation configurations + Settings settings[42]; ///< Constellation Settings + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_CONSTELLATION_SETTINGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ConstellationSettings::Response"; static constexpr const char* DOC_NAME = "ConstellationSettings Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x000000C0; - uint16_t max_channels_available = 0; ///< Maximum channels available - uint16_t max_channels_use = 0; ///< Maximum channels to use - uint8_t config_count = 0; ///< Number of constellation configurations - Settings settings[42]; ///< Constellation Settings - + auto asTuple() const + { + return std::make_tuple(max_channels_available,max_channels_use,config_count,settings); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(max_channels_available),std::ref(max_channels_use),std::ref(config_count),std::ref(settings)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ConstellationSettings& self); -void extract(::microstrain::Serializer& serializer, ConstellationSettings& self); - -void insert(::microstrain::Serializer& serializer, const ConstellationSettings::Settings& self); -void extract(::microstrain::Serializer& serializer, ConstellationSettings::Settings& self); - -void insert(::microstrain::Serializer& serializer, const ConstellationSettings::Response& self); -void extract(::microstrain::Serializer& serializer, ConstellationSettings::Response& self); - TypedResult writeConstellationSettings(C::mip_interface& device, uint16_t maxChannels, uint8_t configCount, const ConstellationSettings::Settings* settings); TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut); TypedResult saveConstellationSettings(C::mip_interface& device); @@ -1501,6 +1550,7 @@ struct GnssSbasSettings { struct SBASOptions : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1519,44 +1569,30 @@ struct GnssSbasSettings SBASOptions& operator|=(uint16_t val) { return *this = value | val; } SBASOptions& operator&=(uint16_t val) { return *this = value & val; } - bool enableRanging() const { return (value & ENABLE_RANGING) > 0; } - void enableRanging(bool val) { if(val) value |= ENABLE_RANGING; else value &= ~ENABLE_RANGING; } - bool enableCorrections() const { return (value & ENABLE_CORRECTIONS) > 0; } - void enableCorrections(bool val) { if(val) value |= ENABLE_CORRECTIONS; else value &= ~ENABLE_CORRECTIONS; } - bool applyIntegrity() const { return (value & APPLY_INTEGRITY) > 0; } - void applyIntegrity(bool val) { if(val) value |= APPLY_INTEGRITY; else value &= ~APPLY_INTEGRITY; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters FunctionSelector function = static_cast(0); uint8_t enable_sbas = 0; ///< 0 - SBAS Disabled, 1 - SBAS enabled SBASOptions sbas_options; ///< SBAS options, see definition uint8_t num_included_prns = 0; ///< Number of SBAS PRNs to include in search (0 = include all) uint16_t included_prns[39] = {0}; ///< List of specific SBAS PRNs to search for + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GNSS_SBAS_SETTINGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssSbasSettings"; static constexpr const char* DOC_NAME = "SBAS Settings"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x800F; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x000000C0; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable_sbas,sbas_options,num_included_prns,included_prns); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable_sbas),std::ref(sbas_options),std::ref(num_included_prns),std::ref(included_prns)); } @@ -1568,34 +1604,42 @@ struct GnssSbasSettings return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t enable_sbas = 0; ///< 0 - SBAS Disabled, 1 - SBAS enabled + SBASOptions sbas_options; ///< SBAS options, see definition + uint8_t num_included_prns = 0; ///< Number of SBAS PRNs to include in search (0 = include all) + uint16_t included_prns[39] = {0}; ///< List of specific SBAS PRNs to search for + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_SBAS_SETTINGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssSbasSettings::Response"; static constexpr const char* DOC_NAME = "SBAS Settings Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x000000C0; - uint8_t enable_sbas = 0; ///< 0 - SBAS Disabled, 1 - SBAS enabled - SBASOptions sbas_options; ///< SBAS options, see definition - uint8_t num_included_prns = 0; ///< Number of SBAS PRNs to include in search (0 = include all) - uint16_t included_prns[39] = {0}; ///< List of specific SBAS PRNs to search for - + auto asTuple() const + { + return std::make_tuple(enable_sbas,sbas_options,num_included_prns,included_prns); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable_sbas),std::ref(sbas_options),std::ref(num_included_prns),std::ref(included_prns)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GnssSbasSettings& self); -void extract(::microstrain::Serializer& serializer, GnssSbasSettings& self); - -void insert(::microstrain::Serializer& serializer, const GnssSbasSettings::Response& self); -void extract(::microstrain::Serializer& serializer, GnssSbasSettings::Response& self); - TypedResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns); TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut); TypedResult saveGnssSbasSettings(C::mip_interface& device); @@ -1628,31 +1672,25 @@ struct GnssAssistedFix ENABLED = 1, ///< Enable assisted fix }; + /// Parameters FunctionSelector function = static_cast(0); AssistedFixOption option = static_cast(0); ///< Assisted fix options uint8_t flags = 0; ///< Assisted fix flags (set to 0xFF) + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GNSS_ASSISTED_FIX_SETTINGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssAssistedFix"; static constexpr const char* DOC_NAME = "GNSS Assisted Fix Settings"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(option,flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(option),std::ref(flags)); } @@ -1664,32 +1702,40 @@ struct GnssAssistedFix return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + AssistedFixOption option = static_cast(0); ///< Assisted fix options + uint8_t flags = 0; ///< Assisted fix flags (set to 0xFF) + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_ASSISTED_FIX_SETTINGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssAssistedFix::Response"; static constexpr const char* DOC_NAME = "GNSS Assisted Fix Settings Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - AssistedFixOption option = static_cast(0); ///< Assisted fix options - uint8_t flags = 0; ///< Assisted fix flags (set to 0xFF) - + auto asTuple() const + { + return std::make_tuple(option,flags); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(option),std::ref(flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GnssAssistedFix& self); -void extract(::microstrain::Serializer& serializer, GnssAssistedFix& self); - -void insert(::microstrain::Serializer& serializer, const GnssAssistedFix::Response& self); -void extract(::microstrain::Serializer& serializer, GnssAssistedFix::Response& self); - TypedResult writeGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption option, uint8_t flags); TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut); TypedResult saveGnssAssistedFix(C::mip_interface& device); @@ -1709,32 +1755,26 @@ TypedResult defaultGnssAssistedFix(C::mip_interface& device); struct GnssTimeAssistance { + /// Parameters FunctionSelector function = static_cast(0); double tow = 0; ///< GPS Time of week [seconds] uint16_t week_number = 0; ///< GPS Weeks since 1980 [weeks] float accuracy = 0; ///< Accuracy of time information [seconds] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GNSS_TIME_ASSISTANCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssTimeAssistance"; static constexpr const char* DOC_NAME = "GnssTimeAssistance"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8007; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x0000; - static constexpr const uint32_t LOAD_PARAMS = 0x0000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x0000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(tow,week_number,accuracy); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(accuracy)); } @@ -1746,33 +1786,41 @@ struct GnssTimeAssistance return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + double tow = 0; ///< GPS Time of week [seconds] + uint16_t week_number = 0; ///< GPS Weeks since 1980 [weeks] + float accuracy = 0; ///< Accuracy of time information [seconds] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GNSS_TIME_ASSISTANCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssTimeAssistance::Response"; static constexpr const char* DOC_NAME = "GnssTimeAssistance Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - double tow = 0; ///< GPS Time of week [seconds] - uint16_t week_number = 0; ///< GPS Weeks since 1980 [weeks] - float accuracy = 0; ///< Accuracy of time information [seconds] - + auto asTuple() const + { + return std::make_tuple(tow,week_number,accuracy); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(accuracy)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GnssTimeAssistance& self); -void extract(::microstrain::Serializer& serializer, GnssTimeAssistance& self); - -void insert(::microstrain::Serializer& serializer, const GnssTimeAssistance::Response& self); -void extract(::microstrain::Serializer& serializer, GnssTimeAssistance::Response& self); - TypedResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy); TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut); @@ -1801,6 +1849,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, struct ImuLowpassFilter { + /// Parameters FunctionSelector function = static_cast(0); uint8_t target_descriptor = 0; ///< Field descriptor of filtered quantity within the Sensor data set. Supported values are accel (0x04), gyro (0x05), mag (0x06), and pressure (0x17), provided the data is supported by the device. Except with the READ function selector, this can be 0 to apply to all of the above quantities. bool enable = 0; ///< The target data will be filtered if this is true. @@ -1808,27 +1857,20 @@ struct ImuLowpassFilter uint16_t frequency = 0; ///< -3dB cutoff frequency in Hz. Will not affect filtering if 'manual' is false. uint8_t reserved = 0; ///< Reserved, set to 0x00. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_IMU_LOWPASS_FILTER; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ImuLowpassFilter"; static constexpr const char* DOC_NAME = "Advanced Low-Pass Filter Settings"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x801F; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(target_descriptor,enable,manual,frequency,reserved); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(target_descriptor),std::ref(enable),std::ref(manual),std::ref(frequency),std::ref(reserved)); } @@ -1841,35 +1883,43 @@ struct ImuLowpassFilter return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { - static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_ADVANCED_DATA_FILTER; - static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "ImuLowpassFilter::Response"; - static constexpr const char* DOC_NAME = "Advanced Low-Pass Filter Settings Response"; - - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + /// Parameters uint8_t target_descriptor = 0; bool enable = 0; ///< True if the filter is currently enabled. bool manual = 0; ///< True if the filter cutoff was manually configured. uint16_t frequency = 0; ///< The cutoff frequency of the filter. If the filter is in auto mode, this value is unspecified. uint8_t reserved = 0; ///< Reserved and must be ignored. + /// Descriptors + static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_ADVANCED_DATA_FILTER; + static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "ImuLowpassFilter::Response"; + static constexpr const char* DOC_NAME = "Advanced Low-Pass Filter Settings Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + + auto asTuple() const + { + return std::make_tuple(target_descriptor,enable,manual,frequency,reserved); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(target_descriptor),std::ref(enable),std::ref(manual),std::ref(frequency),std::ref(reserved)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ImuLowpassFilter& self); -void extract(::microstrain::Serializer& serializer, ImuLowpassFilter& self); - -void insert(::microstrain::Serializer& serializer, const ImuLowpassFilter::Response& self); -void extract(::microstrain::Serializer& serializer, ImuLowpassFilter::Response& self); - TypedResult writeImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved); TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut); TypedResult saveImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor); @@ -1895,30 +1945,24 @@ struct PpsSource GENERATED = 4, ///< PPS is generated from the system oscillator. }; + /// Parameters FunctionSelector function = static_cast(0); Source source = static_cast(0); + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_PPS_SOURCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PpsSource"; static constexpr const char* DOC_NAME = "PpsSource"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source)); } @@ -1930,31 +1974,39 @@ struct PpsSource return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Source source = static_cast(0); + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_PPS_SOURCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PpsSource::Response"; static constexpr const char* DOC_NAME = "PpsSource Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Source source = static_cast(0); - + auto asTuple() const + { + return std::make_tuple(source); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const PpsSource& self); -void extract(::microstrain::Serializer& serializer, PpsSource& self); - -void insert(::microstrain::Serializer& serializer, const PpsSource::Response& self); -void extract(::microstrain::Serializer& serializer, PpsSource::Response& self); - TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source); TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut); TypedResult savePpsSource(C::mip_interface& device); @@ -2018,6 +2070,7 @@ struct GpioConfig struct PinMode : Bitfield { + typedef uint8_t Type; enum _enumType : uint8_t { NONE = 0x00, @@ -2036,44 +2089,30 @@ struct GpioConfig PinMode& operator|=(uint8_t val) { return *this = value | val; } PinMode& operator&=(uint8_t val) { return *this = value & val; } - bool openDrain() const { return (value & OPEN_DRAIN) > 0; } - void openDrain(bool val) { if(val) value |= OPEN_DRAIN; else value &= ~OPEN_DRAIN; } - bool pulldown() const { return (value & PULLDOWN) > 0; } - void pulldown(bool val) { if(val) value |= PULLDOWN; else value &= ~PULLDOWN; } - bool pullup() const { return (value & PULLUP) > 0; } - void pullup(bool val) { if(val) value |= PULLUP; else value &= ~PULLUP; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters FunctionSelector function = static_cast(0); uint8_t pin = 0; ///< GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins. Feature feature = static_cast(0); ///< Determines how the pin will be used. Behavior behavior = static_cast(0); ///< Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.) PinMode pin_mode; ///< GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GPIO_CONFIG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpioConfig"; static constexpr const char* DOC_NAME = "GPIO Configuration"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x800F; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(pin,feature,behavior,pin_mode); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(pin),std::ref(feature),std::ref(behavior),std::ref(pin_mode)); } @@ -2086,34 +2125,42 @@ struct GpioConfig return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t pin = 0; ///< GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins. + Feature feature = static_cast(0); ///< Determines how the pin will be used. + Behavior behavior = static_cast(0); ///< Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.) + PinMode pin_mode; ///< GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GPIO_CONFIG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpioConfig::Response"; static constexpr const char* DOC_NAME = "GPIO Configuration Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t pin = 0; ///< GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins. - Feature feature = static_cast(0); ///< Determines how the pin will be used. - Behavior behavior = static_cast(0); ///< Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.) - PinMode pin_mode; ///< GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual. - + auto asTuple() const + { + return std::make_tuple(pin,feature,behavior,pin_mode); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(pin),std::ref(feature),std::ref(behavior),std::ref(pin_mode)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GpioConfig& self); -void extract(::microstrain::Serializer& serializer, GpioConfig& self); - -void insert(::microstrain::Serializer& serializer, const GpioConfig::Response& self); -void extract(::microstrain::Serializer& serializer, GpioConfig::Response& self); - TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode); TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut); TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin); @@ -2145,31 +2192,25 @@ TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) struct GpioState { + /// Parameters FunctionSelector function = static_cast(0); uint8_t pin = 0; ///< GPIO pin number counting from 1. Cannot be 0. bool state = 0; ///< The pin state. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GPIO_STATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpioState"; static constexpr const char* DOC_NAME = "GPIO State"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x0000; - static constexpr const uint32_t LOAD_PARAMS = 0x0000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x0000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(pin,state); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(pin),std::ref(state)); } @@ -2181,32 +2222,40 @@ struct GpioState return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t pin = 0; ///< GPIO pin number counting from 1. Cannot be 0. + bool state = 0; ///< The pin state. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GPIO_STATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpioState::Response"; static constexpr const char* DOC_NAME = "GPIO State Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t pin = 0; ///< GPIO pin number counting from 1. Cannot be 0. - bool state = 0; ///< The pin state. - + auto asTuple() const + { + return std::make_tuple(pin,state); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(pin),std::ref(state)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GpioState& self); -void extract(::microstrain::Serializer& serializer, GpioState& self); - -void insert(::microstrain::Serializer& serializer, const GpioState::Response& self); -void extract(::microstrain::Serializer& serializer, GpioState::Response& self); - TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state); TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut); @@ -2227,32 +2276,26 @@ struct Odometer QUADRATURE = 2, ///< Quadrature encoder mode. }; + /// Parameters FunctionSelector function = static_cast(0); Mode mode = static_cast(0); ///< Mode setting. float scaling = 0; ///< Encoder pulses per meter of distance traveled [pulses/m]. Distance traveled is computed using the formula d = p / N * 2R * pi, where d is distance, p is the number of pulses received, N is the encoder resolution, and R is the wheel radius. By simplifying all of the parameters into one, the formula d = p / S is obtained, where s is the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and has units of pulses / meter. N is in units of "A" pulses per revolution and R is in meters. Make this value negative if the odometer is mounted so that it rotates backwards. float uncertainty = 0; ///< Uncertainty in encoder counts to distance translation (1-sigma value) [m/m]. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_ODOMETER_CONFIG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Odometer"; static constexpr const char* DOC_NAME = "Odometer Settings"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8007; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(mode,scaling,uncertainty); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(mode),std::ref(scaling),std::ref(uncertainty)); } @@ -2264,33 +2307,41 @@ struct Odometer return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Mode mode = static_cast(0); ///< Mode setting. + float scaling = 0; ///< Encoder pulses per meter of distance traveled [pulses/m]. Distance traveled is computed using the formula d = p / N * 2R * pi, where d is distance, p is the number of pulses received, N is the encoder resolution, and R is the wheel radius. By simplifying all of the parameters into one, the formula d = p / S is obtained, where s is the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and has units of pulses / meter. N is in units of "A" pulses per revolution and R is in meters. Make this value negative if the odometer is mounted so that it rotates backwards. + float uncertainty = 0; ///< Uncertainty in encoder counts to distance translation (1-sigma value) [m/m]. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_ODOMETER_CONFIG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Odometer::Response"; static constexpr const char* DOC_NAME = "Odometer Settings Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Mode mode = static_cast(0); ///< Mode setting. - float scaling = 0; ///< Encoder pulses per meter of distance traveled [pulses/m]. Distance traveled is computed using the formula d = p / N * 2R * pi, where d is distance, p is the number of pulses received, N is the encoder resolution, and R is the wheel radius. By simplifying all of the parameters into one, the formula d = p / S is obtained, where s is the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and has units of pulses / meter. N is in units of "A" pulses per revolution and R is in meters. Make this value negative if the odometer is mounted so that it rotates backwards. - float uncertainty = 0; ///< Uncertainty in encoder counts to distance translation (1-sigma value) [m/m]. - + auto asTuple() const + { + return std::make_tuple(mode,scaling,uncertainty); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(mode),std::ref(scaling),std::ref(uncertainty)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const Odometer& self); -void extract(::microstrain::Serializer& serializer, Odometer& self); - -void insert(::microstrain::Serializer& serializer, const Odometer::Response& self); -void extract(::microstrain::Serializer& serializer, Odometer::Response& self); - TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty); TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut); TypedResult saveOdometer(C::mip_interface& device); @@ -2331,62 +2382,72 @@ struct GetEventSupport struct Info { + /// Parameters uint8_t type = 0; ///< Trigger or action type, as defined in the respective setup command. uint8_t count = 0; ///< This is the maximum number of instances supported for this type. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; + /// Parameters Query query = static_cast(0); ///< What type of information to retrieve. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_SUPPORT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetEventSupport"; static constexpr const char* DOC_NAME = "Get Supported Events"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(query); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(query)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Query query = static_cast(0); ///< Query type specified in the command. + uint8_t max_instances = 0; ///< Number of slots available. The 'instance' number for the configuration or control commands must be between 1 and this value. + uint8_t num_entries = 0; ///< Number of supported types. + Info entries[126]; ///< List of supported types. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_SUPPORT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetEventSupport::Response"; static constexpr const char* DOC_NAME = "Get Supported Events Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x000000C0; - Query query = static_cast(0); ///< Query type specified in the command. - uint8_t max_instances = 0; ///< Number of slots available. The 'instance' number for the configuration or control commands must be between 1 and this value. - uint8_t num_entries = 0; ///< Number of supported types. - Info entries[126]; ///< List of supported types. - + auto asTuple() const + { + return std::make_tuple(query,max_instances,num_entries,entries); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(query),std::ref(max_instances),std::ref(num_entries),std::ref(entries)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetEventSupport& self); -void extract(::microstrain::Serializer& serializer, GetEventSupport& self); - -void insert(::microstrain::Serializer& serializer, const GetEventSupport::Info& self); -void extract(::microstrain::Serializer& serializer, GetEventSupport::Info& self); - -void insert(::microstrain::Serializer& serializer, const GetEventSupport::Response& self); -void extract(::microstrain::Serializer& serializer, GetEventSupport::Response& self); - TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut); ///@} @@ -2416,31 +2477,25 @@ struct EventControl TEST_PULSE = 3, ///< Trigger is forced to the active state for one event cycle only. After the test cycle, the mode reverts to the previous state (either enabled or disabled). }; + /// Parameters FunctionSelector function = static_cast(0); uint8_t instance = 0; ///< Trigger instance to affect. 0 can be used to apply the mode to all configured triggers, except when the function selector is READ. Mode mode = static_cast(0); ///< How to change the trigger state. Except when instance is 0, the corresponding trigger must be configured, i.e. not have type 0. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EventControl"; static constexpr const char* DOC_NAME = "Event Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(instance,mode); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(instance),std::ref(mode)); } @@ -2453,32 +2508,40 @@ struct EventControl return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t instance = 0; ///< Trigger instance to affect. 0 can be used to apply the mode to all configured triggers, except when the function selector is READ. + Mode mode = static_cast(0); ///< How to change the trigger state. Except when instance is 0, the corresponding trigger must be configured, i.e. not have type 0. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EventControl::Response"; static constexpr const char* DOC_NAME = "Event Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t instance = 0; ///< Trigger instance to affect. 0 can be used to apply the mode to all configured triggers, except when the function selector is READ. - Mode mode = static_cast(0); ///< How to change the trigger state. Except when instance is 0, the corresponding trigger must be configured, i.e. not have type 0. - + auto asTuple() const + { + return std::make_tuple(instance,mode); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(instance),std::ref(mode)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const EventControl& self); -void extract(::microstrain::Serializer& serializer, EventControl& self); - -void insert(::microstrain::Serializer& serializer, const EventControl::Response& self); -void extract(::microstrain::Serializer& serializer, EventControl::Response& self); - TypedResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode); TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut); TypedResult saveEventControl(C::mip_interface& device, uint8_t instance); @@ -2496,6 +2559,7 @@ struct GetEventTriggerStatus { struct Status : Bitfield { + typedef uint8_t Type; enum _enumType : uint8_t { NONE = 0x00, @@ -2514,74 +2578,76 @@ struct GetEventTriggerStatus Status& operator|=(uint8_t val) { return *this = value | val; } Status& operator&=(uint8_t val) { return *this = value & val; } - bool active() const { return (value & ACTIVE) > 0; } - void active(bool val) { if(val) value |= ACTIVE; else value &= ~ACTIVE; } - bool enabled() const { return (value & ENABLED) > 0; } - void enabled(bool val) { if(val) value |= ENABLED; else value &= ~ENABLED; } - bool test() const { return (value & TEST) > 0; } - void test(bool val) { if(val) value |= TEST; else value &= ~TEST; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - struct Entry { + /// Parameters uint8_t type = 0; ///< Configured trigger type. Status status; ///< Trigger status. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; + /// Parameters uint8_t requested_count = 0; ///< Number of entries requested. If 0, requests all trigger slots. uint8_t requested_instances[20] = {0}; ///< List of trigger instances to query. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_TRIGGER_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetEventTriggerStatus"; static constexpr const char* DOC_NAME = "Get Trigger Status"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(requested_count,requested_instances); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(requested_count),std::ref(requested_instances)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t count = 0; ///< Number of entries requested. If requested_count was 0, this is the number of supported trigger slots. + Entry triggers[20]; ///< A list of the configured triggers. Entries are in the order requested, or in increasing order if count was 0. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_TRIGGER_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetEventTriggerStatus::Response"; static constexpr const char* DOC_NAME = "Get Trigger Status Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - uint8_t count = 0; ///< Number of entries requested. If requested_count was 0, this is the number of supported trigger slots. - Entry triggers[20]; ///< A list of the configured triggers. Entries are in the order requested, or in increasing order if count was 0. - + auto asTuple() const + { + return std::make_tuple(count,triggers); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(count),std::ref(triggers)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus& self); -void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus& self); - -void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus::Entry& self); -void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus::Entry& self); - -void insert(::microstrain::Serializer& serializer, const GetEventTriggerStatus::Response& self); -void extract(::microstrain::Serializer& serializer, GetEventTriggerStatus::Response& self); - TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut); ///@} @@ -2595,61 +2661,71 @@ struct GetEventActionStatus { struct Entry { + /// Parameters uint8_t action_type = 0; ///< Configured action type. uint8_t trigger_id = 0; ///< Associated trigger instance. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; + /// Parameters uint8_t requested_count = 0; ///< Number of entries requested. If 0, requests all action slots. uint8_t requested_instances[20] = {0}; ///< List of action instances to query. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_ACTION_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetEventActionStatus"; static constexpr const char* DOC_NAME = "Get Action Status"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(requested_count,requested_instances); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(requested_count),std::ref(requested_instances)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t count = 0; ///< Number of entries requested. If requested_count was 0, this is the number of supported action slots. + Entry actions[20]; ///< A list of the configured actions. Entries are in the order requested, or in increasing order if count was 0. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_ACTION_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetEventActionStatus::Response"; static constexpr const char* DOC_NAME = "Get Action Status Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - uint8_t count = 0; ///< Number of entries requested. If requested_count was 0, this is the number of supported action slots. - Entry actions[20]; ///< A list of the configured actions. Entries are in the order requested, or in increasing order if count was 0. - + auto asTuple() const + { + return std::make_tuple(count,actions); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(count),std::ref(actions)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetEventActionStatus& self); -void extract(::microstrain::Serializer& serializer, GetEventActionStatus& self); - -void insert(::microstrain::Serializer& serializer, const GetEventActionStatus::Entry& self); -void extract(::microstrain::Serializer& serializer, GetEventActionStatus::Entry& self); - -void insert(::microstrain::Serializer& serializer, const GetEventActionStatus::Response& self); -void extract(::microstrain::Serializer& serializer, GetEventActionStatus::Response& self); - TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut); ///@} @@ -2672,9 +2748,14 @@ struct EventTrigger EDGE = 4, ///< Use if the pin is configured for timestamping via the 3DM Gpio Configuration command (0x0C41). }; + /// Parameters uint8_t pin = 0; ///< GPIO pin number. Mode mode = static_cast(0); ///< How the pin state affects the trigger. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; struct ThresholdParams { @@ -2684,6 +2765,7 @@ struct EventTrigger INTERVAL = 2, ///< Trigger at evenly-spaced intervals. Normally used with time fields to trigger periodically. Trigger is active when (value % interval) <= int_thres. If the thresholds are reversed (high_thres < low_thres) then the trigger is active when (value % low_thres) > high_thres. }; + /// Parameters uint8_t desc_set = 0; ///< Descriptor set of target data quantity. uint8_t field_desc = 0; ///< Field descriptor of target data quantity. uint8_t param_id = 0; ///< 1-based index of the target parameter within the MIP field. E.g. for Scaled Accel (0x80,0x04) a value of 2 would represent the Y axis. @@ -2699,6 +2781,10 @@ struct EventTrigger double interval; }; + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; struct CombinationParams { @@ -2715,9 +2801,14 @@ struct EventTrigger static constexpr const uint16_t LOGIC_AND_AB = 0x8888; static constexpr const uint16_t LOGIC_AB_OR_C = 0xF8F8; static constexpr const uint16_t LOGIC_AND = 0x8000; + /// Parameters uint16_t logic_table = 0; ///< The last column of a truth table describing the output given the state of each input. uint8_t input_triggers[4] = {0}; ///< List of trigger IDs for inputs. Use 0 for unused inputs. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; enum class Type : uint8_t { @@ -2729,38 +2820,32 @@ struct EventTrigger union Parameters { - Parameters() {} GpioParams gpio; ThresholdParams threshold; CombinationParams combination; + + Parameters() {} }; - + /// Parameters FunctionSelector function = static_cast(0); uint8_t instance = 0; ///< Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances. Type type = static_cast(0); ///< Type of trigger to configure. Parameters parameters; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_TRIGGER_CONFIG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EventTrigger"; static constexpr const char* DOC_NAME = "Event Trigger Configuration"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8007; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(instance,type,parameters); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(instance),std::ref(type),std::ref(parameters)); } @@ -2773,42 +2858,41 @@ struct EventTrigger return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t instance = 0; ///< Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances. + Type type = static_cast(0); ///< Type of trigger to configure. + Parameters parameters; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_TRIGGER_CONFIG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EventTrigger::Response"; static constexpr const char* DOC_NAME = "Event Trigger Configuration Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t instance = 0; ///< Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances. - Type type = static_cast(0); ///< Type of trigger to configure. - Parameters parameters; - + auto asTuple() const + { + return std::make_tuple(instance,type,parameters); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(instance),std::ref(type),std::ref(parameters)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const EventTrigger& self); -void extract(::microstrain::Serializer& serializer, EventTrigger& self); - -void insert(::microstrain::Serializer& serializer, const EventTrigger::GpioParams& self); -void extract(::microstrain::Serializer& serializer, EventTrigger::GpioParams& self); - -void insert(::microstrain::Serializer& serializer, const EventTrigger::ThresholdParams& self); -void extract(::microstrain::Serializer& serializer, EventTrigger::ThresholdParams& self); - -void insert(::microstrain::Serializer& serializer, const EventTrigger::CombinationParams& self); -void extract(::microstrain::Serializer& serializer, EventTrigger::CombinationParams& self); - -void insert(::microstrain::Serializer& serializer, const EventTrigger::Response& self); -void extract(::microstrain::Serializer& serializer, EventTrigger::Response& self); - TypedResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters); TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut); TypedResult saveEventTrigger(C::mip_interface& device, uint8_t instance); @@ -2837,17 +2921,27 @@ struct EventAction TOGGLE = 7, ///< Pin will change to the opposite state each time the trigger activates. }; + /// Parameters uint8_t pin = 0; ///< GPIO pin number. Mode mode = static_cast(0); ///< Behavior of the pin. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; struct MessageParams { + /// Parameters uint8_t desc_set = 0; ///< MIP data descriptor set. uint16_t decimation = 0; ///< Decimation from the base rate. If 0, a packet is emitted each time the trigger activates. Otherwise, packets will be streamed while the trigger is active. The internal decimation counter is reset if the trigger deactivates. uint8_t num_fields = 0; ///< Number of mip fields in the packet. Limited to 12. uint8_t descriptors[20] = {0}; ///< List of field descriptors. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; enum class Type : uint8_t { @@ -2858,38 +2952,32 @@ struct EventAction union Parameters { - Parameters() {} GpioParams gpio; MessageParams message; + + Parameters() {} }; - + /// Parameters FunctionSelector function = static_cast(0); uint8_t instance = 0; ///< Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances. uint8_t trigger = 0; ///< Trigger ID number. Type type = static_cast(0); ///< Type of action to configure. Parameters parameters; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_EVENT_ACTION_CONFIG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EventAction"; static constexpr const char* DOC_NAME = "Event Action Configuration"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x800F; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(instance,trigger,type,parameters); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(instance),std::ref(trigger),std::ref(type),std::ref(parameters)); } @@ -2902,40 +2990,42 @@ struct EventAction return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t instance = 0; ///< Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances. + uint8_t trigger = 0; ///< Trigger ID number. + Type type = static_cast(0); ///< Type of action to configure. + Parameters parameters; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_EVENT_ACTION_CONFIG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EventAction::Response"; static constexpr const char* DOC_NAME = "Event Action Configuration Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t instance = 0; ///< Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances. - uint8_t trigger = 0; ///< Trigger ID number. - Type type = static_cast(0); ///< Type of action to configure. - Parameters parameters; - + auto asTuple() const + { + return std::make_tuple(instance,trigger,type,parameters); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(instance),std::ref(trigger),std::ref(type),std::ref(parameters)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const EventAction& self); -void extract(::microstrain::Serializer& serializer, EventAction& self); - -void insert(::microstrain::Serializer& serializer, const EventAction::GpioParams& self); -void extract(::microstrain::Serializer& serializer, EventAction::GpioParams& self); - -void insert(::microstrain::Serializer& serializer, const EventAction::MessageParams& self); -void extract(::microstrain::Serializer& serializer, EventAction::MessageParams& self); - -void insert(::microstrain::Serializer& serializer, const EventAction::Response& self); -void extract(::microstrain::Serializer& serializer, EventAction::Response& self); - TypedResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters); TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut); TypedResult saveEventAction(C::mip_interface& device, uint8_t instance); @@ -2954,30 +3044,24 @@ TypedResult defaultEventAction(C::mip_interface& device, uint8_t in struct AccelBias { + /// Parameters FunctionSelector function = static_cast(0); Vector3f bias; ///< accelerometer bias in the sensor frame (x,y,z) [g] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_ACCEL_BIAS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelBias"; static constexpr const char* DOC_NAME = "Configure Accel Bias"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias)); } @@ -2989,31 +3073,39 @@ struct AccelBias return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f bias; ///< accelerometer bias in the sensor frame (x,y,z) [g] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_ACCEL_BIAS_VECTOR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelBias::Response"; static constexpr const char* DOC_NAME = "Configure Accel Bias Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f bias; ///< accelerometer bias in the sensor frame (x,y,z) [g] - + auto asTuple() const + { + return std::make_tuple(bias); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AccelBias& self); -void extract(::microstrain::Serializer& serializer, AccelBias& self); - -void insert(::microstrain::Serializer& serializer, const AccelBias::Response& self); -void extract(::microstrain::Serializer& serializer, AccelBias::Response& self); - TypedResult writeAccelBias(C::mip_interface& device, const float* bias); TypedResult readAccelBias(C::mip_interface& device, float* biasOut); TypedResult saveAccelBias(C::mip_interface& device); @@ -3032,30 +3124,24 @@ TypedResult defaultAccelBias(C::mip_interface& device); struct GyroBias { + /// Parameters FunctionSelector function = static_cast(0); Vector3f bias; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_GYRO_BIAS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroBias"; static constexpr const char* DOC_NAME = "Configure Gyro Bias"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias)); } @@ -3067,31 +3153,39 @@ struct GyroBias return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f bias; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GYRO_BIAS_VECTOR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroBias::Response"; static constexpr const char* DOC_NAME = "Configure Gyro Bias Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f bias; ///< gyro bias in the sensor frame (x,y,z) [radians/second] - + auto asTuple() const + { + return std::make_tuple(bias); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GyroBias& self); -void extract(::microstrain::Serializer& serializer, GyroBias& self); - -void insert(::microstrain::Serializer& serializer, const GyroBias::Response& self); -void extract(::microstrain::Serializer& serializer, GyroBias::Response& self); - TypedResult writeGyroBias(C::mip_interface& device, const float* bias); TypedResult readGyroBias(C::mip_interface& device, float* biasOut); TypedResult saveGyroBias(C::mip_interface& device); @@ -3113,52 +3207,60 @@ TypedResult defaultGyroBias(C::mip_interface& device); struct CaptureGyroBias { + /// Parameters uint16_t averaging_time_ms = 0; ///< Averaging time [milliseconds] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_CAPTURE_GYRO_BIAS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CaptureGyroBias"; static constexpr const char* DOC_NAME = "Capture Gyro Bias"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(averaging_time_ms); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(averaging_time_ms)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f bias; ///< gyro bias in the sensor frame (x,y,z) [radians/second] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_GYRO_BIAS_VECTOR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CaptureGyroBias::Response"; static constexpr const char* DOC_NAME = "Capture Gyro Bias Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f bias; ///< gyro bias in the sensor frame (x,y,z) [radians/second] - + auto asTuple() const + { + return std::make_tuple(bias); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const CaptureGyroBias& self); -void extract(::microstrain::Serializer& serializer, CaptureGyroBias& self); - -void insert(::microstrain::Serializer& serializer, const CaptureGyroBias::Response& self); -void extract(::microstrain::Serializer& serializer, CaptureGyroBias::Response& self); - TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut); ///@} @@ -3177,30 +3279,24 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t struct MagHardIronOffset { + /// Parameters FunctionSelector function = static_cast(0); Vector3f offset; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_HARD_IRON_OFFSET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagHardIronOffset"; static constexpr const char* DOC_NAME = "Magnetometer Hard Iron Offset"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(offset); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset)); } @@ -3212,31 +3308,39 @@ struct MagHardIronOffset return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f offset; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_HARD_IRON_OFFSET_VECTOR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagHardIronOffset::Response"; static constexpr const char* DOC_NAME = "Magnetometer Hard Iron Offset Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f offset; ///< hard iron offset in the sensor frame (x,y,z) [Gauss] - + auto asTuple() const + { + return std::make_tuple(offset); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const MagHardIronOffset& self); -void extract(::microstrain::Serializer& serializer, MagHardIronOffset& self); - -void insert(::microstrain::Serializer& serializer, const MagHardIronOffset::Response& self); -void extract(::microstrain::Serializer& serializer, MagHardIronOffset::Response& self); - TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset); TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut); TypedResult saveMagHardIronOffset(C::mip_interface& device); @@ -3263,30 +3367,24 @@ TypedResult defaultMagHardIronOffset(C::mip_interface& device struct MagSoftIronMatrix { + /// Parameters FunctionSelector function = static_cast(0); Matrix3f offset; ///< soft iron matrix [dimensionless] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SOFT_IRON_MATRIX; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagSoftIronMatrix"; static constexpr const char* DOC_NAME = "Magnetometer Soft Iron Matrix"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(offset); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset)); } @@ -3298,31 +3396,39 @@ struct MagSoftIronMatrix return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Matrix3f offset; ///< soft iron matrix [dimensionless] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SOFT_IRON_COMP_MATRIX; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagSoftIronMatrix::Response"; static constexpr const char* DOC_NAME = "Magnetometer Soft Iron Matrix Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Matrix3f offset; ///< soft iron matrix [dimensionless] - + auto asTuple() const + { + return std::make_tuple(offset); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const MagSoftIronMatrix& self); -void extract(::microstrain::Serializer& serializer, MagSoftIronMatrix& self); - -void insert(::microstrain::Serializer& serializer, const MagSoftIronMatrix::Response& self); -void extract(::microstrain::Serializer& serializer, MagSoftIronMatrix::Response& self); - TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset); TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut); TypedResult saveMagSoftIronMatrix(C::mip_interface& device); @@ -3339,30 +3445,24 @@ TypedResult defaultMagSoftIronMatrix(C::mip_interface& device struct ConingScullingEnable { + /// Parameters FunctionSelector function = static_cast(0); bool enable = 0; ///< If true, coning and sculling compensation is enabled. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_CONING_AND_SCULLING_ENABLE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ConingScullingEnable"; static constexpr const char* DOC_NAME = "Coning and Sculling Enable"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } @@ -3374,31 +3474,39 @@ struct ConingScullingEnable return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + bool enable = 0; ///< If true, coning and sculling compensation is enabled. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_CONING_AND_SCULLING_ENABLE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ConingScullingEnable::Response"; static constexpr const char* DOC_NAME = "Coning and Sculling Enable Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - bool enable = 0; ///< If true, coning and sculling compensation is enabled. - + auto asTuple() const + { + return std::make_tuple(enable); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ConingScullingEnable& self); -void extract(::microstrain::Serializer& serializer, ConingScullingEnable& self); - -void insert(::microstrain::Serializer& serializer, const ConingScullingEnable::Response& self); -void extract(::microstrain::Serializer& serializer, ConingScullingEnable::Response& self); - TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable); TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut); TypedResult saveConingScullingEnable(C::mip_interface& device); @@ -3439,32 +3547,26 @@ TypedResult defaultConingScullingEnable(C::mip_interface& struct Sensor2VehicleTransformEuler { + /// Parameters FunctionSelector function = static_cast(0); float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SENSOR2VEHICLE_TRANSFORM_EUL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Sensor2VehicleTransformEuler"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Transformation Euler"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8007; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(roll,pitch,yaw); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); } @@ -3476,33 +3578,41 @@ struct Sensor2VehicleTransformEuler return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + float roll = 0; ///< [radians] + float pitch = 0; ///< [radians] + float yaw = 0; ///< [radians] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SENSOR2VEHICLE_TRANSFORM_EUL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Sensor2VehicleTransformEuler::Response"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Transformation Euler Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - float roll = 0; ///< [radians] - float pitch = 0; ///< [radians] - float yaw = 0; ///< [radians] - + auto asTuple() const + { + return std::make_tuple(roll,pitch,yaw); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformEuler& self); -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformEuler& self); - -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformEuler::Response& self); -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformEuler::Response& self); - TypedResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw); TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut); TypedResult saveSensor2VehicleTransformEuler(C::mip_interface& device); @@ -3551,30 +3661,24 @@ TypedResult defaultSensor2VehicleTransformEuler(C: struct Sensor2VehicleTransformQuaternion { + /// Parameters FunctionSelector function = static_cast(0); Quatf q; ///< Unit length quaternion representing transform [w, i, j, k] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SENSOR2VEHICLE_TRANSFORM_QUAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Sensor2VehicleTransformQuaternion"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Transformation Quaternion"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(q); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(q)); } @@ -3586,31 +3690,39 @@ struct Sensor2VehicleTransformQuaternion return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Quatf q; ///< Unit length quaternion representing transform [w, i, j, k] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Sensor2VehicleTransformQuaternion::Response"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Transformation Quaternion Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Quatf q; ///< Unit length quaternion representing transform [w, i, j, k] - + auto asTuple() const + { + return std::make_tuple(q); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(q)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformQuaternion& self); -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformQuaternion& self); - -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformQuaternion::Response& self); -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformQuaternion::Response& self); - TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q); TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut); TypedResult saveSensor2VehicleTransformQuaternion(C::mip_interface& device); @@ -3657,30 +3769,24 @@ TypedResult defaultSensor2VehicleTransformQua struct Sensor2VehicleTransformDcm { + /// Parameters FunctionSelector function = static_cast(0); Matrix3f dcm; ///< 3 x 3 direction cosine matrix, stored in row-major order + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SENSOR2VEHICLE_TRANSFORM_DCM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Sensor2VehicleTransformDcm"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Transformation Direction Cosine Matrix"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(dcm); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(dcm)); } @@ -3692,31 +3798,39 @@ struct Sensor2VehicleTransformDcm return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Matrix3f dcm; ///< 3 x 3 direction cosine matrix, stored in row-major order + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SENSOR2VEHICLE_TRANSFORM_DCM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Sensor2VehicleTransformDcm::Response"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Transformation Direction Cosine Matrix Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Matrix3f dcm; ///< 3 x 3 direction cosine matrix, stored in row-major order - + auto asTuple() const + { + return std::make_tuple(dcm); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(dcm)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformDcm& self); -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformDcm& self); - -void insert(::microstrain::Serializer& serializer, const Sensor2VehicleTransformDcm::Response& self); -void extract(::microstrain::Serializer& serializer, Sensor2VehicleTransformDcm::Response& self); - TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm); TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut); TypedResult saveSensor2VehicleTransformDcm(C::mip_interface& device); @@ -3737,33 +3851,27 @@ TypedResult defaultSensor2VehicleTransformDcm(C::mip struct ComplementaryFilter { + /// Parameters FunctionSelector function = static_cast(0); bool pitch_roll_enable = 0; ///< Enable Pitch/Roll corrections bool heading_enable = 0; ///< Enable Heading corrections (only available on devices with magnetometer) float pitch_roll_time_constant = 0; ///< Time constant associated with the pitch/roll corrections [s] float heading_time_constant = 0; ///< Time constant associated with the heading corrections [s] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_LEGACY_COMP_FILTER; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ComplementaryFilter"; static constexpr const char* DOC_NAME = "Complementary filter settings"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x800F; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(pitch_roll_enable,heading_enable,pitch_roll_time_constant,heading_time_constant); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(pitch_roll_enable),std::ref(heading_enable),std::ref(pitch_roll_time_constant),std::ref(heading_time_constant)); } @@ -3775,34 +3883,42 @@ struct ComplementaryFilter return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + bool pitch_roll_enable = 0; ///< Enable Pitch/Roll corrections + bool heading_enable = 0; ///< Enable Heading corrections (only available on devices with magnetometer) + float pitch_roll_time_constant = 0; ///< Time constant associated with the pitch/roll corrections [s] + float heading_time_constant = 0; ///< Time constant associated with the heading corrections [s] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_LEGACY_COMP_FILTER; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ComplementaryFilter::Response"; static constexpr const char* DOC_NAME = "Complementary filter settings Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - bool pitch_roll_enable = 0; ///< Enable Pitch/Roll corrections - bool heading_enable = 0; ///< Enable Heading corrections (only available on devices with magnetometer) - float pitch_roll_time_constant = 0; ///< Time constant associated with the pitch/roll corrections [s] - float heading_time_constant = 0; ///< Time constant associated with the heading corrections [s] - + auto asTuple() const + { + return std::make_tuple(pitch_roll_enable,heading_enable,pitch_roll_time_constant,heading_time_constant); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(pitch_roll_enable),std::ref(heading_enable),std::ref(pitch_roll_time_constant),std::ref(heading_time_constant)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ComplementaryFilter& self); -void extract(::microstrain::Serializer& serializer, ComplementaryFilter& self); - -void insert(::microstrain::Serializer& serializer, const ComplementaryFilter::Response& self); -void extract(::microstrain::Serializer& serializer, ComplementaryFilter::Response& self); - TypedResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant); TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut); TypedResult saveComplementaryFilter(C::mip_interface& device); @@ -3826,31 +3942,25 @@ TypedResult defaultComplementaryFilter(C::mip_interface& de struct SensorRange { + /// Parameters FunctionSelector function = static_cast(0); SensorRangeType sensor = static_cast(0); ///< Which type of sensor will get the new range value. uint8_t setting = 0; ///< Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_SENSOR_RANGE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorRange"; static constexpr const char* DOC_NAME = "Sensor Range"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(sensor,setting); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(sensor),std::ref(setting)); } @@ -3863,32 +3973,40 @@ struct SensorRange return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + SensorRangeType sensor = static_cast(0); ///< Which type of sensor will get the new range value. + uint8_t setting = 0; ///< Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_SENSOR_RANGE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorRange::Response"; static constexpr const char* DOC_NAME = "Sensor Range Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - SensorRangeType sensor = static_cast(0); ///< Which type of sensor will get the new range value. - uint8_t setting = 0; ///< Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value. - + auto asTuple() const + { + return std::make_tuple(sensor,setting); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(sensor),std::ref(setting)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const SensorRange& self); -void extract(::microstrain::Serializer& serializer, SensorRange& self); - -void insert(::microstrain::Serializer& serializer, const SensorRange::Response& self); -void extract(::microstrain::Serializer& serializer, SensorRange::Response& self); - TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting); TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut); TypedResult saveSensorRange(C::mip_interface& device, SensorRangeType sensor); @@ -3910,61 +4028,71 @@ struct CalibratedSensorRanges { struct Entry { + /// Parameters uint8_t setting = 0; ///< The value used in the 3DM Sensor Range command and response. float range = 0; ///< The actual range value. Units depend on the sensor type. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; + /// Parameters SensorRangeType sensor = static_cast(0); ///< The sensor to query. Cannot be ALL. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_CALIBRATED_RANGES; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CalibratedSensorRanges"; static constexpr const char* DOC_NAME = "Get Calibrated Sensor Ranges"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(sensor); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(sensor)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + SensorRangeType sensor = static_cast(0); ///< The sensor type from the command. + uint8_t num_ranges = 0; ///< Number of supported ranges. + Entry ranges[50]; ///< List of possible range settings. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_CALIBRATED_RANGES; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CalibratedSensorRanges::Response"; static constexpr const char* DOC_NAME = "Get Calibrated Sensor Ranges Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000030; - SensorRangeType sensor = static_cast(0); ///< The sensor type from the command. - uint8_t num_ranges = 0; ///< Number of supported ranges. - Entry ranges[50]; ///< List of possible range settings. - + auto asTuple() const + { + return std::make_tuple(sensor,num_ranges,ranges); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(sensor),std::ref(num_ranges),std::ref(ranges)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges& self); -void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges& self); - -void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges::Entry& self); -void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges::Entry& self); - -void insert(::microstrain::Serializer& serializer, const CalibratedSensorRanges::Response& self); -void extract(::microstrain::Serializer& serializer, CalibratedSensorRanges::Response& self); - TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut); ///@} @@ -3990,6 +4118,7 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev struct LowpassFilter { + /// Parameters FunctionSelector function = static_cast(0); uint8_t desc_set = 0; ///< Descriptor set of the quantity to be filtered. uint8_t field_desc = 0; ///< Field descriptor of the quantity to be filtered. @@ -3997,27 +4126,20 @@ struct LowpassFilter bool manual = 0; ///< If false, the frequency parameter is ignored and the filter will track to half of the configured message format frequency. float frequency = 0; ///< Cutoff frequency in Hz. This will return the actual frequency when read out in automatic mode. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::CMD_LOWPASS_FILTER; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "LowpassFilter"; static constexpr const char* DOC_NAME = "Low-pass anti-aliasing filter"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x801F; - static constexpr const uint32_t READ_PARAMS = 0x8003; - static constexpr const uint32_t SAVE_PARAMS = 0x8003; - static constexpr const uint32_t LOAD_PARAMS = 0x8003; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8003; - static constexpr const uint32_t ECHOED_PARAMS = 0x0003; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(desc_set,field_desc,enable,manual,frequency); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(desc_set),std::ref(field_desc),std::ref(enable),std::ref(manual),std::ref(frequency)); } @@ -4031,35 +4153,43 @@ struct LowpassFilter return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { - static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_LOWPASS_FILTER; - static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "LowpassFilter::Response"; - static constexpr const char* DOC_NAME = "Low-pass anti-aliasing filter Response"; - - static constexpr const uint32_t ECHOED_PARAMS = 0x0003; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + /// Parameters uint8_t desc_set = 0; ///< Descriptor set of the quantity to be filtered. uint8_t field_desc = 0; ///< Field descriptor of the quantity to be filtered. bool enable = 0; ///< The filter will be enabled if this is true. bool manual = 0; ///< If false, the frequency parameter is ignored and the filter will track to half of the configured message format frequency. float frequency = 0; ///< Cutoff frequency in Hz. This will return the actual frequency when read out in automatic mode. + /// Descriptors + static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_3dm::DESCRIPTOR_SET; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_3dm::REPLY_LOWPASS_FILTER; + static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "LowpassFilter::Response"; + static constexpr const char* DOC_NAME = "Low-pass anti-aliasing filter Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + + auto asTuple() const + { + return std::make_tuple(desc_set,field_desc,enable,manual,frequency); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(desc_set),std::ref(field_desc),std::ref(enable),std::ref(manual),std::ref(frequency)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const LowpassFilter& self); -void extract(::microstrain::Serializer& serializer, LowpassFilter& self); - -void insert(::microstrain::Serializer& serializer, const LowpassFilter::Response& self); -void extract(::microstrain::Serializer& serializer, LowpassFilter::Response& self); - TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool enable, bool manual, float frequency); TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut); TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc); diff --git a/src/cpp/mip/definitions/commands_aiding.cpp b/src/cpp/mip/definitions/commands_aiding.cpp index 6c839f013..a477b84d9 100644 --- a/src/cpp/mip/definitions/commands_aiding.cpp +++ b/src/cpp/mip/definitions/commands_aiding.cpp @@ -1,183 +1,127 @@ #include "commands_aiding.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace commands_aiding { -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; //////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions +// Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const Time& self) +void Time::insert(Serializer& serializer) const { - insert(serializer, self.timebase); + serializer.insert(timebase); - insert(serializer, self.reserved); + serializer.insert(reserved); - insert(serializer, self.nanoseconds); + serializer.insert(nanoseconds); } -void extract(::microstrain::Serializer& serializer, Time& self) +void Time::extract(Serializer& serializer) { - extract(serializer, self.timebase); + serializer.extract(timebase); - extract(serializer, self.reserved); + serializer.extract(reserved); - extract(serializer, self.nanoseconds); + serializer.extract(nanoseconds); } - -//////////////////////////////////////////////////////////////////////////////// -// Mip Fields -//////////////////////////////////////////////////////////////////////////////// - -void insert(::microstrain::Serializer& serializer, const FrameConfig& self) +void FrameConfig::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - if( self.function == FunctionSelector::WRITE || self.function == FunctionSelector::READ ) + if( function == FunctionSelector::WRITE || function == FunctionSelector::READ ) { - insert(serializer, self.format); + serializer.insert(format); } - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.tracking_enabled); + serializer.insert(tracking_enabled); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.translation[i]); + serializer.insert(translation); - if( self.format == FrameConfig::Format::EULER ) + if( format == FrameConfig::Format::EULER ) { - insert(serializer, self.rotation.euler); + serializer.insert(rotation.euler); } - if( self.format == FrameConfig::Format::QUATERNION ) + if( format == FrameConfig::Format::QUATERNION ) { - insert(serializer, self.rotation.quaternion); + serializer.insert(rotation.quaternion); } } } -void extract(::microstrain::Serializer& serializer, FrameConfig& self) +void FrameConfig::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - if( self.function == FunctionSelector::WRITE || self.function == FunctionSelector::READ ) + if( function == FunctionSelector::WRITE || function == FunctionSelector::READ ) { - extract(serializer, self.format); + serializer.extract(format); } - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.tracking_enabled); + serializer.extract(tracking_enabled); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.translation[i]); + serializer.extract(translation); - if( self.format == FrameConfig::Format::EULER ) + if( format == FrameConfig::Format::EULER ) { - extract(serializer, self.rotation.euler); + serializer.extract(rotation.euler); } - if( self.format == FrameConfig::Format::QUATERNION ) + if( format == FrameConfig::Format::QUATERNION ) { - extract(serializer, self.rotation.quaternion); + serializer.extract(rotation.quaternion); } } } -void insert(::microstrain::Serializer& serializer, const FrameConfig::Response& self) -{ - insert(serializer, self.frame_id); - - insert(serializer, self.format); - - insert(serializer, self.tracking_enabled); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.translation[i]); - - if( self.format == FrameConfig::Format::EULER ) - { - insert(serializer, self.rotation.euler); - - } - if( self.format == FrameConfig::Format::QUATERNION ) - { - insert(serializer, self.rotation.quaternion); - - } -} -void extract(::microstrain::Serializer& serializer, FrameConfig::Response& self) -{ - extract(serializer, self.frame_id); - - extract(serializer, self.format); - - extract(serializer, self.tracking_enabled); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.translation[i]); - - if( self.format == FrameConfig::Format::EULER ) - { - extract(serializer, self.rotation.euler); - - } - if( self.format == FrameConfig::Format::QUATERNION ) - { - extract(serializer, self.rotation.quaternion); - - } -} - TypedResult writeFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool trackingEnabled, const float* translation, const FrameConfig::Rotation& rotation) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, frameId); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(frameId); - insert(serializer, format); + serializer.insert(format); - insert(serializer, trackingEnabled); + serializer.insert(trackingEnabled); - assert(translation || (3 == 0)); + assert(translation); for(unsigned int i=0; i < 3; i++) - insert(serializer, translation[i]); + serializer.insert(translation[i]); if( format == FrameConfig::Format::EULER ) { - insert(serializer, rotation.euler); + serializer.insert(rotation.euler); } if( format == FrameConfig::Format::QUATERNION ) { - insert(serializer, rotation.quaternion); + serializer.insert(rotation.quaternion); } assert(serializer.isOk()); @@ -186,56 +130,56 @@ TypedResult writeFrameConfig(C::mip_interface& device, uint8_t fram } TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, frameId); + serializer.insert(FunctionSelector::READ); + serializer.insert(frameId); - insert(serializer, format); + serializer.insert(format); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_FRAME_CONFIG, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, frameId); + deserializer.extract(frameId); - extract(deserializer, format); + deserializer.extract(format); assert(trackingEnabledOut); - extract(deserializer, *trackingEnabledOut); + deserializer.extract(*trackingEnabledOut); - assert(translationOut || (3 == 0)); + assert(translationOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, translationOut[i]); + deserializer.extract(translationOut[i]); if( format == FrameConfig::Format::EULER ) { - extract(deserializer, rotationOut->euler); + deserializer.extract(rotationOut->euler); } if( format == FrameConfig::Format::QUATERNION ) { - extract(deserializer, rotationOut->quaternion); + deserializer.extract(rotationOut->quaternion); } if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frameId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, frameId); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(frameId); assert(serializer.isOk()); @@ -243,11 +187,11 @@ TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frame } TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frameId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, frameId); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(frameId); assert(serializer.isOk()); @@ -255,55 +199,44 @@ TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frame } TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t frameId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, frameId); + serializer.insert(FunctionSelector::RESET); + serializer.insert(frameId); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AidingEchoControl& self) +void AidingEchoControl::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.mode); + serializer.insert(mode); } } -void extract(::microstrain::Serializer& serializer, AidingEchoControl& self) +void AidingEchoControl::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.mode); + serializer.extract(mode); } } -void insert(::microstrain::Serializer& serializer, const AidingEchoControl::Response& self) -{ - insert(serializer, self.mode); - -} -void extract(::microstrain::Serializer& serializer, AidingEchoControl::Response& self) -{ - extract(serializer, self.mode); - -} - TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, mode); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(mode); assert(serializer.isOk()); @@ -311,522 +244,500 @@ TypedResult writeAidingEchoControl(C::mip_interface& device, } TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(modeOut); - extract(deserializer, *modeOut); + deserializer.extract(*modeOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAidingEchoControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAidingEchoControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAidingEchoControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const EcefPos& self) +void EcefPos::insert(Serializer& serializer) const { - insert(serializer, self.time); + serializer.insert(time); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.position[i]); + serializer.insert(position); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.uncertainty[i]); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, EcefPos& self) +void EcefPos::extract(Serializer& serializer) { - extract(serializer, self.time); + serializer.extract(time); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.position[i]); + serializer.extract(position); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.uncertainty[i]); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, time); + serializer.insert(time); - insert(serializer, frameId); + serializer.insert(frameId); - assert(position || (3 == 0)); + assert(position); for(unsigned int i=0; i < 3; i++) - insert(serializer, position[i]); + serializer.insert(position[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) - insert(serializer, uncertainty[i]); + serializer.insert(uncertainty[i]); - insert(serializer, validFlags); + serializer.insert(validFlags); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const LlhPos& self) +void LlhPos::insert(Serializer& serializer) const { - insert(serializer, self.time); + serializer.insert(time); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - insert(serializer, self.latitude); + serializer.insert(latitude); - insert(serializer, self.longitude); + serializer.insert(longitude); - insert(serializer, self.height); + serializer.insert(height); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.uncertainty[i]); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, LlhPos& self) +void LlhPos::extract(Serializer& serializer) { - extract(serializer, self.time); + serializer.extract(time); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - extract(serializer, self.latitude); + serializer.extract(latitude); - extract(serializer, self.longitude); + serializer.extract(longitude); - extract(serializer, self.height); + serializer.extract(height); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.uncertainty[i]); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, time); + serializer.insert(time); - insert(serializer, frameId); + serializer.insert(frameId); - insert(serializer, latitude); + serializer.insert(latitude); - insert(serializer, longitude); + serializer.insert(longitude); - insert(serializer, height); + serializer.insert(height); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) - insert(serializer, uncertainty[i]); + serializer.insert(uncertainty[i]); - insert(serializer, validFlags); + serializer.insert(validFlags); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const Height& self) +void Height::insert(Serializer& serializer) const { - insert(serializer, self.time); + serializer.insert(time); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - insert(serializer, self.height); + serializer.insert(height); - insert(serializer, self.uncertainty); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, Height& self) +void Height::extract(Serializer& serializer) { - extract(serializer, self.time); + serializer.extract(time); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - extract(serializer, self.height); + serializer.extract(height); - extract(serializer, self.uncertainty); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, time); + serializer.insert(time); - insert(serializer, frameId); + serializer.insert(frameId); - insert(serializer, height); + serializer.insert(height); - insert(serializer, uncertainty); + serializer.insert(uncertainty); - insert(serializer, validFlags); + serializer.insert(validFlags); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const EcefVel& self) +void EcefVel::insert(Serializer& serializer) const { - insert(serializer, self.time); + serializer.insert(time); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.velocity[i]); + serializer.insert(velocity); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.uncertainty[i]); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, EcefVel& self) +void EcefVel::extract(Serializer& serializer) { - extract(serializer, self.time); + serializer.extract(time); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.velocity[i]); + serializer.extract(velocity); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.uncertainty[i]); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, time); + serializer.insert(time); - insert(serializer, frameId); + serializer.insert(frameId); - assert(velocity || (3 == 0)); + assert(velocity); for(unsigned int i=0; i < 3; i++) - insert(serializer, velocity[i]); + serializer.insert(velocity[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) - insert(serializer, uncertainty[i]); + serializer.insert(uncertainty[i]); - insert(serializer, validFlags); + serializer.insert(validFlags); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const NedVel& self) +void NedVel::insert(Serializer& serializer) const { - insert(serializer, self.time); + serializer.insert(time); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.velocity[i]); + serializer.insert(velocity); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.uncertainty[i]); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, NedVel& self) +void NedVel::extract(Serializer& serializer) { - extract(serializer, self.time); + serializer.extract(time); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.velocity[i]); + serializer.extract(velocity); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.uncertainty[i]); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, time); + serializer.insert(time); - insert(serializer, frameId); + serializer.insert(frameId); - assert(velocity || (3 == 0)); + assert(velocity); for(unsigned int i=0; i < 3; i++) - insert(serializer, velocity[i]); + serializer.insert(velocity[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) - insert(serializer, uncertainty[i]); + serializer.insert(uncertainty[i]); - insert(serializer, validFlags); + serializer.insert(validFlags); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const VehicleFixedFrameVelocity& self) +void VehicleFixedFrameVelocity::insert(Serializer& serializer) const { - insert(serializer, self.time); + serializer.insert(time); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.velocity[i]); + serializer.insert(velocity); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.uncertainty[i]); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, VehicleFixedFrameVelocity& self) +void VehicleFixedFrameVelocity::extract(Serializer& serializer) { - extract(serializer, self.time); + serializer.extract(time); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.velocity[i]); + serializer.extract(velocity); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.uncertainty[i]); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, time); + serializer.insert(time); - insert(serializer, frameId); + serializer.insert(frameId); - assert(velocity || (3 == 0)); + assert(velocity); for(unsigned int i=0; i < 3; i++) - insert(serializer, velocity[i]); + serializer.insert(velocity[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) - insert(serializer, uncertainty[i]); + serializer.insert(uncertainty[i]); - insert(serializer, validFlags); + serializer.insert(validFlags); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ODOM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const TrueHeading& self) +void TrueHeading::insert(Serializer& serializer) const { - insert(serializer, self.time); + serializer.insert(time); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - insert(serializer, self.heading); + serializer.insert(heading); - insert(serializer, self.uncertainty); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, TrueHeading& self) +void TrueHeading::extract(Serializer& serializer) { - extract(serializer, self.time); + serializer.extract(time); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - extract(serializer, self.heading); + serializer.extract(heading); - extract(serializer, self.uncertainty); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, time); + serializer.insert(time); - insert(serializer, frameId); + serializer.insert(frameId); - insert(serializer, heading); + serializer.insert(heading); - insert(serializer, uncertainty); + serializer.insert(uncertainty); - insert(serializer, validFlags); + serializer.insert(validFlags); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_TRUE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const MagneticField& self) +void MagneticField::insert(Serializer& serializer) const { - insert(serializer, self.time); + serializer.insert(time); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.magnetic_field[i]); + serializer.insert(magnetic_field); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.uncertainty[i]); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagneticField& self) +void MagneticField::extract(Serializer& serializer) { - extract(serializer, self.time); + serializer.extract(time); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.magnetic_field[i]); + serializer.extract(magnetic_field); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.uncertainty[i]); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } TypedResult magneticField(C::mip_interface& device, const Time& time, uint8_t frameId, const float* magneticField, const float* uncertainty, MagneticField::ValidFlags validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, time); + serializer.insert(time); - insert(serializer, frameId); + serializer.insert(frameId); - assert(magneticField || (3 == 0)); + assert(magneticField); for(unsigned int i=0; i < 3; i++) - insert(serializer, magneticField[i]); + serializer.insert(magneticField[i]); - assert(uncertainty || (3 == 0)); + assert(uncertainty); for(unsigned int i=0; i < 3; i++) - insert(serializer, uncertainty[i]); + serializer.insert(uncertainty[i]); - insert(serializer, validFlags); + serializer.insert(validFlags); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_FIELD, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const Pressure& self) +void Pressure::insert(Serializer& serializer) const { - insert(serializer, self.time); + serializer.insert(time); - insert(serializer, self.frame_id); + serializer.insert(frame_id); - insert(serializer, self.pressure); + serializer.insert(pressure); - insert(serializer, self.uncertainty); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, Pressure& self) +void Pressure::extract(Serializer& serializer) { - extract(serializer, self.time); + serializer.extract(time); - extract(serializer, self.frame_id); + serializer.extract(frame_id); - extract(serializer, self.pressure); + serializer.extract(pressure); - extract(serializer, self.uncertainty); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } TypedResult pressure(C::mip_interface& device, const Time& time, uint8_t frameId, float pressure, float uncertainty, uint16_t validFlags) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, time); + serializer.insert(time); - insert(serializer, frameId); + serializer.insert(frameId); - insert(serializer, pressure); + serializer.insert(pressure); - insert(serializer, uncertainty); + serializer.insert(uncertainty); - insert(serializer, validFlags); + serializer.insert(validFlags); assert(serializer.isOk()); diff --git a/src/cpp/mip/definitions/commands_aiding.hpp b/src/cpp/mip/definitions/commands_aiding.hpp index fdb5ca91f..dd4b9218e 100644 --- a/src/cpp/mip/definitions/commands_aiding.hpp +++ b/src/cpp/mip/definitions/commands_aiding.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -68,14 +66,16 @@ struct Time TIME_OF_ARRIVAL = 3, ///< Timestamp provided is a fixed latency relative to time of message arrival. }; + /// Parameters Timebase timebase = static_cast(0); ///< Timebase reference, e.g. internal, external, GPS, UTC, etc. uint8_t reserved = 0; ///< Reserved, set to 0x01. uint64_t nanoseconds = 0; ///< Nanoseconds since the timebase epoch. + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const Time& self); -void extract(::microstrain::Serializer& serializer, Time& self); - //////////////////////////////////////////////////////////////////////////////// // Mip Fields @@ -120,11 +120,12 @@ struct FrameConfig union Rotation { - Rotation() {} Vector3f euler; Quatf quaternion; + + Rotation() {} }; - + /// Parameters FunctionSelector function = static_cast(0); uint8_t frame_id = 0; ///< Reference frame number. Limit 4. Format format = static_cast(0); ///< Format of the transformation. @@ -132,27 +133,20 @@ struct FrameConfig Vector3f translation; ///< Translation X, Y, and Z. Rotation rotation; ///< Rotation as specified by format. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_FRAME_CONFIG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "FrameConfig"; static constexpr const char* DOC_NAME = "Frame Configuration"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x801F; - static constexpr const uint32_t READ_PARAMS = 0x8003; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0003; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(frame_id,format,tracking_enabled,translation,rotation); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(frame_id),std::ref(format),std::ref(tracking_enabled),std::ref(translation),std::ref(rotation)); } @@ -165,35 +159,43 @@ struct FrameConfig return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { - static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::REPLY_FRAME_CONFIG; - static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "FrameConfig::Response"; - static constexpr const char* DOC_NAME = "Frame Configuration Response"; - - static constexpr const uint32_t ECHOED_PARAMS = 0x0003; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + /// Parameters uint8_t frame_id = 0; ///< Reference frame number. Limit 4. Format format = static_cast(0); ///< Format of the transformation. bool tracking_enabled = 0; ///< If enabled, the Kalman filter will track errors. Vector3f translation; ///< Translation X, Y, and Z. Rotation rotation; ///< Rotation as specified by format. + /// Descriptors + static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::REPLY_FRAME_CONFIG; + static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "FrameConfig::Response"; + static constexpr const char* DOC_NAME = "Frame Configuration Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + + auto asTuple() const + { + return std::make_tuple(frame_id,format,tracking_enabled,translation,rotation); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(frame_id),std::ref(format),std::ref(tracking_enabled),std::ref(translation),std::ref(rotation)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const FrameConfig& self); -void extract(::microstrain::Serializer& serializer, FrameConfig& self); - -void insert(::microstrain::Serializer& serializer, const FrameConfig::Response& self); -void extract(::microstrain::Serializer& serializer, FrameConfig::Response& self); - TypedResult writeFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool trackingEnabled, const float* translation, const FrameConfig::Rotation& rotation); TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut); TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frameId); @@ -217,30 +219,24 @@ struct AidingEchoControl RESPONSE = 2, ///< Echo the data back as a response. }; + /// Parameters FunctionSelector function = static_cast(0); Mode mode = static_cast(0); ///< Controls data echoing. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_ECHO_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AidingEchoControl"; static constexpr const char* DOC_NAME = "Aiding Command Echo Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(mode); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(mode)); } @@ -252,31 +248,39 @@ struct AidingEchoControl return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Mode mode = static_cast(0); ///< Controls data echoing. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::REPLY_ECHO_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AidingEchoControl::Response"; static constexpr const char* DOC_NAME = "Aiding Command Echo Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Mode mode = static_cast(0); ///< Controls data echoing. - + auto asTuple() const + { + return std::make_tuple(mode); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(mode)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AidingEchoControl& self); -void extract(::microstrain::Serializer& serializer, AidingEchoControl& self); - -void insert(::microstrain::Serializer& serializer, const AidingEchoControl::Response& self); -void extract(::microstrain::Serializer& serializer, AidingEchoControl::Response& self); - TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode); TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut); TypedResult saveAidingEchoControl(C::mip_interface& device); @@ -295,6 +299,7 @@ struct EcefPos { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -313,46 +318,40 @@ struct EcefPos ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Time time; ///< Timestamp of the measurement. uint8_t frame_id = 0; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). Vector3d position; ///< ECEF position [m]. Vector3f uncertainty; ///< ECEF position uncertainty [m]. Cannot be 0 unless the corresponding valid flags are 0. ValidFlags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_POS_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EcefPos"; static constexpr const char* DOC_NAME = "ECEF Position"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time,frame_id,position,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(position),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const EcefPos& self); -void extract(::microstrain::Serializer& serializer, EcefPos& self); - TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags); ///@} @@ -368,6 +367,7 @@ struct LlhPos { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -386,17 +386,10 @@ struct LlhPos ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool latitude() const { return (value & LATITUDE) > 0; } - void latitude(bool val) { if(val) value |= LATITUDE; else value &= ~LATITUDE; } - bool longitude() const { return (value & LONGITUDE) > 0; } - void longitude(bool val) { if(val) value |= LONGITUDE; else value &= ~LONGITUDE; } - bool height() const { return (value & HEIGHT) > 0; } - void height(bool val) { if(val) value |= HEIGHT; else value &= ~HEIGHT; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Time time; ///< Timestamp of the measurement. uint8_t frame_id = 0; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). double latitude = 0; ///< [deg] @@ -405,29 +398,30 @@ struct LlhPos Vector3f uncertainty; ///< NED position uncertainty. Cannot be 0 unless the corresponding valid flags are 0. ValidFlags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_POS_LLH; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "LlhPos"; static constexpr const char* DOC_NAME = "LLH Position"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time,frame_id,latitude,longitude,height,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(latitude),std::ref(longitude),std::ref(height),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const LlhPos& self); -void extract(::microstrain::Serializer& serializer, LlhPos& self); - TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags); ///@} @@ -440,35 +434,37 @@ TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t f struct Height { + /// Parameters Time time; ///< Timestamp of the measurement. uint8_t frame_id = 0; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). float height = 0; ///< [m] float uncertainty = 0; ///< [m] uint16_t valid_flags = 0; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEIGHT_ABS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Height"; static constexpr const char* DOC_NAME = "Height"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time,frame_id,height,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(height),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const Height& self); -void extract(::microstrain::Serializer& serializer, Height& self); - TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags); ///@} @@ -483,6 +479,7 @@ struct EcefVel { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -501,46 +498,40 @@ struct EcefVel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Time time; ///< Timestamp of the measurement. uint8_t frame_id = 0; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). Vector3f velocity; ///< ECEF velocity [m/s]. Vector3f uncertainty; ///< ECEF velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. ValidFlags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EcefVel"; static constexpr const char* DOC_NAME = "ECEF Velocity"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time,frame_id,velocity,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(velocity),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const EcefVel& self); -void extract(::microstrain::Serializer& serializer, EcefVel& self); - TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags); ///@} @@ -555,6 +546,7 @@ struct NedVel { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -573,46 +565,40 @@ struct NedVel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Time time; ///< Timestamp of the measurement. uint8_t frame_id = 0; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). Vector3f velocity; ///< NED velocity [m/s]. Vector3f uncertainty; ///< NED velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. ValidFlags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_NED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "NedVel"; static constexpr const char* DOC_NAME = "NED Velocity"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time,frame_id,velocity,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(velocity),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const NedVel& self); -void extract(::microstrain::Serializer& serializer, NedVel& self); - TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags); ///@} @@ -628,6 +614,7 @@ struct VehicleFixedFrameVelocity { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -646,46 +633,40 @@ struct VehicleFixedFrameVelocity ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Time time; ///< Timestamp of the measurement. uint8_t frame_id = 0; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). Vector3f velocity; ///< [m/s] Vector3f uncertainty; ///< [m/s] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0. ValidFlags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_ODOM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "VehicleFixedFrameVelocity"; static constexpr const char* DOC_NAME = "Vehicle Frame Velocity"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time,frame_id,velocity,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(velocity),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const VehicleFixedFrameVelocity& self); -void extract(::microstrain::Serializer& serializer, VehicleFixedFrameVelocity& self); - TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags); ///@} @@ -697,35 +678,37 @@ TypedResult vehicleFixedFrameVelocity(C::mip_interfac struct TrueHeading { + /// Parameters Time time; ///< Timestamp of the measurement. uint8_t frame_id = 0; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). float heading = 0; ///< Heading [radians]. Range +/- Pi. float uncertainty = 0; ///< Cannot be 0 unless the valid flags are 0. uint16_t valid_flags = 0; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEADING_TRUE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "TrueHeading"; static constexpr const char* DOC_NAME = "True Heading"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time,frame_id,heading,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(heading),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const TrueHeading& self); -void extract(::microstrain::Serializer& serializer, TrueHeading& self); - TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); ///@} @@ -740,6 +723,7 @@ struct MagneticField { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -758,46 +742,40 @@ struct MagneticField ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Time time; ///< Timestamp of the measurement. uint8_t frame_id = 0; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). Vector3f magnetic_field; ///< [G] Vector3f uncertainty; ///< [G] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0. ValidFlags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_MAGNETIC_FIELD; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagneticField"; static constexpr const char* DOC_NAME = "Magnetic Field"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time,frame_id,magnetic_field,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(magnetic_field),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const MagneticField& self); -void extract(::microstrain::Serializer& serializer, MagneticField& self); - TypedResult magneticField(C::mip_interface& device, const Time& time, uint8_t frameId, const float* magneticField, const float* uncertainty, MagneticField::ValidFlags validFlags); ///@} @@ -810,35 +788,37 @@ TypedResult magneticField(C::mip_interface& device, const Time& t struct Pressure { + /// Parameters Time time; ///< Timestamp of the measurement. uint8_t frame_id = 0; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). float pressure = 0; ///< [mbar] float uncertainty = 0; ///< [mbar] 1-sigma uncertainty. Cannot be 0 unless the valid flags are 0. uint16_t valid_flags = 0; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_PRESSURE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Pressure"; static constexpr const char* DOC_NAME = "Pressure"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time,frame_id,pressure,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time),std::ref(frame_id),std::ref(pressure),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const Pressure& self); -void extract(::microstrain::Serializer& serializer, Pressure& self); - TypedResult pressure(C::mip_interface& device, const Time& time, uint8_t frameId, float pressure, float uncertainty, uint16_t validFlags); ///@} diff --git a/src/cpp/mip/definitions/commands_base.cpp b/src/cpp/mip/definitions/commands_base.cpp index 8796511d2..10671dd3e 100644 --- a/src/cpp/mip/definitions/commands_base.cpp +++ b/src/cpp/mip/definitions/commands_base.cpp @@ -1,8 +1,8 @@ #include "commands_base.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include @@ -14,367 +14,267 @@ struct mip_interface; namespace commands_base { -using ::microstrain::Serializer; -using ::microstrain::insert; -using ::microstrain::extract; using namespace ::mip::C; //////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions +// Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const BaseDeviceInfo& self) +void BaseDeviceInfo::insert(Serializer& serializer) const { - insert(serializer, self.firmware_version); + serializer.insert(firmware_version); for(unsigned int i=0; i < 16; i++) - insert(serializer, self.model_name[i]); + serializer.insert(model_name[i]); for(unsigned int i=0; i < 16; i++) - insert(serializer, self.model_number[i]); + serializer.insert(model_number[i]); for(unsigned int i=0; i < 16; i++) - insert(serializer, self.serial_number[i]); + serializer.insert(serial_number[i]); for(unsigned int i=0; i < 16; i++) - insert(serializer, self.lot_number[i]); + serializer.insert(lot_number[i]); for(unsigned int i=0; i < 16; i++) - insert(serializer, self.device_options[i]); + serializer.insert(device_options[i]); } -void extract(::microstrain::Serializer& serializer, BaseDeviceInfo& self) +void BaseDeviceInfo::extract(Serializer& serializer) { - extract(serializer, self.firmware_version); + serializer.extract(firmware_version); for(unsigned int i=0; i < 16; i++) - extract(serializer, self.model_name[i]); + serializer.extract(model_name[i]); for(unsigned int i=0; i < 16; i++) - extract(serializer, self.model_number[i]); + serializer.extract(model_number[i]); for(unsigned int i=0; i < 16; i++) - extract(serializer, self.serial_number[i]); + serializer.extract(serial_number[i]); for(unsigned int i=0; i < 16; i++) - extract(serializer, self.lot_number[i]); + serializer.extract(lot_number[i]); for(unsigned int i=0; i < 16; i++) - extract(serializer, self.device_options[i]); + serializer.extract(device_options[i]); } - -//////////////////////////////////////////////////////////////////////////////// -// Mip Fields -//////////////////////////////////////////////////////////////////////////////// - -void insert(::microstrain::Serializer& serializer, const Ping& self) +void Ping::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, Ping& self) +void Ping::extract(Serializer& serializer) { (void)serializer; - (void)self; } TypedResult ping(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PING, NULL, 0); } -void insert(::microstrain::Serializer& serializer, const SetIdle& self) +void SetIdle::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, SetIdle& self) +void SetIdle::extract(Serializer& serializer) { (void)serializer; - (void)self; } TypedResult setIdle(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_TO_IDLE, NULL, 0); } -void insert(::microstrain::Serializer& serializer, const GetDeviceInfo& self) +void GetDeviceInfo::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetDeviceInfo& self) +void GetDeviceInfo::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetDeviceInfo::Response& self) -{ - insert(serializer, self.device_info); - -} -void extract(::microstrain::Serializer& serializer, GetDeviceInfo::Response& self) -{ - extract(serializer, self.device_info); - } TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_INFO, NULL, 0, REPLY_DEVICE_INFO, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(deviceInfoOut); - extract(deserializer, *deviceInfoOut); + deserializer.extract(*deviceInfoOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const GetDeviceDescriptors& self) +void GetDeviceDescriptors::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetDeviceDescriptors& self) +void GetDeviceDescriptors::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetDeviceDescriptors::Response& self) -{ - for(unsigned int i=0; i < self.descriptors_count; i++) - insert(serializer, self.descriptors[i]); - -} -void extract(::microstrain::Serializer& serializer, GetDeviceDescriptors::Response& self) -{ - for(self.descriptors_count = 0; (self.descriptors_count < sizeof(self.descriptors)/sizeof(self.descriptors[0])) && (serializer.remaining() > 0); (self.descriptors_count)++) - extract(serializer, self.descriptors[self.descriptors_count]); - } TypedResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_DESCRIPTORS, NULL, 0, REPLY_DEVICE_DESCRIPTORS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) - extract(deserializer, descriptorsOut[*descriptorsOutCount]); + deserializer.extract(descriptorsOut[*descriptorsOutCount]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const BuiltInTest& self) +void BuiltInTest::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, BuiltInTest& self) +void BuiltInTest::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const BuiltInTest::Response& self) -{ - insert(serializer, self.result); - -} -void extract(::microstrain::Serializer& serializer, BuiltInTest::Response& self) -{ - extract(serializer, self.result); - } TypedResult builtInTest(C::mip_interface& device, uint32_t* resultOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_BUILT_IN_TEST, NULL, 0, REPLY_BUILT_IN_TEST, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(resultOut); - extract(deserializer, *resultOut); + deserializer.extract(*resultOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const Resume& self) +void Resume::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, Resume& self) +void Resume::extract(Serializer& serializer) { (void)serializer; - (void)self; } TypedResult resume(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESUME, NULL, 0); } -void insert(::microstrain::Serializer& serializer, const GetExtendedDescriptors& self) +void GetExtendedDescriptors::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetExtendedDescriptors& self) +void GetExtendedDescriptors::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetExtendedDescriptors::Response& self) -{ - for(unsigned int i=0; i < self.descriptors_count; i++) - insert(serializer, self.descriptors[i]); - -} -void extract(::microstrain::Serializer& serializer, GetExtendedDescriptors::Response& self) -{ - for(self.descriptors_count = 0; (self.descriptors_count < sizeof(self.descriptors)/sizeof(self.descriptors[0])) && (serializer.remaining() > 0); (self.descriptors_count)++) - extract(serializer, self.descriptors[self.descriptors_count]); - } TypedResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_EXTENDED_DESCRIPTORS, NULL, 0, REPLY_GET_EXTENDED_DESCRIPTORS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) - extract(deserializer, descriptorsOut[*descriptorsOutCount]); + deserializer.extract(descriptorsOut[*descriptorsOutCount]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const ContinuousBit& self) +void ContinuousBit::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, ContinuousBit& self) +void ContinuousBit::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const ContinuousBit::Response& self) -{ - for(unsigned int i=0; i < 16; i++) - insert(serializer, self.result[i]); - -} -void extract(::microstrain::Serializer& serializer, ContinuousBit::Response& self) -{ - for(unsigned int i=0; i < 16; i++) - extract(serializer, self.result[i]); - } TypedResult continuousBit(C::mip_interface& device, uint8_t* resultOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTINUOUS_BIT, NULL, 0, REPLY_CONTINUOUS_BIT, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(resultOut || (16 == 0)); + assert(resultOut); for(unsigned int i=0; i < 16; i++) - extract(deserializer, resultOut[i]); + deserializer.extract(resultOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const CommSpeed& self) +void CommSpeed::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.port); + serializer.insert(port); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.baud); + serializer.insert(baud); } } -void extract(::microstrain::Serializer& serializer, CommSpeed& self) +void CommSpeed::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.port); + serializer.extract(port); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.baud); + serializer.extract(baud); } } -void insert(::microstrain::Serializer& serializer, const CommSpeed::Response& self) -{ - insert(serializer, self.port); - - insert(serializer, self.baud); - -} -void extract(::microstrain::Serializer& serializer, CommSpeed::Response& self) -{ - extract(serializer, self.port); - - extract(serializer, self.baud); - -} - TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, port); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(port); - insert(serializer, baud); + serializer.insert(baud); assert(serializer.isOk()); @@ -382,38 +282,38 @@ TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, ui } TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, port); + serializer.insert(FunctionSelector::READ); + serializer.insert(port); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length(), REPLY_COMM_SPEED, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, port); + deserializer.extract(port); assert(baudOut); - extract(deserializer, *baudOut); + deserializer.extract(*baudOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, port); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(port); assert(serializer.isOk()); @@ -421,11 +321,11 @@ TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) } TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, port); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(port); assert(serializer.isOk()); @@ -433,64 +333,62 @@ TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) } TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, port); + serializer.insert(FunctionSelector::RESET); + serializer.insert(port); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GpsTimeUpdate& self) +void GpsTimeUpdate::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.field_id); + serializer.insert(field_id); - insert(serializer, self.value); + serializer.insert(value); } } -void extract(::microstrain::Serializer& serializer, GpsTimeUpdate& self) +void GpsTimeUpdate::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.field_id); + serializer.extract(field_id); - extract(serializer, self.value); + serializer.extract(value); } } TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, fieldId); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(fieldId); - insert(serializer, value); + serializer.insert(value); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SoftReset& self) +void SoftReset::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, SoftReset& self) +void SoftReset::extract(Serializer& serializer) { (void)serializer; - (void)self; } TypedResult softReset(C::mip_interface& device) diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index 6d7545633..85fea5d5f 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -3,19 +3,12 @@ #include "common.hpp" #include #include +#include #include #include -#include - -namespace microstrain -{ -class Serializer; -} namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -65,6 +58,7 @@ enum struct BaseDeviceInfo { + /// Parameters uint16_t firmware_version = 0; char model_name[16] = {0}; char model_number[16] = {0}; @@ -72,10 +66,11 @@ struct BaseDeviceInfo char lot_number[16] = {0}; char device_options[16] = {0}; + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const BaseDeviceInfo& self); -void extract(::microstrain::Serializer& serializer, BaseDeviceInfo& self); - enum class TimeFormat : uint8_t { GPS = 1, ///< GPS time, a = week number since 1980, b = time of week in milliseconds. @@ -83,6 +78,7 @@ enum class TimeFormat : uint8_t struct CommandedTestBitsGq7 : Bitfield { + typedef uint32_t Type; enum _enumType : uint32_t { NONE = 0x00000000, @@ -125,66 +121,10 @@ struct CommandedTestBitsGq7 : Bitfield CommandedTestBitsGq7& operator|=(uint32_t val) { return *this = value | val; } CommandedTestBitsGq7& operator&=(uint32_t val) { return *this = value & val; } - bool generalHardwareFault() const { return (value & GENERAL_HARDWARE_FAULT) > 0; } - void generalHardwareFault(bool val) { if(val) value |= GENERAL_HARDWARE_FAULT; else value &= ~GENERAL_HARDWARE_FAULT; } - bool generalFirmwareFault() const { return (value & GENERAL_FIRMWARE_FAULT) > 0; } - void generalFirmwareFault(bool val) { if(val) value |= GENERAL_FIRMWARE_FAULT; else value &= ~GENERAL_FIRMWARE_FAULT; } - bool timingOverload() const { return (value & TIMING_OVERLOAD) > 0; } - void timingOverload(bool val) { if(val) value |= TIMING_OVERLOAD; else value &= ~TIMING_OVERLOAD; } - bool bufferOverrun() const { return (value & BUFFER_OVERRUN) > 0; } - void bufferOverrun(bool val) { if(val) value |= BUFFER_OVERRUN; else value &= ~BUFFER_OVERRUN; } - uint32_t reserved() const { return (value & RESERVED) >> 4; } - void reserved(uint32_t val) { value = (value & ~RESERVED) | (val << 4); } - bool ipcImuFault() const { return (value & IPC_IMU_FAULT) > 0; } - void ipcImuFault(bool val) { if(val) value |= IPC_IMU_FAULT; else value &= ~IPC_IMU_FAULT; } - bool ipcNavFault() const { return (value & IPC_NAV_FAULT) > 0; } - void ipcNavFault(bool val) { if(val) value |= IPC_NAV_FAULT; else value &= ~IPC_NAV_FAULT; } - bool ipcGnssFault() const { return (value & IPC_GNSS_FAULT) > 0; } - void ipcGnssFault(bool val) { if(val) value |= IPC_GNSS_FAULT; else value &= ~IPC_GNSS_FAULT; } - bool commsFault() const { return (value & COMMS_FAULT) > 0; } - void commsFault(bool val) { if(val) value |= COMMS_FAULT; else value &= ~COMMS_FAULT; } - bool imuAccelFault() const { return (value & IMU_ACCEL_FAULT) > 0; } - void imuAccelFault(bool val) { if(val) value |= IMU_ACCEL_FAULT; else value &= ~IMU_ACCEL_FAULT; } - bool imuGyroFault() const { return (value & IMU_GYRO_FAULT) > 0; } - void imuGyroFault(bool val) { if(val) value |= IMU_GYRO_FAULT; else value &= ~IMU_GYRO_FAULT; } - bool imuMagFault() const { return (value & IMU_MAG_FAULT) > 0; } - void imuMagFault(bool val) { if(val) value |= IMU_MAG_FAULT; else value &= ~IMU_MAG_FAULT; } - bool imuPressFault() const { return (value & IMU_PRESS_FAULT) > 0; } - void imuPressFault(bool val) { if(val) value |= IMU_PRESS_FAULT; else value &= ~IMU_PRESS_FAULT; } - uint32_t imuReserved() const { return (value & IMU_RESERVED) >> 16; } - void imuReserved(uint32_t val) { value = (value & ~IMU_RESERVED) | (val << 16); } - bool imuCalError() const { return (value & IMU_CAL_ERROR) > 0; } - void imuCalError(bool val) { if(val) value |= IMU_CAL_ERROR; else value &= ~IMU_CAL_ERROR; } - bool imuGeneralFault() const { return (value & IMU_GENERAL_FAULT) > 0; } - void imuGeneralFault(bool val) { if(val) value |= IMU_GENERAL_FAULT; else value &= ~IMU_GENERAL_FAULT; } - uint32_t filtReserved() const { return (value & FILT_RESERVED) >> 20; } - void filtReserved(uint32_t val) { value = (value & ~FILT_RESERVED) | (val << 20); } - bool filtSolutionFault() const { return (value & FILT_SOLUTION_FAULT) > 0; } - void filtSolutionFault(bool val) { if(val) value |= FILT_SOLUTION_FAULT; else value &= ~FILT_SOLUTION_FAULT; } - bool filtGeneralFault() const { return (value & FILT_GENERAL_FAULT) > 0; } - void filtGeneralFault(bool val) { if(val) value |= FILT_GENERAL_FAULT; else value &= ~FILT_GENERAL_FAULT; } - bool gnssReceiver1Fault() const { return (value & GNSS_RECEIVER1_FAULT) > 0; } - void gnssReceiver1Fault(bool val) { if(val) value |= GNSS_RECEIVER1_FAULT; else value &= ~GNSS_RECEIVER1_FAULT; } - bool gnssAntenna1Fault() const { return (value & GNSS_ANTENNA1_FAULT) > 0; } - void gnssAntenna1Fault(bool val) { if(val) value |= GNSS_ANTENNA1_FAULT; else value &= ~GNSS_ANTENNA1_FAULT; } - bool gnssReceiver2Fault() const { return (value & GNSS_RECEIVER2_FAULT) > 0; } - void gnssReceiver2Fault(bool val) { if(val) value |= GNSS_RECEIVER2_FAULT; else value &= ~GNSS_RECEIVER2_FAULT; } - bool gnssAntenna2Fault() const { return (value & GNSS_ANTENNA2_FAULT) > 0; } - void gnssAntenna2Fault(bool val) { if(val) value |= GNSS_ANTENNA2_FAULT; else value &= ~GNSS_ANTENNA2_FAULT; } - bool gnssRtcmFailure() const { return (value & GNSS_RTCM_FAILURE) > 0; } - void gnssRtcmFailure(bool val) { if(val) value |= GNSS_RTCM_FAILURE; else value &= ~GNSS_RTCM_FAILURE; } - bool gnssRtkFault() const { return (value & GNSS_RTK_FAULT) > 0; } - void gnssRtkFault(bool val) { if(val) value |= GNSS_RTK_FAULT; else value &= ~GNSS_RTK_FAULT; } - bool gnssSolutionFault() const { return (value & GNSS_SOLUTION_FAULT) > 0; } - void gnssSolutionFault(bool val) { if(val) value |= GNSS_SOLUTION_FAULT; else value &= ~GNSS_SOLUTION_FAULT; } - bool gnssGeneralFault() const { return (value & GNSS_GENERAL_FAULT) > 0; } - void gnssGeneralFault(bool val) { if(val) value |= GNSS_GENERAL_FAULT; else value &= ~GNSS_GENERAL_FAULT; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// @@ -201,34 +141,30 @@ struct CommandedTestBitsGq7 : Bitfield struct Ping { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_PING; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Ping"; static constexpr const char* DOC_NAME = "Ping"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - - auto as_tuple() const + + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } - - auto asTuple() const { return as_tuple(); } - auto asTuple() { return as_tuple(); } - + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const Ping& self); -void extract(::microstrain::Serializer& serializer, Ping& self); - TypedResult ping(C::mip_interface& device); ///@} @@ -245,34 +181,30 @@ TypedResult ping(C::mip_interface& device); struct SetIdle { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_SET_TO_IDLE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SetIdle"; static constexpr const char* DOC_NAME = "Set to idle"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } - - auto asTuple() const { return as_tuple(); } - auto asTuple() { return as_tuple(); } - + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const SetIdle& self); -void extract(::microstrain::Serializer& serializer, SetIdle& self); - TypedResult setIdle(C::mip_interface& device); ///@} @@ -285,55 +217,57 @@ TypedResult setIdle(C::mip_interface& device); struct GetDeviceInfo { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_GET_DEVICE_INFO; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetDeviceInfo"; static constexpr const char* DOC_NAME = "Get device information"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } - - auto asTuple() const { return as_tuple(); } - auto asTuple() { return as_tuple(); } - + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + BaseDeviceInfo device_info; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_DEVICE_INFO; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetDeviceInfo::Response"; static constexpr const char* DOC_NAME = "Get device information Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - BaseDeviceInfo device_info; - + auto asTuple() const + { + return std::make_tuple(device_info); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(device_info)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetDeviceInfo& self); -void extract(::microstrain::Serializer& serializer, GetDeviceInfo& self); - -void insert(::microstrain::Serializer& serializer, const GetDeviceInfo::Response& self); -void extract(::microstrain::Serializer& serializer, GetDeviceInfo::Response& self); - TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut); ///@} @@ -349,53 +283,58 @@ TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInf struct GetDeviceDescriptors { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_GET_DEVICE_DESCRIPTORS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetDeviceDescriptors"; static constexpr const char* DOC_NAME = "Get device descriptors"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } - + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint16_t descriptors[253] = {0}; + uint8_t descriptors_count = 0; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_DEVICE_DESCRIPTORS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetDeviceDescriptors::Response"; static constexpr const char* DOC_NAME = "Get device descriptors Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000001; - uint16_t descriptors[253] = {0}; - uint8_t descriptors_count = 0; - + auto asTuple() const + { + return std::make_tuple(descriptors,descriptors_count); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(descriptors),std::ref(descriptors_count)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetDeviceDescriptors& self); -void extract(::microstrain::Serializer& serializer, GetDeviceDescriptors& self); - -void insert(::microstrain::Serializer& serializer, const GetDeviceDescriptors::Response& self); -void extract(::microstrain::Serializer& serializer, GetDeviceDescriptors::Response& self); - TypedResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); ///@} @@ -413,51 +352,57 @@ TypedResult getDeviceDescriptors(C::mip_interface& device, struct BuiltInTest { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_BUILT_IN_TEST; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "BuiltInTest"; static constexpr const char* DOC_NAME = "Built in test"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint32_t result = 0; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_BUILT_IN_TEST; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "BuiltInTest::Response"; static constexpr const char* DOC_NAME = "Built in test Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint32_t result = 0; - + auto asTuple() const + { + return std::make_tuple(result); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(result)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const BuiltInTest& self); -void extract(::microstrain::Serializer& serializer, BuiltInTest& self); - -void insert(::microstrain::Serializer& serializer, const BuiltInTest::Response& self); -void extract(::microstrain::Serializer& serializer, BuiltInTest::Response& self); - TypedResult builtInTest(C::mip_interface& device, uint32_t* resultOut); ///@} @@ -472,30 +417,30 @@ TypedResult builtInTest(C::mip_interface& device, uint32_t* resultO struct Resume { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_RESUME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Resume"; static constexpr const char* DOC_NAME = "Resume"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const Resume& self); -void extract(::microstrain::Serializer& serializer, Resume& self); - TypedResult resume(C::mip_interface& device); ///@} @@ -511,52 +456,58 @@ TypedResult resume(C::mip_interface& device); struct GetExtendedDescriptors { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_GET_EXTENDED_DESCRIPTORS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetExtendedDescriptors"; static constexpr const char* DOC_NAME = "Get device descriptors (extended)"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint16_t descriptors[253] = {0}; + uint8_t descriptors_count = 0; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_GET_EXTENDED_DESCRIPTORS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetExtendedDescriptors::Response"; static constexpr const char* DOC_NAME = "Get device descriptors (extended) Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000001; - uint16_t descriptors[253] = {0}; - uint8_t descriptors_count = 0; - + auto asTuple() const + { + return std::make_tuple(descriptors,descriptors_count); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(descriptors),std::ref(descriptors_count)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetExtendedDescriptors& self); -void extract(::microstrain::Serializer& serializer, GetExtendedDescriptors& self); - -void insert(::microstrain::Serializer& serializer, const GetExtendedDescriptors::Response& self); -void extract(::microstrain::Serializer& serializer, GetExtendedDescriptors::Response& self); - TypedResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount); ///@} @@ -571,51 +522,57 @@ TypedResult getExtendedDescriptors(C::mip_interface& dev struct ContinuousBit { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_CONTINUOUS_BIT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ContinuousBit"; static constexpr const char* DOC_NAME = "Continuous built-in test"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t result[16] = {0}; ///< Device-specific bitfield (128 bits). See device user manual. Bits are least-significant-byte first. For example, bit 0 is located at bit 0 of result[0], bit 1 is located at bit 1 of result[0], bit 8 is located at bit 0 of result[1], and bit 127 is located at bit 7 of result[15]. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_CONTINUOUS_BIT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ContinuousBit::Response"; static constexpr const char* DOC_NAME = "Continuous built-in test Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t result[16] = {0}; ///< Device-specific bitfield (128 bits). See device user manual. Bits are least-significant-byte first. For example, bit 0 is located at bit 0 of result[0], bit 1 is located at bit 1 of result[0], bit 8 is located at bit 0 of result[1], and bit 127 is located at bit 7 of result[15]. - + auto asTuple() const + { + return std::make_tuple(result); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(result)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ContinuousBit& self); -void extract(::microstrain::Serializer& serializer, ContinuousBit& self); - -void insert(::microstrain::Serializer& serializer, const ContinuousBit::Response& self); -void extract(::microstrain::Serializer& serializer, ContinuousBit::Response& self); - TypedResult continuousBit(C::mip_interface& device, uint8_t* resultOut); ///@} @@ -642,35 +599,29 @@ TypedResult continuousBit(C::mip_interface& device, uint8_t* resu struct CommSpeed { static constexpr const uint32_t ALL_PORTS = 0; + /// Parameters FunctionSelector function = static_cast(0); uint8_t port = 0; ///< Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details. uint32_t baud = 0; ///< Port baud rate. Must be a supported rate. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_COMM_SPEED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CommSpeed"; static constexpr const char* DOC_NAME = "Comm Port Speed"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - - auto as_tuple() const + + auto asTuple() const { return std::make_tuple(port,baud); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(port),std::ref(baud)); } - + static CommSpeed create_sld_all(::mip::FunctionSelector function) { CommSpeed cmd; @@ -678,36 +629,41 @@ struct CommSpeed cmd.port = 0; return cmd; } - - auto asTuple() const { return as_tuple(); } - auto asTuple() { return as_tuple(); } - + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t port = 0; ///< Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details. + uint32_t baud = 0; ///< Port baud rate. Must be a supported rate. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::REPLY_COMM_SPEED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CommSpeed::Response"; static constexpr const char* DOC_NAME = "Comm Port Speed Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t port = 0; ///< Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details. - uint32_t baud = 0; ///< Port baud rate. Must be a supported rate. - + auto asTuple() const + { + return std::make_tuple(port,baud); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(port),std::ref(baud)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const CommSpeed& self); -void extract(::microstrain::Serializer& serializer, CommSpeed& self); - -void insert(::microstrain::Serializer& serializer, const CommSpeed::Response& self); -void extract(::microstrain::Serializer& serializer, CommSpeed::Response& self); - TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud); TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut); TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port); @@ -733,30 +689,25 @@ struct GpsTimeUpdate TIME_OF_WEEK = 2, ///< Time of week in seconds. }; + /// Parameters FunctionSelector function = static_cast(0); FieldId field_id = static_cast(0); ///< Determines how to interpret value. uint32_t value = 0; ///< Week number or time of week, depending on the field_id. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_GPS_TIME_UPDATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsTimeUpdate"; static constexpr const char* DOC_NAME = "GPS Time Update Command"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x0000; - static constexpr const uint32_t SAVE_PARAMS = 0x0000; - static constexpr const uint32_t LOAD_PARAMS = 0x0000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(field_id,value); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(field_id),std::ref(value)); } @@ -768,11 +719,12 @@ struct GpsTimeUpdate return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const GpsTimeUpdate& self); -void extract(::microstrain::Serializer& serializer, GpsTimeUpdate& self); - TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value); ///@} @@ -787,30 +739,30 @@ TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeU struct SoftReset { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_base::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_base::CMD_SOFT_RESET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SoftReset"; static constexpr const char* DOC_NAME = "Reset device"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const SoftReset& self); -void extract(::microstrain::Serializer& serializer, SoftReset& self); - TypedResult softReset(C::mip_interface& device); ///@} diff --git a/src/cpp/mip/definitions/commands_filter.cpp b/src/cpp/mip/definitions/commands_filter.cpp index f823e73ec..f0f6c80d4 100644 --- a/src/cpp/mip/definitions/commands_filter.cpp +++ b/src/cpp/mip/definitions/commands_filter.cpp @@ -1,123 +1,100 @@ #include "commands_filter.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace commands_filter { -using ::microstrain::Serializer; -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const Reset& self) +void Reset::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, Reset& self) +void Reset::extract(Serializer& serializer) { (void)serializer; - (void)self; } TypedResult reset(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESET_FILTER, NULL, 0); } -void insert(::microstrain::Serializer& serializer, const SetInitialAttitude& self) +void SetInitialAttitude::insert(Serializer& serializer) const { - insert(serializer, self.roll); + serializer.insert(roll); - insert(serializer, self.pitch); + serializer.insert(pitch); - insert(serializer, self.heading); + serializer.insert(heading); } -void extract(::microstrain::Serializer& serializer, SetInitialAttitude& self) +void SetInitialAttitude::extract(Serializer& serializer) { - extract(serializer, self.roll); + serializer.extract(roll); - extract(serializer, self.pitch); + serializer.extract(pitch); - extract(serializer, self.heading); + serializer.extract(heading); } TypedResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, roll); + serializer.insert(roll); - insert(serializer, pitch); + serializer.insert(pitch); - insert(serializer, heading); + serializer.insert(heading); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_ATTITUDE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const EstimationControl& self) +void EstimationControl::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); } } -void extract(::microstrain::Serializer& serializer, EstimationControl& self) +void EstimationControl::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); } } -void insert(::microstrain::Serializer& serializer, const EstimationControl::Response& self) -{ - insert(serializer, self.enable); - -} -void extract(::microstrain::Serializer& serializer, EstimationControl::Response& self) -{ - extract(serializer, self.enable); - -} - TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); assert(serializer.isOk()); @@ -125,252 +102,235 @@ TypedResult writeEstimationControl(C::mip_interface& device, } TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length(), REPLY_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveEstimationControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); } TypedResult loadEstimationControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); } TypedResult defaultEstimationControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ExternalGnssUpdate& self) +void ExternalGnssUpdate::insert(Serializer& serializer) const { - insert(serializer, self.gps_time); + serializer.insert(gps_time); - insert(serializer, self.gps_week); + serializer.insert(gps_week); - insert(serializer, self.latitude); + serializer.insert(latitude); - insert(serializer, self.longitude); + serializer.insert(longitude); - insert(serializer, self.height); + serializer.insert(height); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.velocity[i]); + serializer.insert(velocity); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.pos_uncertainty[i]); + serializer.insert(pos_uncertainty); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.vel_uncertainty[i]); + serializer.insert(vel_uncertainty); } -void extract(::microstrain::Serializer& serializer, ExternalGnssUpdate& self) +void ExternalGnssUpdate::extract(Serializer& serializer) { - extract(serializer, self.gps_time); + serializer.extract(gps_time); - extract(serializer, self.gps_week); + serializer.extract(gps_week); - extract(serializer, self.latitude); + serializer.extract(latitude); - extract(serializer, self.longitude); + serializer.extract(longitude); - extract(serializer, self.height); + serializer.extract(height); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.velocity[i]); + serializer.extract(velocity); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.pos_uncertainty[i]); + serializer.extract(pos_uncertainty); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.vel_uncertainty[i]); + serializer.extract(vel_uncertainty); } TypedResult externalGnssUpdate(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, double latitude, double longitude, double height, const float* velocity, const float* posUncertainty, const float* velUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, gpsTime); + serializer.insert(gpsTime); - insert(serializer, gpsWeek); + serializer.insert(gpsWeek); - insert(serializer, latitude); + serializer.insert(latitude); - insert(serializer, longitude); + serializer.insert(longitude); - insert(serializer, height); + serializer.insert(height); - assert(velocity || (3 == 0)); + assert(velocity); for(unsigned int i=0; i < 3; i++) - insert(serializer, velocity[i]); + serializer.insert(velocity[i]); - assert(posUncertainty || (3 == 0)); + assert(posUncertainty); for(unsigned int i=0; i < 3; i++) - insert(serializer, posUncertainty[i]); + serializer.insert(posUncertainty[i]); - assert(velUncertainty || (3 == 0)); + assert(velUncertainty); for(unsigned int i=0; i < 3; i++) - insert(serializer, velUncertainty[i]); + serializer.insert(velUncertainty[i]); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ExternalHeadingUpdate& self) +void ExternalHeadingUpdate::insert(Serializer& serializer) const { - insert(serializer, self.heading); + serializer.insert(heading); - insert(serializer, self.heading_uncertainty); + serializer.insert(heading_uncertainty); - insert(serializer, self.type); + serializer.insert(type); } -void extract(::microstrain::Serializer& serializer, ExternalHeadingUpdate& self) +void ExternalHeadingUpdate::extract(Serializer& serializer) { - extract(serializer, self.heading); + serializer.extract(heading); - extract(serializer, self.heading_uncertainty); + serializer.extract(heading_uncertainty); - extract(serializer, self.type); + serializer.extract(type); } TypedResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, heading); + serializer.insert(heading); - insert(serializer, headingUncertainty); + serializer.insert(headingUncertainty); - insert(serializer, type); + serializer.insert(type); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ExternalHeadingUpdateWithTime& self) +void ExternalHeadingUpdateWithTime::insert(Serializer& serializer) const { - insert(serializer, self.gps_time); + serializer.insert(gps_time); - insert(serializer, self.gps_week); + serializer.insert(gps_week); - insert(serializer, self.heading); + serializer.insert(heading); - insert(serializer, self.heading_uncertainty); + serializer.insert(heading_uncertainty); - insert(serializer, self.type); + serializer.insert(type); } -void extract(::microstrain::Serializer& serializer, ExternalHeadingUpdateWithTime& self) +void ExternalHeadingUpdateWithTime::extract(Serializer& serializer) { - extract(serializer, self.gps_time); + serializer.extract(gps_time); - extract(serializer, self.gps_week); + serializer.extract(gps_week); - extract(serializer, self.heading); + serializer.extract(heading); - extract(serializer, self.heading_uncertainty); + serializer.extract(heading_uncertainty); - extract(serializer, self.type); + serializer.extract(type); } TypedResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, gpsTime); + serializer.insert(gpsTime); - insert(serializer, gpsWeek); + serializer.insert(gpsWeek); - insert(serializer, heading); + serializer.insert(heading); - insert(serializer, headingUncertainty); + serializer.insert(headingUncertainty); - insert(serializer, type); + serializer.insert(type); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const TareOrientation& self) +void TareOrientation::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.axes); + serializer.insert(axes); } } -void extract(::microstrain::Serializer& serializer, TareOrientation& self) +void TareOrientation::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.axes); + serializer.extract(axes); } } -void insert(::microstrain::Serializer& serializer, const TareOrientation::Response& self) -{ - insert(serializer, self.axes); - -} -void extract(::microstrain::Serializer& serializer, TareOrientation::Response& self) -{ - extract(serializer, self.axes); - -} - TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, axes); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(axes); assert(serializer.isOk()); @@ -378,96 +338,85 @@ TypedResult writeTareOrientation(C::mip_interface& device, Tare } TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length(), REPLY_TARE_ORIENTATION, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(axesOut); - extract(deserializer, *axesOut); + deserializer.extract(*axesOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveTareOrientation(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); } TypedResult loadTareOrientation(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultTareOrientation(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const VehicleDynamicsMode& self) +void VehicleDynamicsMode::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.mode); + serializer.insert(mode); } } -void extract(::microstrain::Serializer& serializer, VehicleDynamicsMode& self) +void VehicleDynamicsMode::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.mode); + serializer.extract(mode); } } -void insert(::microstrain::Serializer& serializer, const VehicleDynamicsMode::Response& self) -{ - insert(serializer, self.mode); - -} -void extract(::microstrain::Serializer& serializer, VehicleDynamicsMode::Response& self) -{ - extract(serializer, self.mode); - -} - TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, mode); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(mode); assert(serializer.isOk()); @@ -475,116 +424,97 @@ TypedResult writeVehicleDynamicsMode(C::mip_interface& devi } TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length(), REPLY_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(modeOut); - extract(deserializer, *modeOut); + deserializer.extract(*modeOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveVehicleDynamicsMode(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); } TypedResult loadVehicleDynamicsMode(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); } TypedResult defaultVehicleDynamicsMode(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationEuler& self) +void SensorToVehicleRotationEuler::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.roll); + serializer.insert(roll); - insert(serializer, self.pitch); + serializer.insert(pitch); - insert(serializer, self.yaw); + serializer.insert(yaw); } } -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationEuler& self) +void SensorToVehicleRotationEuler::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.roll); + serializer.extract(roll); - extract(serializer, self.pitch); + serializer.extract(pitch); - extract(serializer, self.yaw); + serializer.extract(yaw); } } -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationEuler::Response& self) -{ - insert(serializer, self.roll); - - insert(serializer, self.pitch); - - insert(serializer, self.yaw); - -} -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationEuler::Response& self) -{ - extract(serializer, self.roll); - - extract(serializer, self.pitch); - - extract(serializer, self.yaw); - -} - TypedResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, roll); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(roll); - insert(serializer, pitch); + serializer.insert(pitch); - insert(serializer, yaw); + serializer.insert(yaw); assert(serializer.isOk()); @@ -592,108 +522,93 @@ TypedResult writeSensorToVehicleRotationEuler(C::m } TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(rollOut); - extract(deserializer, *rollOut); + deserializer.extract(*rollOut); assert(pitchOut); - extract(deserializer, *pitchOut); + deserializer.extract(*pitchOut); assert(yawOut); - extract(deserializer, *yawOut); + deserializer.extract(*yawOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSensorToVehicleRotationEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); } TypedResult loadSensorToVehicleRotationEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensorToVehicleRotationEuler(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationDcm& self) +void SensorToVehicleRotationDcm::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.dcm[i]); + serializer.insert(dcm); } } -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationDcm& self) +void SensorToVehicleRotationDcm::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.dcm[i]); + serializer.extract(dcm); } } -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationDcm::Response& self) -{ - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.dcm[i]); - -} -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationDcm::Response& self) -{ - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.dcm[i]); - -} - TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(dcm || (9 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(dcm); for(unsigned int i=0; i < 9; i++) - insert(serializer, dcm[i]); + serializer.insert(dcm[i]); assert(serializer.isOk()); @@ -701,103 +616,88 @@ TypedResult writeSensorToVehicleRotationDcm(C::mip_i } TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(dcmOut || (9 == 0)); + assert(dcmOut); for(unsigned int i=0; i < 9; i++) - extract(deserializer, dcmOut[i]); + deserializer.extract(dcmOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSensorToVehicleRotationDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); } TypedResult loadSensorToVehicleRotationDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensorToVehicleRotationDcm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationQuaternion& self) +void SensorToVehicleRotationQuaternion::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.quat[i]); + serializer.insert(quat); } } -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationQuaternion& self) +void SensorToVehicleRotationQuaternion::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.quat[i]); + serializer.extract(quat); } } -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationQuaternion::Response& self) -{ - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.quat[i]); - -} -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationQuaternion::Response& self) -{ - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.quat[i]); - -} - TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(quat || (4 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(quat); for(unsigned int i=0; i < 4; i++) - insert(serializer, quat[i]); + serializer.insert(quat[i]); assert(serializer.isOk()); @@ -805,103 +705,88 @@ TypedResult writeSensorToVehicleRotationQuate } TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(quatOut || (4 == 0)); + assert(quatOut); for(unsigned int i=0; i < 4; i++) - extract(deserializer, quatOut[i]); + deserializer.extract(quatOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); } TypedResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SensorToVehicleOffset& self) +void SensorToVehicleOffset::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset[i]); + serializer.insert(offset); } } -void extract(::microstrain::Serializer& serializer, SensorToVehicleOffset& self) +void SensorToVehicleOffset::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset[i]); + serializer.extract(offset); } } -void insert(::microstrain::Serializer& serializer, const SensorToVehicleOffset::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset[i]); - -} -void extract(::microstrain::Serializer& serializer, SensorToVehicleOffset::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset[i]); - -} - TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(offset || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(offset); for(unsigned int i=0; i < 3; i++) - insert(serializer, offset[i]); + serializer.insert(offset[i]); assert(serializer.isOk()); @@ -909,103 +794,88 @@ TypedResult writeSensorToVehicleOffset(C::mip_interface& } TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(offsetOut || (3 == 0)); + assert(offsetOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, offsetOut[i]); + deserializer.extract(offsetOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSensorToVehicleOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult loadSensorToVehicleOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult defaultSensorToVehicleOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AntennaOffset& self) +void AntennaOffset::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset[i]); + serializer.insert(offset); } } -void extract(::microstrain::Serializer& serializer, AntennaOffset& self) +void AntennaOffset::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset[i]); + serializer.extract(offset); } } -void insert(::microstrain::Serializer& serializer, const AntennaOffset::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset[i]); - -} -void extract(::microstrain::Serializer& serializer, AntennaOffset::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset[i]); - -} - TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(offset || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(offset); for(unsigned int i=0; i < 3; i++) - insert(serializer, offset[i]); + serializer.insert(offset[i]); assert(serializer.isOk()); @@ -1013,97 +883,86 @@ TypedResult writeAntennaOffset(C::mip_interface& device, const fl } TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_ANTENNA_OFFSET, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(offsetOut || (3 == 0)); + assert(offsetOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, offsetOut[i]); + deserializer.extract(offsetOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAntennaOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult loadAntennaOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } TypedResult defaultAntennaOffset(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GnssSource& self) +void GnssSource::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.source); + serializer.insert(source); } } -void extract(::microstrain::Serializer& serializer, GnssSource& self) +void GnssSource::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.source); + serializer.extract(source); } } -void insert(::microstrain::Serializer& serializer, const GnssSource::Response& self) -{ - insert(serializer, self.source); - -} -void extract(::microstrain::Serializer& serializer, GnssSource::Response& self) -{ - extract(serializer, self.source); - -} - TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(source); assert(serializer.isOk()); @@ -1111,96 +970,85 @@ TypedResult writeGnssSource(C::mip_interface& device, GnssSource::So } TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_GNSS_SOURCE_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(sourceOut); - extract(deserializer, *sourceOut); + deserializer.extract(*sourceOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGnssSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadGnssSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultGnssSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const HeadingSource& self) +void HeadingSource::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.source); + serializer.insert(source); } } -void extract(::microstrain::Serializer& serializer, HeadingSource& self) +void HeadingSource::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.source); + serializer.extract(source); } } -void insert(::microstrain::Serializer& serializer, const HeadingSource::Response& self) -{ - insert(serializer, self.source); - -} -void extract(::microstrain::Serializer& serializer, HeadingSource::Response& self) -{ - extract(serializer, self.source); - -} - TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(source); assert(serializer.isOk()); @@ -1208,96 +1056,85 @@ TypedResult writeHeadingSource(C::mip_interface& device, HeadingS } TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_HEADING_UPDATE_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(sourceOut); - extract(deserializer, *sourceOut); + deserializer.extract(*sourceOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveHeadingSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadHeadingSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultHeadingSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AutoInitControl& self) +void AutoInitControl::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); } } -void extract(::microstrain::Serializer& serializer, AutoInitControl& self) +void AutoInitControl::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); } } -void insert(::microstrain::Serializer& serializer, const AutoInitControl::Response& self) -{ - insert(serializer, self.enable); - -} -void extract(::microstrain::Serializer& serializer, AutoInitControl::Response& self) -{ - extract(serializer, self.enable); - -} - TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); assert(serializer.isOk()); @@ -1305,102 +1142,87 @@ TypedResult writeAutoInitControl(C::mip_interface& device, uint } TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_AUTOINIT_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAutoInitControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAutoInitControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAutoInitControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AccelNoise& self) +void AccelNoise::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); + serializer.insert(noise); } } -void extract(::microstrain::Serializer& serializer, AccelNoise& self) +void AccelNoise::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); + serializer.extract(noise); } } -void insert(::microstrain::Serializer& serializer, const AccelNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); - -} -void extract(::microstrain::Serializer& serializer, AccelNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); - -} - TypedResult writeAccelNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(noise || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(noise); for(unsigned int i=0; i < 3; i++) - insert(serializer, noise[i]); + serializer.insert(noise[i]); assert(serializer.isOk()); @@ -1408,103 +1230,88 @@ TypedResult writeAccelNoise(C::mip_interface& device, const float* n } TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_NOISE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(noiseOut || (3 == 0)); + assert(noiseOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, noiseOut[i]); + deserializer.extract(noiseOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAccelNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadAccelNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultAccelNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GyroNoise& self) +void GyroNoise::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); + serializer.insert(noise); } } -void extract(::microstrain::Serializer& serializer, GyroNoise& self) +void GyroNoise::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); + serializer.extract(noise); } } -void insert(::microstrain::Serializer& serializer, const GyroNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); - -} -void extract(::microstrain::Serializer& serializer, GyroNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); - -} - TypedResult writeGyroNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(noise || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(noise); for(unsigned int i=0; i < 3; i++) - insert(serializer, noise[i]); + serializer.insert(noise[i]); assert(serializer.isOk()); @@ -1512,119 +1319,96 @@ TypedResult writeGyroNoise(C::mip_interface& device, const float* noi } TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length(), REPLY_GYRO_NOISE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(noiseOut || (3 == 0)); + assert(noiseOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, noiseOut[i]); + deserializer.extract(noiseOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGyroNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadGyroNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultGyroNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AccelBiasModel& self) +void AccelBiasModel::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.beta[i]); + serializer.insert(beta); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); + serializer.insert(noise); } } -void extract(::microstrain::Serializer& serializer, AccelBiasModel& self) +void AccelBiasModel::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.beta[i]); + serializer.extract(beta); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); + serializer.extract(noise); } } -void insert(::microstrain::Serializer& serializer, const AccelBiasModel::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.beta[i]); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); - -} -void extract(::microstrain::Serializer& serializer, AccelBiasModel::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.beta[i]); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); - -} - TypedResult writeAccelBiasModel(C::mip_interface& device, const float* beta, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(beta || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(beta); for(unsigned int i=0; i < 3; i++) - insert(serializer, beta[i]); + serializer.insert(beta[i]); - assert(noise || (3 == 0)); + assert(noise); for(unsigned int i=0; i < 3; i++) - insert(serializer, noise[i]); + serializer.insert(noise[i]); assert(serializer.isOk()); @@ -1632,123 +1416,100 @@ TypedResult writeAccelBiasModel(C::mip_interface& device, const } TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_BIAS_MODEL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(betaOut || (3 == 0)); + assert(betaOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, betaOut[i]); + deserializer.extract(betaOut[i]); - assert(noiseOut || (3 == 0)); + assert(noiseOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, noiseOut[i]); + deserializer.extract(noiseOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAccelBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult loadAccelBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAccelBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GyroBiasModel& self) +void GyroBiasModel::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.beta[i]); + serializer.insert(beta); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); + serializer.insert(noise); } } -void extract(::microstrain::Serializer& serializer, GyroBiasModel& self) +void GyroBiasModel::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.beta[i]); + serializer.extract(beta); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); + serializer.extract(noise); } } -void insert(::microstrain::Serializer& serializer, const GyroBiasModel::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.beta[i]); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); - -} -void extract(::microstrain::Serializer& serializer, GyroBiasModel::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.beta[i]); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); - -} - TypedResult writeGyroBiasModel(C::mip_interface& device, const float* beta, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(beta || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(beta); for(unsigned int i=0; i < 3; i++) - insert(serializer, beta[i]); + serializer.insert(beta[i]); - assert(noise || (3 == 0)); + assert(noise); for(unsigned int i=0; i < 3; i++) - insert(serializer, noise[i]); + serializer.insert(noise[i]); assert(serializer.isOk()); @@ -1756,101 +1517,90 @@ TypedResult writeGyroBiasModel(C::mip_interface& device, const fl } TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_MODEL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(betaOut || (3 == 0)); + assert(betaOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, betaOut[i]); + deserializer.extract(betaOut[i]); - assert(noiseOut || (3 == 0)); + assert(noiseOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, noiseOut[i]); + deserializer.extract(noiseOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGyroBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult loadGyroBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } TypedResult defaultGyroBiasModel(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AltitudeAiding& self) +void AltitudeAiding::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.selector); + serializer.insert(selector); } } -void extract(::microstrain::Serializer& serializer, AltitudeAiding& self) +void AltitudeAiding::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.selector); + serializer.extract(selector); } } -void insert(::microstrain::Serializer& serializer, const AltitudeAiding::Response& self) -{ - insert(serializer, self.selector); - -} -void extract(::microstrain::Serializer& serializer, AltitudeAiding::Response& self) -{ - extract(serializer, self.selector); - -} - TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, selector); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(selector); assert(serializer.isOk()); @@ -1858,96 +1608,85 @@ TypedResult writeAltitudeAiding(C::mip_interface& device, Altitu } TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(selectorOut); - extract(deserializer, *selectorOut); + deserializer.extract(*selectorOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAltitudeAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAltitudeAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAltitudeAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const PitchRollAiding& self) +void PitchRollAiding::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.source); + serializer.insert(source); } } -void extract(::microstrain::Serializer& serializer, PitchRollAiding& self) +void PitchRollAiding::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.source); + serializer.extract(source); } } -void insert(::microstrain::Serializer& serializer, const PitchRollAiding::Response& self) -{ - insert(serializer, self.source); - -} -void extract(::microstrain::Serializer& serializer, PitchRollAiding::Response& self) -{ - extract(serializer, self.source); - -} - TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(source); assert(serializer.isOk()); @@ -1955,106 +1694,91 @@ TypedResult writePitchRollAiding(C::mip_interface& device, Pitc } TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(sourceOut); - extract(deserializer, *sourceOut); + deserializer.extract(*sourceOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult savePitchRollAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadPitchRollAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultPitchRollAiding(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AutoZupt& self) +void AutoZupt::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); - insert(serializer, self.threshold); + serializer.insert(threshold); } } -void extract(::microstrain::Serializer& serializer, AutoZupt& self) +void AutoZupt::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); - extract(serializer, self.threshold); + serializer.extract(threshold); } } -void insert(::microstrain::Serializer& serializer, const AutoZupt::Response& self) -{ - insert(serializer, self.enable); - - insert(serializer, self.threshold); - -} -void extract(::microstrain::Serializer& serializer, AutoZupt::Response& self) -{ - extract(serializer, self.enable); - - extract(serializer, self.threshold); - -} - TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); - insert(serializer, threshold); + serializer.insert(threshold); assert(serializer.isOk()); @@ -2062,109 +1786,94 @@ TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, fl } TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ZUPT_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); assert(thresholdOut); - extract(deserializer, *thresholdOut); + deserializer.extract(*thresholdOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAutoZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAutoZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAutoZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AutoAngularZupt& self) +void AutoAngularZupt::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); - insert(serializer, self.threshold); + serializer.insert(threshold); } } -void extract(::microstrain::Serializer& serializer, AutoAngularZupt& self) +void AutoAngularZupt::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); - extract(serializer, self.threshold); + serializer.extract(threshold); } } -void insert(::microstrain::Serializer& serializer, const AutoAngularZupt::Response& self) -{ - insert(serializer, self.enable); - - insert(serializer, self.threshold); - -} -void extract(::microstrain::Serializer& serializer, AutoAngularZupt::Response& self) -{ - extract(serializer, self.enable); - - extract(serializer, self.threshold); - -} - TypedResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); - insert(serializer, threshold); + serializer.insert(threshold); assert(serializer.isOk()); @@ -2172,166 +1881,147 @@ TypedResult writeAutoAngularZupt(C::mip_interface& device, uint } TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); assert(thresholdOut); - extract(deserializer, *thresholdOut); + deserializer.extract(*thresholdOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAutoAngularZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAutoAngularZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAutoAngularZupt(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const CommandedZupt& self) +void CommandedZupt::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, CommandedZupt& self) +void CommandedZupt::extract(Serializer& serializer) { (void)serializer; - (void)self; } TypedResult commandedZupt(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMMANDED_ZUPT, NULL, 0); } -void insert(::microstrain::Serializer& serializer, const CommandedAngularZupt& self) +void CommandedAngularZupt::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, CommandedAngularZupt& self) +void CommandedAngularZupt::extract(Serializer& serializer) { (void)serializer; - (void)self; } TypedResult commandedAngularZupt(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMMANDED_ANGULAR_ZUPT, NULL, 0); } -void insert(::microstrain::Serializer& serializer, const MagCaptureAutoCal& self) +void MagCaptureAutoCal::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); } -void extract(::microstrain::Serializer& serializer, MagCaptureAutoCal& self) +void MagCaptureAutoCal::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); } TypedResult writeMagCaptureAutoCal(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); + serializer.insert(FunctionSelector::WRITE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)serializer.length()); } TypedResult saveMagCaptureAutoCal(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GravityNoise& self) +void GravityNoise::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); + serializer.insert(noise); } } -void extract(::microstrain::Serializer& serializer, GravityNoise& self) +void GravityNoise::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); + serializer.extract(noise); } } -void insert(::microstrain::Serializer& serializer, const GravityNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); - -} -void extract(::microstrain::Serializer& serializer, GravityNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); - -} - TypedResult writeGravityNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(noise || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(noise); for(unsigned int i=0; i < 3; i++) - insert(serializer, noise[i]); + serializer.insert(noise[i]); assert(serializer.isOk()); @@ -2339,97 +2029,86 @@ TypedResult writeGravityNoise(C::mip_interface& device, const floa } TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length(), REPLY_GRAVITY_NOISE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(noiseOut || (3 == 0)); + assert(noiseOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, noiseOut[i]); + deserializer.extract(noiseOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGravityNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadGravityNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultGravityNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const PressureAltitudeNoise& self) +void PressureAltitudeNoise::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.noise); + serializer.insert(noise); } } -void extract(::microstrain::Serializer& serializer, PressureAltitudeNoise& self) +void PressureAltitudeNoise::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.noise); + serializer.extract(noise); } } -void insert(::microstrain::Serializer& serializer, const PressureAltitudeNoise::Response& self) -{ - insert(serializer, self.noise); - -} -void extract(::microstrain::Serializer& serializer, PressureAltitudeNoise::Response& self) -{ - extract(serializer, self.noise); - -} - TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, noise); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(noise); assert(serializer.isOk()); @@ -2437,102 +2116,87 @@ TypedResult writePressureAltitudeNoise(C::mip_interface& } TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length(), REPLY_PRESSURE_NOISE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(noiseOut); - extract(deserializer, *noiseOut); + deserializer.extract(*noiseOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult savePressureAltitudeNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadPressureAltitudeNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultPressureAltitudeNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const HardIronOffsetNoise& self) +void HardIronOffsetNoise::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); + serializer.insert(noise); } } -void extract(::microstrain::Serializer& serializer, HardIronOffsetNoise& self) +void HardIronOffsetNoise::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); + serializer.extract(noise); } } -void insert(::microstrain::Serializer& serializer, const HardIronOffsetNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); - -} -void extract(::microstrain::Serializer& serializer, HardIronOffsetNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); - -} - TypedResult writeHardIronOffsetNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(noise || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(noise); for(unsigned int i=0; i < 3; i++) - insert(serializer, noise[i]); + serializer.insert(noise[i]); assert(serializer.isOk()); @@ -2540,103 +2204,88 @@ TypedResult writeHardIronOffsetNoise(C::mip_interface& devi } TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length(), REPLY_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(noiseOut || (3 == 0)); + assert(noiseOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, noiseOut[i]); + deserializer.extract(noiseOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveHardIronOffsetNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadHardIronOffsetNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultHardIronOffsetNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SoftIronMatrixNoise& self) +void SoftIronMatrixNoise::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.noise[i]); + serializer.insert(noise); } } -void extract(::microstrain::Serializer& serializer, SoftIronMatrixNoise& self) +void SoftIronMatrixNoise::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.noise[i]); + serializer.extract(noise); } } -void insert(::microstrain::Serializer& serializer, const SoftIronMatrixNoise::Response& self) -{ - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.noise[i]); - -} -void extract(::microstrain::Serializer& serializer, SoftIronMatrixNoise::Response& self) -{ - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.noise[i]); - -} - TypedResult writeSoftIronMatrixNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(noise || (9 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(noise); for(unsigned int i=0; i < 9; i++) - insert(serializer, noise[i]); + serializer.insert(noise[i]); assert(serializer.isOk()); @@ -2644,103 +2293,88 @@ TypedResult writeSoftIronMatrixNoise(C::mip_interface& devi } TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length(), REPLY_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(noiseOut || (9 == 0)); + assert(noiseOut); for(unsigned int i=0; i < 9; i++) - extract(deserializer, noiseOut[i]); + deserializer.extract(noiseOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSoftIronMatrixNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadSoftIronMatrixNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultSoftIronMatrixNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const MagNoise& self) +void MagNoise::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); + serializer.insert(noise); } } -void extract(::microstrain::Serializer& serializer, MagNoise& self) +void MagNoise::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); + serializer.extract(noise); } } -void insert(::microstrain::Serializer& serializer, const MagNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.noise[i]); - -} -void extract(::microstrain::Serializer& serializer, MagNoise::Response& self) -{ - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.noise[i]); - -} - TypedResult writeMagNoise(C::mip_interface& device, const float* noise) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - assert(noise || (3 == 0)); + serializer.insert(FunctionSelector::WRITE); + assert(noise); for(unsigned int i=0; i < 3; i++) - insert(serializer, noise[i]); + serializer.insert(noise[i]); assert(serializer.isOk()); @@ -2748,107 +2382,92 @@ TypedResult writeMagNoise(C::mip_interface& device, const float* noise } TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length(), REPLY_MAG_NOISE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(noiseOut || (3 == 0)); + assert(noiseOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, noiseOut[i]); + deserializer.extract(noiseOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveMagNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult loadMagNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagNoise(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const InclinationSource& self) +void InclinationSource::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.source); + serializer.insert(source); - insert(serializer, self.inclination); + serializer.insert(inclination); } } -void extract(::microstrain::Serializer& serializer, InclinationSource& self) +void InclinationSource::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.source); + serializer.extract(source); - extract(serializer, self.inclination); + serializer.extract(inclination); } } -void insert(::microstrain::Serializer& serializer, const InclinationSource::Response& self) -{ - insert(serializer, self.source); - - insert(serializer, self.inclination); - -} -void extract(::microstrain::Serializer& serializer, InclinationSource::Response& self) -{ - extract(serializer, self.source); - - extract(serializer, self.inclination); - -} - TypedResult writeInclinationSource(C::mip_interface& device, FilterMagParamSource source, float inclination) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(source); - insert(serializer, inclination); + serializer.insert(inclination); assert(serializer.isOk()); @@ -2856,109 +2475,94 @@ TypedResult writeInclinationSource(C::mip_interface& device, } TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_INCLINATION_SOURCE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(sourceOut); - extract(deserializer, *sourceOut); + deserializer.extract(*sourceOut); assert(inclinationOut); - extract(deserializer, *inclinationOut); + deserializer.extract(*inclinationOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveInclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult loadInclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult defaultInclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const MagneticDeclinationSource& self) +void MagneticDeclinationSource::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.source); + serializer.insert(source); - insert(serializer, self.declination); + serializer.insert(declination); } } -void extract(::microstrain::Serializer& serializer, MagneticDeclinationSource& self) +void MagneticDeclinationSource::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.source); + serializer.extract(source); - extract(serializer, self.declination); + serializer.extract(declination); } } -void insert(::microstrain::Serializer& serializer, const MagneticDeclinationSource::Response& self) -{ - insert(serializer, self.source); - - insert(serializer, self.declination); - -} -void extract(::microstrain::Serializer& serializer, MagneticDeclinationSource::Response& self) -{ - extract(serializer, self.source); - - extract(serializer, self.declination); - -} - TypedResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource source, float declination) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(source); - insert(serializer, declination); + serializer.insert(declination); assert(serializer.isOk()); @@ -2966,109 +2570,94 @@ TypedResult writeMagneticDeclinationSource(C::mip_int } TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_DECLINATION_SOURCE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(sourceOut); - extract(deserializer, *sourceOut); + deserializer.extract(*sourceOut); assert(declinationOut); - extract(deserializer, *declinationOut); + deserializer.extract(*declinationOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveMagneticDeclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult loadMagneticDeclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagneticDeclinationSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const MagFieldMagnitudeSource& self) +void MagFieldMagnitudeSource::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.source); + serializer.insert(source); - insert(serializer, self.magnitude); + serializer.insert(magnitude); } } -void extract(::microstrain::Serializer& serializer, MagFieldMagnitudeSource& self) +void MagFieldMagnitudeSource::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.source); + serializer.extract(source); - extract(serializer, self.magnitude); + serializer.extract(magnitude); } } -void insert(::microstrain::Serializer& serializer, const MagFieldMagnitudeSource::Response& self) -{ - insert(serializer, self.source); - - insert(serializer, self.magnitude); - -} -void extract(::microstrain::Serializer& serializer, MagFieldMagnitudeSource::Response& self) -{ - extract(serializer, self.source); - - extract(serializer, self.magnitude); - -} - TypedResult writeMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource source, float magnitude) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(source); - insert(serializer, magnitude); + serializer.insert(magnitude); assert(serializer.isOk()); @@ -3076,129 +2665,106 @@ TypedResult writeMagFieldMagnitudeSource(C::mip_interfa } TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(sourceOut); - extract(deserializer, *sourceOut); + deserializer.extract(*sourceOut); assert(magnitudeOut); - extract(deserializer, *magnitudeOut); + deserializer.extract(*magnitudeOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveMagFieldMagnitudeSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult loadMagFieldMagnitudeSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagFieldMagnitudeSource(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ReferencePosition& self) +void ReferencePosition::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); - insert(serializer, self.latitude); + serializer.insert(latitude); - insert(serializer, self.longitude); + serializer.insert(longitude); - insert(serializer, self.altitude); + serializer.insert(altitude); } } -void extract(::microstrain::Serializer& serializer, ReferencePosition& self) +void ReferencePosition::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); - extract(serializer, self.latitude); + serializer.extract(latitude); - extract(serializer, self.longitude); + serializer.extract(longitude); - extract(serializer, self.altitude); + serializer.extract(altitude); } } -void insert(::microstrain::Serializer& serializer, const ReferencePosition::Response& self) -{ - insert(serializer, self.enable); - - insert(serializer, self.latitude); - - insert(serializer, self.longitude); - - insert(serializer, self.altitude); - -} -void extract(::microstrain::Serializer& serializer, ReferencePosition::Response& self) -{ - extract(serializer, self.enable); - - extract(serializer, self.latitude); - - extract(serializer, self.longitude); - - extract(serializer, self.altitude); - -} - TypedResult writeReferencePosition(C::mip_interface& device, bool enable, double latitude, double longitude, double altitude) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); - insert(serializer, latitude); + serializer.insert(latitude); - insert(serializer, longitude); + serializer.insert(longitude); - insert(serializer, altitude); + serializer.insert(altitude); assert(serializer.isOk()); @@ -3206,165 +2772,130 @@ TypedResult writeReferencePosition(C::mip_interface& device, } TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length(), REPLY_REFERENCE_POSITION, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); assert(latitudeOut); - extract(deserializer, *latitudeOut); + deserializer.extract(*latitudeOut); assert(longitudeOut); - extract(deserializer, *longitudeOut); + deserializer.extract(*longitudeOut); assert(altitudeOut); - extract(deserializer, *altitudeOut); + deserializer.extract(*altitudeOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveReferencePosition(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); } TypedResult loadReferencePosition(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); } TypedResult defaultReferencePosition(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self) +void AccelMagnitudeErrorAdaptiveMeasurement::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.adaptive_measurement); + serializer.insert(adaptive_measurement); - insert(serializer, self.frequency); + serializer.insert(frequency); - insert(serializer, self.low_limit); + serializer.insert(low_limit); - insert(serializer, self.high_limit); + serializer.insert(high_limit); - insert(serializer, self.low_limit_uncertainty); + serializer.insert(low_limit_uncertainty); - insert(serializer, self.high_limit_uncertainty); + serializer.insert(high_limit_uncertainty); - insert(serializer, self.minimum_uncertainty); + serializer.insert(minimum_uncertainty); } } -void extract(::microstrain::Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self) +void AccelMagnitudeErrorAdaptiveMeasurement::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.adaptive_measurement); + serializer.extract(adaptive_measurement); - extract(serializer, self.frequency); + serializer.extract(frequency); - extract(serializer, self.low_limit); + serializer.extract(low_limit); - extract(serializer, self.high_limit); + serializer.extract(high_limit); - extract(serializer, self.low_limit_uncertainty); + serializer.extract(low_limit_uncertainty); - extract(serializer, self.high_limit_uncertainty); + serializer.extract(high_limit_uncertainty); - extract(serializer, self.minimum_uncertainty); + serializer.extract(minimum_uncertainty); } } -void insert(::microstrain::Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self) -{ - insert(serializer, self.adaptive_measurement); - - insert(serializer, self.frequency); - - insert(serializer, self.low_limit); - - insert(serializer, self.high_limit); - - insert(serializer, self.low_limit_uncertainty); - - insert(serializer, self.high_limit_uncertainty); - - insert(serializer, self.minimum_uncertainty); - -} -void extract(::microstrain::Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self) -{ - extract(serializer, self.adaptive_measurement); - - extract(serializer, self.frequency); - - extract(serializer, self.low_limit); - - extract(serializer, self.high_limit); - - extract(serializer, self.low_limit_uncertainty); - - extract(serializer, self.high_limit_uncertainty); - - extract(serializer, self.minimum_uncertainty); - -} - TypedResult writeAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, adaptiveMeasurement); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(adaptiveMeasurement); - insert(serializer, frequency); + serializer.insert(frequency); - insert(serializer, lowLimit); + serializer.insert(lowLimit); - insert(serializer, highLimit); + serializer.insert(highLimit); - insert(serializer, lowLimitUncertainty); + serializer.insert(lowLimitUncertainty); - insert(serializer, highLimitUncertainty); + serializer.insert(highLimitUncertainty); - insert(serializer, minimumUncertainty); + serializer.insert(minimumUncertainty); assert(serializer.isOk()); @@ -3372,174 +2903,139 @@ TypedResult writeAccelMagnitudeErrorAdap } TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(adaptiveMeasurementOut); - extract(deserializer, *adaptiveMeasurementOut); + deserializer.extract(*adaptiveMeasurementOut); assert(frequencyOut); - extract(deserializer, *frequencyOut); + deserializer.extract(*frequencyOut); assert(lowLimitOut); - extract(deserializer, *lowLimitOut); + deserializer.extract(*lowLimitOut); assert(highLimitOut); - extract(deserializer, *highLimitOut); + deserializer.extract(*highLimitOut); assert(lowLimitUncertaintyOut); - extract(deserializer, *lowLimitUncertaintyOut); + deserializer.extract(*lowLimitUncertaintyOut); assert(highLimitUncertaintyOut); - extract(deserializer, *highLimitUncertaintyOut); + deserializer.extract(*highLimitUncertaintyOut); assert(minimumUncertaintyOut); - extract(deserializer, *minimumUncertaintyOut); + deserializer.extract(*minimumUncertaintyOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self) +void MagMagnitudeErrorAdaptiveMeasurement::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.adaptive_measurement); + serializer.insert(adaptive_measurement); - insert(serializer, self.frequency); + serializer.insert(frequency); - insert(serializer, self.low_limit); + serializer.insert(low_limit); - insert(serializer, self.high_limit); + serializer.insert(high_limit); - insert(serializer, self.low_limit_uncertainty); + serializer.insert(low_limit_uncertainty); - insert(serializer, self.high_limit_uncertainty); + serializer.insert(high_limit_uncertainty); - insert(serializer, self.minimum_uncertainty); + serializer.insert(minimum_uncertainty); } } -void extract(::microstrain::Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self) +void MagMagnitudeErrorAdaptiveMeasurement::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.adaptive_measurement); + serializer.extract(adaptive_measurement); - extract(serializer, self.frequency); + serializer.extract(frequency); - extract(serializer, self.low_limit); + serializer.extract(low_limit); - extract(serializer, self.high_limit); + serializer.extract(high_limit); - extract(serializer, self.low_limit_uncertainty); + serializer.extract(low_limit_uncertainty); - extract(serializer, self.high_limit_uncertainty); + serializer.extract(high_limit_uncertainty); - extract(serializer, self.minimum_uncertainty); + serializer.extract(minimum_uncertainty); } } -void insert(::microstrain::Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self) -{ - insert(serializer, self.adaptive_measurement); - - insert(serializer, self.frequency); - - insert(serializer, self.low_limit); - - insert(serializer, self.high_limit); - - insert(serializer, self.low_limit_uncertainty); - - insert(serializer, self.high_limit_uncertainty); - - insert(serializer, self.minimum_uncertainty); - -} -void extract(::microstrain::Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self) -{ - extract(serializer, self.adaptive_measurement); - - extract(serializer, self.frequency); - - extract(serializer, self.low_limit); - - extract(serializer, self.high_limit); - - extract(serializer, self.low_limit_uncertainty); - - extract(serializer, self.high_limit_uncertainty); - - extract(serializer, self.minimum_uncertainty); - -} - TypedResult writeMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, adaptiveMeasurement); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(adaptiveMeasurement); - insert(serializer, frequency); + serializer.insert(frequency); - insert(serializer, lowLimit); + serializer.insert(lowLimit); - insert(serializer, highLimit); + serializer.insert(highLimit); - insert(serializer, lowLimitUncertainty); + serializer.insert(lowLimitUncertainty); - insert(serializer, highLimitUncertainty); + serializer.insert(highLimitUncertainty); - insert(serializer, minimumUncertainty); + serializer.insert(minimumUncertainty); assert(serializer.isOk()); @@ -3547,154 +3043,127 @@ TypedResult writeMagMagnitudeErrorAdaptive } TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(adaptiveMeasurementOut); - extract(deserializer, *adaptiveMeasurementOut); + deserializer.extract(*adaptiveMeasurementOut); assert(frequencyOut); - extract(deserializer, *frequencyOut); + deserializer.extract(*frequencyOut); assert(lowLimitOut); - extract(deserializer, *lowLimitOut); + deserializer.extract(*lowLimitOut); assert(highLimitOut); - extract(deserializer, *highLimitOut); + deserializer.extract(*highLimitOut); assert(lowLimitUncertaintyOut); - extract(deserializer, *lowLimitUncertaintyOut); + deserializer.extract(*lowLimitUncertaintyOut); assert(highLimitUncertaintyOut); - extract(deserializer, *highLimitUncertaintyOut); + deserializer.extract(*highLimitUncertaintyOut); assert(minimumUncertaintyOut); - extract(deserializer, *minimumUncertaintyOut); + deserializer.extract(*minimumUncertaintyOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self) +void MagDipAngleErrorAdaptiveMeasurement::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); - insert(serializer, self.frequency); + serializer.insert(frequency); - insert(serializer, self.high_limit); + serializer.insert(high_limit); - insert(serializer, self.high_limit_uncertainty); + serializer.insert(high_limit_uncertainty); - insert(serializer, self.minimum_uncertainty); + serializer.insert(minimum_uncertainty); } } -void extract(::microstrain::Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement& self) +void MagDipAngleErrorAdaptiveMeasurement::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); - extract(serializer, self.frequency); + serializer.extract(frequency); - extract(serializer, self.high_limit); + serializer.extract(high_limit); - extract(serializer, self.high_limit_uncertainty); + serializer.extract(high_limit_uncertainty); - extract(serializer, self.minimum_uncertainty); + serializer.extract(minimum_uncertainty); } } -void insert(::microstrain::Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self) -{ - insert(serializer, self.enable); - - insert(serializer, self.frequency); - - insert(serializer, self.high_limit); - - insert(serializer, self.high_limit_uncertainty); - - insert(serializer, self.minimum_uncertainty); - -} -void extract(::microstrain::Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self) -{ - extract(serializer, self.enable); - - extract(serializer, self.frequency); - - extract(serializer, self.high_limit); - - extract(serializer, self.high_limit_uncertainty); - - extract(serializer, self.minimum_uncertainty); - -} - TypedResult writeMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool enable, float frequency, float highLimit, float highLimitUncertainty, float minimumUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); - insert(serializer, frequency); + serializer.insert(frequency); - insert(serializer, highLimit); + serializer.insert(highLimit); - insert(serializer, highLimitUncertainty); + serializer.insert(highLimitUncertainty); - insert(serializer, minimumUncertainty); + serializer.insert(minimumUncertainty); assert(serializer.isOk()); @@ -3702,118 +3171,103 @@ TypedResult writeMagDipAngleErrorAdaptiveMe } TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); assert(frequencyOut); - extract(deserializer, *frequencyOut); + deserializer.extract(*frequencyOut); assert(highLimitOut); - extract(deserializer, *highLimitOut); + deserializer.extract(*highLimitOut); assert(highLimitUncertaintyOut); - extract(deserializer, *highLimitUncertaintyOut); + deserializer.extract(*highLimitUncertaintyOut); assert(minimumUncertaintyOut); - extract(deserializer, *minimumUncertaintyOut); + deserializer.extract(*minimumUncertaintyOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AidingMeasurementEnable& self) +void AidingMeasurementEnable::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.aiding_source); + serializer.insert(aiding_source); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); } } -void extract(::microstrain::Serializer& serializer, AidingMeasurementEnable& self) +void AidingMeasurementEnable::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.aiding_source); + serializer.extract(aiding_source); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); } } -void insert(::microstrain::Serializer& serializer, const AidingMeasurementEnable::Response& self) -{ - insert(serializer, self.aiding_source); - - insert(serializer, self.enable); - -} -void extract(::microstrain::Serializer& serializer, AidingMeasurementEnable::Response& self) -{ - extract(serializer, self.aiding_source); - - extract(serializer, self.enable); - -} - TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, aidingSource); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(aidingSource); - insert(serializer, enable); + serializer.insert(enable); assert(serializer.isOk()); @@ -3821,38 +3275,38 @@ TypedResult writeAidingMeasurementEnable(C::mip_interfa } TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, aidingSource); + serializer.insert(FunctionSelector::READ); + serializer.insert(aidingSource); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length(), REPLY_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, aidingSource); + deserializer.extract(aidingSource); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, aidingSource); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(aidingSource); assert(serializer.isOk()); @@ -3860,11 +3314,11 @@ TypedResult saveAidingMeasurementEnable(C::mip_interfac } TypedResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, aidingSource); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(aidingSource); assert(serializer.isOk()); @@ -3872,90 +3326,69 @@ TypedResult loadAidingMeasurementEnable(C::mip_interfac } TypedResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, aidingSource); + serializer.insert(FunctionSelector::RESET); + serializer.insert(aidingSource); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const Run& self) +void Run::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, Run& self) +void Run::extract(Serializer& serializer) { (void)serializer; - (void)self; } TypedResult run(C::mip_interface& device) { return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RUN, NULL, 0); } -void insert(::microstrain::Serializer& serializer, const KinematicConstraint& self) +void KinematicConstraint::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.acceleration_constraint_selection); + serializer.insert(acceleration_constraint_selection); - insert(serializer, self.velocity_constraint_selection); + serializer.insert(velocity_constraint_selection); - insert(serializer, self.angular_constraint_selection); + serializer.insert(angular_constraint_selection); } } -void extract(::microstrain::Serializer& serializer, KinematicConstraint& self) +void KinematicConstraint::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.acceleration_constraint_selection); + serializer.extract(acceleration_constraint_selection); - extract(serializer, self.velocity_constraint_selection); + serializer.extract(velocity_constraint_selection); - extract(serializer, self.angular_constraint_selection); + serializer.extract(angular_constraint_selection); } } -void insert(::microstrain::Serializer& serializer, const KinematicConstraint::Response& self) -{ - insert(serializer, self.acceleration_constraint_selection); - - insert(serializer, self.velocity_constraint_selection); - - insert(serializer, self.angular_constraint_selection); - -} -void extract(::microstrain::Serializer& serializer, KinematicConstraint::Response& self) -{ - extract(serializer, self.acceleration_constraint_selection); - - extract(serializer, self.velocity_constraint_selection); - - extract(serializer, self.angular_constraint_selection); - -} - TypedResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, accelerationConstraintSelection); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(accelerationConstraintSelection); - insert(serializer, velocityConstraintSelection); + serializer.insert(velocityConstraintSelection); - insert(serializer, angularConstraintSelection); + serializer.insert(angularConstraintSelection); assert(serializer.isOk()); @@ -3963,194 +3396,143 @@ TypedResult writeKinematicConstraint(C::mip_interface& devi } TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length(), REPLY_KINEMATIC_CONSTRAINT, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(accelerationConstraintSelectionOut); - extract(deserializer, *accelerationConstraintSelectionOut); + deserializer.extract(*accelerationConstraintSelectionOut); assert(velocityConstraintSelectionOut); - extract(deserializer, *velocityConstraintSelectionOut); + deserializer.extract(*velocityConstraintSelectionOut); assert(angularConstraintSelectionOut); - extract(deserializer, *angularConstraintSelectionOut); + deserializer.extract(*angularConstraintSelectionOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveKinematicConstraint(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); } TypedResult loadKinematicConstraint(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); } TypedResult defaultKinematicConstraint(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const InitializationConfiguration& self) +void InitializationConfiguration::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.wait_for_run_command); + serializer.insert(wait_for_run_command); - insert(serializer, self.initial_cond_src); + serializer.insert(initial_cond_src); - insert(serializer, self.auto_heading_alignment_selector); + serializer.insert(auto_heading_alignment_selector); - insert(serializer, self.initial_heading); + serializer.insert(initial_heading); - insert(serializer, self.initial_pitch); + serializer.insert(initial_pitch); - insert(serializer, self.initial_roll); + serializer.insert(initial_roll); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.initial_position[i]); + serializer.insert(initial_position); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.initial_velocity[i]); + serializer.insert(initial_velocity); - insert(serializer, self.reference_frame_selector); + serializer.insert(reference_frame_selector); } } -void extract(::microstrain::Serializer& serializer, InitializationConfiguration& self) +void InitializationConfiguration::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.wait_for_run_command); + serializer.extract(wait_for_run_command); - extract(serializer, self.initial_cond_src); + serializer.extract(initial_cond_src); - extract(serializer, self.auto_heading_alignment_selector); + serializer.extract(auto_heading_alignment_selector); - extract(serializer, self.initial_heading); + serializer.extract(initial_heading); - extract(serializer, self.initial_pitch); + serializer.extract(initial_pitch); - extract(serializer, self.initial_roll); + serializer.extract(initial_roll); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.initial_position[i]); + serializer.extract(initial_position); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.initial_velocity[i]); + serializer.extract(initial_velocity); - extract(serializer, self.reference_frame_selector); + serializer.extract(reference_frame_selector); } } -void insert(::microstrain::Serializer& serializer, const InitializationConfiguration::Response& self) -{ - insert(serializer, self.wait_for_run_command); - - insert(serializer, self.initial_cond_src); - - insert(serializer, self.auto_heading_alignment_selector); - - insert(serializer, self.initial_heading); - - insert(serializer, self.initial_pitch); - - insert(serializer, self.initial_roll); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.initial_position[i]); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.initial_velocity[i]); - - insert(serializer, self.reference_frame_selector); - -} -void extract(::microstrain::Serializer& serializer, InitializationConfiguration::Response& self) -{ - extract(serializer, self.wait_for_run_command); - - extract(serializer, self.initial_cond_src); - - extract(serializer, self.auto_heading_alignment_selector); - - extract(serializer, self.initial_heading); - - extract(serializer, self.initial_pitch); - - extract(serializer, self.initial_roll); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.initial_position[i]); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.initial_velocity[i]); - - extract(serializer, self.reference_frame_selector); - -} - TypedResult writeInitializationConfiguration(C::mip_interface& device, uint8_t waitForRunCommand, InitializationConfiguration::InitialConditionSource initialCondSrc, InitializationConfiguration::AlignmentSelector autoHeadingAlignmentSelector, float initialHeading, float initialPitch, float initialRoll, const float* initialPosition, const float* initialVelocity, FilterReferenceFrame referenceFrameSelector) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, waitForRunCommand); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(waitForRunCommand); - insert(serializer, initialCondSrc); + serializer.insert(initialCondSrc); - insert(serializer, autoHeadingAlignmentSelector); + serializer.insert(autoHeadingAlignmentSelector); - insert(serializer, initialHeading); + serializer.insert(initialHeading); - insert(serializer, initialPitch); + serializer.insert(initialPitch); - insert(serializer, initialRoll); + serializer.insert(initialRoll); - assert(initialPosition || (3 == 0)); + assert(initialPosition); for(unsigned int i=0; i < 3; i++) - insert(serializer, initialPosition[i]); + serializer.insert(initialPosition[i]); - assert(initialVelocity || (3 == 0)); + assert(initialVelocity); for(unsigned int i=0; i < 3; i++) - insert(serializer, initialVelocity[i]); + serializer.insert(initialVelocity[i]); - insert(serializer, referenceFrameSelector); + serializer.insert(referenceFrameSelector); assert(serializer.isOk()); @@ -4158,132 +3540,117 @@ TypedResult writeInitializationConfiguration(C::mip } TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_INITIALIZATION_CONFIGURATION, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(waitForRunCommandOut); - extract(deserializer, *waitForRunCommandOut); + deserializer.extract(*waitForRunCommandOut); assert(initialCondSrcOut); - extract(deserializer, *initialCondSrcOut); + deserializer.extract(*initialCondSrcOut); assert(autoHeadingAlignmentSelectorOut); - extract(deserializer, *autoHeadingAlignmentSelectorOut); + deserializer.extract(*autoHeadingAlignmentSelectorOut); assert(initialHeadingOut); - extract(deserializer, *initialHeadingOut); + deserializer.extract(*initialHeadingOut); assert(initialPitchOut); - extract(deserializer, *initialPitchOut); + deserializer.extract(*initialPitchOut); assert(initialRollOut); - extract(deserializer, *initialRollOut); + deserializer.extract(*initialRollOut); - assert(initialPositionOut || (3 == 0)); + assert(initialPositionOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, initialPositionOut[i]); + deserializer.extract(initialPositionOut[i]); - assert(initialVelocityOut || (3 == 0)); + assert(initialVelocityOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, initialVelocityOut[i]); + deserializer.extract(initialVelocityOut[i]); assert(referenceFrameSelectorOut); - extract(deserializer, *referenceFrameSelectorOut); + deserializer.extract(*referenceFrameSelectorOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveInitializationConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult loadInitializationConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultInitializationConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const AdaptiveFilterOptions& self) +void AdaptiveFilterOptions::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.level); + serializer.insert(level); - insert(serializer, self.time_limit); + serializer.insert(time_limit); } } -void extract(::microstrain::Serializer& serializer, AdaptiveFilterOptions& self) +void AdaptiveFilterOptions::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.level); + serializer.extract(level); - extract(serializer, self.time_limit); + serializer.extract(time_limit); } } -void insert(::microstrain::Serializer& serializer, const AdaptiveFilterOptions::Response& self) -{ - insert(serializer, self.level); - - insert(serializer, self.time_limit); - -} -void extract(::microstrain::Serializer& serializer, AdaptiveFilterOptions::Response& self) -{ - extract(serializer, self.level); - - extract(serializer, self.time_limit); - -} - TypedResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, level); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(level); - insert(serializer, timeLimit); + serializer.insert(timeLimit); assert(serializer.isOk()); @@ -4291,115 +3658,96 @@ TypedResult writeAdaptiveFilterOptions(C::mip_interface& } TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length(), REPLY_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(levelOut); - extract(deserializer, *levelOut); + deserializer.extract(*levelOut); assert(timeLimitOut); - extract(deserializer, *timeLimitOut); + deserializer.extract(*timeLimitOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveAdaptiveFilterOptions(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); } TypedResult loadAdaptiveFilterOptions(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); } TypedResult defaultAdaptiveFilterOptions(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const MultiAntennaOffset& self) +void MultiAntennaOffset::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.receiver_id); + serializer.insert(receiver_id); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.antenna_offset[i]); + serializer.insert(antenna_offset); } } -void extract(::microstrain::Serializer& serializer, MultiAntennaOffset& self) +void MultiAntennaOffset::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.receiver_id); + serializer.extract(receiver_id); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.antenna_offset[i]); + serializer.extract(antenna_offset); } } -void insert(::microstrain::Serializer& serializer, const MultiAntennaOffset::Response& self) -{ - insert(serializer, self.receiver_id); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.antenna_offset[i]); - -} -void extract(::microstrain::Serializer& serializer, MultiAntennaOffset::Response& self) -{ - extract(serializer, self.receiver_id); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.antenna_offset[i]); - -} - TypedResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, receiverId); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(receiverId); - assert(antennaOffset || (3 == 0)); + assert(antennaOffset); for(unsigned int i=0; i < 3; i++) - insert(serializer, antennaOffset[i]); + serializer.insert(antennaOffset[i]); assert(serializer.isOk()); @@ -4407,39 +3755,39 @@ TypedResult writeMultiAntennaOffset(C::mip_interface& device } TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, receiverId); + serializer.insert(FunctionSelector::READ); + serializer.insert(receiverId); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_MULTI_ANTENNA_OFFSET, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, receiverId); + deserializer.extract(receiverId); - assert(antennaOffsetOut || (3 == 0)); + assert(antennaOffsetOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, antennaOffsetOut[i]); + deserializer.extract(antennaOffsetOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, receiverId); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(receiverId); assert(serializer.isOk()); @@ -4447,11 +3795,11 @@ TypedResult saveMultiAntennaOffset(C::mip_interface& device, } TypedResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, receiverId); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(receiverId); assert(serializer.isOk()); @@ -4459,81 +3807,58 @@ TypedResult loadMultiAntennaOffset(C::mip_interface& device, } TypedResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, receiverId); + serializer.insert(FunctionSelector::RESET); + serializer.insert(receiverId); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const RelPosConfiguration& self) +void RelPosConfiguration::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.source); + serializer.insert(source); - insert(serializer, self.reference_frame_selector); + serializer.insert(reference_frame_selector); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.reference_coordinates[i]); + serializer.insert(reference_coordinates); } } -void extract(::microstrain::Serializer& serializer, RelPosConfiguration& self) +void RelPosConfiguration::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.source); + serializer.extract(source); - extract(serializer, self.reference_frame_selector); + serializer.extract(reference_frame_selector); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.reference_coordinates[i]); + serializer.extract(reference_coordinates); } } -void insert(::microstrain::Serializer& serializer, const RelPosConfiguration::Response& self) -{ - insert(serializer, self.source); - - insert(serializer, self.reference_frame_selector); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.reference_coordinates[i]); - -} -void extract(::microstrain::Serializer& serializer, RelPosConfiguration::Response& self) -{ - extract(serializer, self.source); - - extract(serializer, self.reference_frame_selector); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.reference_coordinates[i]); - -} - TypedResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(source); - insert(serializer, referenceFrameSelector); + serializer.insert(referenceFrameSelector); - assert(referenceCoordinates || (3 == 0)); + assert(referenceCoordinates); for(unsigned int i=0; i < 3; i++) - insert(serializer, referenceCoordinates[i]); + serializer.insert(referenceCoordinates[i]); assert(serializer.isOk()); @@ -4541,119 +3866,100 @@ TypedResult writeRelPosConfiguration(C::mip_interface& devi } TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_REL_POS_CONFIGURATION, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(sourceOut); - extract(deserializer, *sourceOut); + deserializer.extract(*sourceOut); assert(referenceFrameSelectorOut); - extract(deserializer, *referenceFrameSelectorOut); + deserializer.extract(*referenceFrameSelectorOut); - assert(referenceCoordinatesOut || (3 == 0)); + assert(referenceCoordinatesOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, referenceCoordinatesOut[i]); + deserializer.extract(referenceCoordinatesOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveRelPosConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult loadRelPosConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultRelPosConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const RefPointLeverArm& self) +void RefPointLeverArm::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.ref_point_sel); + serializer.insert(ref_point_sel); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.lever_arm_offset[i]); + serializer.insert(lever_arm_offset); } } -void extract(::microstrain::Serializer& serializer, RefPointLeverArm& self) +void RefPointLeverArm::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.ref_point_sel); + serializer.extract(ref_point_sel); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.lever_arm_offset[i]); + serializer.extract(lever_arm_offset); } } -void insert(::microstrain::Serializer& serializer, const RefPointLeverArm::Response& self) -{ - insert(serializer, self.ref_point_sel); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.lever_arm_offset[i]); - -} -void extract(::microstrain::Serializer& serializer, RefPointLeverArm::Response& self) -{ - extract(serializer, self.ref_point_sel); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.lever_arm_offset[i]); - -} - TypedResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, refPointSel); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(refPointSel); - assert(leverArmOffset || (3 == 0)); + assert(leverArmOffset); for(unsigned int i=0; i < 3; i++) - insert(serializer, leverArmOffset[i]); + serializer.insert(leverArmOffset[i]); assert(serializer.isOk()); @@ -4661,156 +3967,137 @@ TypedResult writeRefPointLeverArm(C::mip_interface& device, Re } TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length(), REPLY_REF_POINT_LEVER_ARM, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(refPointSelOut); - extract(deserializer, *refPointSelOut); + deserializer.extract(*refPointSelOut); - assert(leverArmOffsetOut || (3 == 0)); + assert(leverArmOffsetOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, leverArmOffsetOut[i]); + deserializer.extract(leverArmOffsetOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveRefPointLeverArm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); } TypedResult loadRefPointLeverArm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); } TypedResult defaultRefPointLeverArm(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SpeedMeasurement& self) +void SpeedMeasurement::insert(Serializer& serializer) const { - insert(serializer, self.source); + serializer.insert(source); - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.speed); + serializer.insert(speed); - insert(serializer, self.speed_uncertainty); + serializer.insert(speed_uncertainty); } -void extract(::microstrain::Serializer& serializer, SpeedMeasurement& self) +void SpeedMeasurement::extract(Serializer& serializer) { - extract(serializer, self.source); + serializer.extract(source); - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.speed); + serializer.extract(speed); - extract(serializer, self.speed_uncertainty); + serializer.extract(speed_uncertainty); } TypedResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, source); + serializer.insert(source); - insert(serializer, timeOfWeek); + serializer.insert(timeOfWeek); - insert(serializer, speed); + serializer.insert(speed); - insert(serializer, speedUncertainty); + serializer.insert(speedUncertainty); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_MEASUREMENT, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SpeedLeverArm& self) +void SpeedLeverArm::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - insert(serializer, self.source); + serializer.insert(source); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.lever_arm_offset[i]); + serializer.insert(lever_arm_offset); } } -void extract(::microstrain::Serializer& serializer, SpeedLeverArm& self) +void SpeedLeverArm::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - extract(serializer, self.source); + serializer.extract(source); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.lever_arm_offset[i]); + serializer.extract(lever_arm_offset); } } -void insert(::microstrain::Serializer& serializer, const SpeedLeverArm::Response& self) -{ - insert(serializer, self.source); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.lever_arm_offset[i]); - -} -void extract(::microstrain::Serializer& serializer, SpeedLeverArm::Response& self) -{ - extract(serializer, self.source); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.lever_arm_offset[i]); - -} - TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, source); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(source); - assert(leverArmOffset || (3 == 0)); + assert(leverArmOffset); for(unsigned int i=0; i < 3; i++) - insert(serializer, leverArmOffset[i]); + serializer.insert(leverArmOffset[i]); assert(serializer.isOk()); @@ -4818,39 +4105,39 @@ TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t } TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); - insert(serializer, source); + serializer.insert(FunctionSelector::READ); + serializer.insert(source); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length(), REPLY_SPEED_LEVER_ARM, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract(deserializer, source); + deserializer.extract(source); - assert(leverArmOffsetOut || (3 == 0)); + assert(leverArmOffsetOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, leverArmOffsetOut[i]); + deserializer.extract(leverArmOffsetOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); - insert(serializer, source); + serializer.insert(FunctionSelector::SAVE); + serializer.insert(source); assert(serializer.isOk()); @@ -4858,11 +4145,11 @@ TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t s } TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); - insert(serializer, source); + serializer.insert(FunctionSelector::LOAD); + serializer.insert(source); assert(serializer.isOk()); @@ -4870,55 +4157,44 @@ TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t s } TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); - insert(serializer, source); + serializer.insert(FunctionSelector::RESET); + serializer.insert(source); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const WheeledVehicleConstraintControl& self) +void WheeledVehicleConstraintControl::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); } } -void extract(::microstrain::Serializer& serializer, WheeledVehicleConstraintControl& self) +void WheeledVehicleConstraintControl::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); } } -void insert(::microstrain::Serializer& serializer, const WheeledVehicleConstraintControl::Response& self) -{ - insert(serializer, self.enable); - -} -void extract(::microstrain::Serializer& serializer, WheeledVehicleConstraintControl::Response& self) -{ - extract(serializer, self.enable); - -} - TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); assert(serializer.isOk()); @@ -4926,96 +4202,85 @@ TypedResult writeWheeledVehicleConstraintContro } TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveWheeledVehicleConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadWheeledVehicleConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultWheeledVehicleConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const VerticalGyroConstraintControl& self) +void VerticalGyroConstraintControl::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); } } -void extract(::microstrain::Serializer& serializer, VerticalGyroConstraintControl& self) +void VerticalGyroConstraintControl::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); } } -void insert(::microstrain::Serializer& serializer, const VerticalGyroConstraintControl::Response& self) -{ - insert(serializer, self.enable); - -} -void extract(::microstrain::Serializer& serializer, VerticalGyroConstraintControl::Response& self) -{ - extract(serializer, self.enable); - -} - TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); assert(serializer.isOk()); @@ -5023,106 +4288,91 @@ TypedResult writeVerticalGyroConstraintControl(C: } TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveVerticalGyroConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadVerticalGyroConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultVerticalGyroConstraintControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GnssAntennaCalControl& self) +void GnssAntennaCalControl::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); - insert(serializer, self.max_offset); + serializer.insert(max_offset); } } -void extract(::microstrain::Serializer& serializer, GnssAntennaCalControl& self) +void GnssAntennaCalControl::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); - extract(serializer, self.max_offset); + serializer.extract(max_offset); } } -void insert(::microstrain::Serializer& serializer, const GnssAntennaCalControl::Response& self) -{ - insert(serializer, self.enable); - - insert(serializer, self.max_offset); - -} -void extract(::microstrain::Serializer& serializer, GnssAntennaCalControl::Response& self) -{ - extract(serializer, self.enable); - - extract(serializer, self.max_offset); - -} - TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); - insert(serializer, maxOffset); + serializer.insert(maxOffset); assert(serializer.isOk()); @@ -5130,77 +4380,77 @@ TypedResult writeGnssAntennaCalControl(C::mip_interface& } TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); assert(maxOffsetOut); - extract(deserializer, *maxOffsetOut); + deserializer.extract(*maxOffsetOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveGnssAntennaCalControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult loadGnssAntennaCalControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); } TypedResult defaultGnssAntennaCalControl(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const SetInitialHeading& self) +void SetInitialHeading::insert(Serializer& serializer) const { - insert(serializer, self.heading); + serializer.insert(heading); } -void extract(::microstrain::Serializer& serializer, SetInitialHeading& self) +void SetInitialHeading::extract(Serializer& serializer) { - extract(serializer, self.heading); + serializer.extract(heading); } TypedResult setInitialHeading(C::mip_interface& device, float heading) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, heading); + serializer.insert(heading); assert(serializer.isOk()); diff --git a/src/cpp/mip/definitions/commands_filter.hpp b/src/cpp/mip/definitions/commands_filter.hpp index 48708d853..8809aeefa 100644 --- a/src/cpp/mip/definitions/commands_filter.hpp +++ b/src/cpp/mip/definitions/commands_filter.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" +#include #include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -191,30 +189,30 @@ enum class FilterAdaptiveMeasurement : uint8_t struct Reset { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_RESET_FILTER; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Reset"; static constexpr const char* DOC_NAME = "Reset Navigation Filter"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const Reset& self); -void extract(::microstrain::Serializer& serializer, Reset& self); - TypedResult reset(C::mip_interface& device); ///@} @@ -238,33 +236,35 @@ TypedResult reset(C::mip_interface& device); struct SetInitialAttitude { + /// Parameters float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float heading = 0; ///< [radians] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SET_INITIAL_ATTITUDE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SetInitialAttitude"; static constexpr const char* DOC_NAME = "Set Initial Attitude"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(roll,pitch,heading); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(heading)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const SetInitialAttitude& self); -void extract(::microstrain::Serializer& serializer, SetInitialAttitude& self); - TypedResult setInitialAttitude(C::mip_interface& device, float roll, float pitch, float heading); ///@} @@ -289,6 +289,7 @@ struct EstimationControl { struct EnableFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -311,49 +312,27 @@ struct EstimationControl EnableFlags& operator|=(uint16_t val) { return *this = value | val; } EnableFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gyroBias() const { return (value & GYRO_BIAS) > 0; } - void gyroBias(bool val) { if(val) value |= GYRO_BIAS; else value &= ~GYRO_BIAS; } - bool accelBias() const { return (value & ACCEL_BIAS) > 0; } - void accelBias(bool val) { if(val) value |= ACCEL_BIAS; else value &= ~ACCEL_BIAS; } - bool gyroScaleFactor() const { return (value & GYRO_SCALE_FACTOR) > 0; } - void gyroScaleFactor(bool val) { if(val) value |= GYRO_SCALE_FACTOR; else value &= ~GYRO_SCALE_FACTOR; } - bool accelScaleFactor() const { return (value & ACCEL_SCALE_FACTOR) > 0; } - void accelScaleFactor(bool val) { if(val) value |= ACCEL_SCALE_FACTOR; else value &= ~ACCEL_SCALE_FACTOR; } - bool antennaOffset() const { return (value & ANTENNA_OFFSET) > 0; } - void antennaOffset(bool val) { if(val) value |= ANTENNA_OFFSET; else value &= ~ANTENNA_OFFSET; } - bool autoMagHardIron() const { return (value & AUTO_MAG_HARD_IRON) > 0; } - void autoMagHardIron(bool val) { if(val) value |= AUTO_MAG_HARD_IRON; else value &= ~AUTO_MAG_HARD_IRON; } - bool autoMagSoftIron() const { return (value & AUTO_MAG_SOFT_IRON) > 0; } - void autoMagSoftIron(bool val) { if(val) value |= AUTO_MAG_SOFT_IRON; else value &= ~AUTO_MAG_SOFT_IRON; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters FunctionSelector function = static_cast(0); EnableFlags enable; ///< See above + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ESTIMATION_CONTROL_FLAGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EstimationControl"; static constexpr const char* DOC_NAME = "Estimation Control Flags"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } @@ -365,31 +344,39 @@ struct EstimationControl return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + EnableFlags enable; ///< See above + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ESTIMATION_CONTROL_FLAGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EstimationControl::Response"; static constexpr const char* DOC_NAME = "Estimation Control Flags Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - EnableFlags enable; ///< See above - + auto asTuple() const + { + return std::make_tuple(enable); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const EstimationControl& self); -void extract(::microstrain::Serializer& serializer, EstimationControl& self); - -void insert(::microstrain::Serializer& serializer, const EstimationControl::Response& self); -void extract(::microstrain::Serializer& serializer, EstimationControl::Response& self); - TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable); TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut); TypedResult saveEstimationControl(C::mip_interface& device); @@ -410,6 +397,7 @@ TypedResult defaultEstimationControl(C::mip_interface& device struct ExternalGnssUpdate { + /// Parameters double gps_time = 0; ///< [seconds] uint16_t gps_week = 0; ///< [GPS week number, not modulus 1024] double latitude = 0; ///< [degrees] @@ -419,29 +407,30 @@ struct ExternalGnssUpdate Vector3f pos_uncertainty; ///< NED Frame, 1-sigma [meters] Vector3f vel_uncertainty; ///< NED Frame, 1-sigma [meters/second] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_EXTERNAL_GNSS_UPDATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ExternalGnssUpdate"; static constexpr const char* DOC_NAME = "External GNSS Update"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(gps_time,gps_week,latitude,longitude,height,velocity,pos_uncertainty,vel_uncertainty); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(gps_time),std::ref(gps_week),std::ref(latitude),std::ref(longitude),std::ref(height),std::ref(velocity),std::ref(pos_uncertainty),std::ref(vel_uncertainty)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const ExternalGnssUpdate& self); -void extract(::microstrain::Serializer& serializer, ExternalGnssUpdate& self); - TypedResult externalGnssUpdate(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, double latitude, double longitude, double height, const float* velocity, const float* posUncertainty, const float* velUncertainty); ///@} @@ -466,33 +455,35 @@ TypedResult externalGnssUpdate(C::mip_interface& device, dou struct ExternalHeadingUpdate { + /// Parameters float heading = 0; ///< Bounded by +-PI [radians] float heading_uncertainty = 0; ///< 1-sigma [radians] uint8_t type = 0; ///< 1 - True, 2 - Magnetic + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_EXTERNAL_HEADING_UPDATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ExternalHeadingUpdate"; static constexpr const char* DOC_NAME = "External Heading Update"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(heading,heading_uncertainty,type); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(heading),std::ref(heading_uncertainty),std::ref(type)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const ExternalHeadingUpdate& self); -void extract(::microstrain::Serializer& serializer, ExternalHeadingUpdate& self); - TypedResult externalHeadingUpdate(C::mip_interface& device, float heading, float headingUncertainty, uint8_t type); ///@} @@ -521,35 +512,37 @@ TypedResult externalHeadingUpdate(C::mip_interface& devic struct ExternalHeadingUpdateWithTime { + /// Parameters double gps_time = 0; ///< [seconds] uint16_t gps_week = 0; ///< [GPS week number, not modulus 1024] float heading = 0; ///< Relative to true north, bounded by +-PI [radians] float heading_uncertainty = 0; ///< 1-sigma [radians] uint8_t type = 0; ///< 1 - True, 2 - Magnetic + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ExternalHeadingUpdateWithTime"; static constexpr const char* DOC_NAME = "External Heading Update With Time"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(gps_time,gps_week,heading,heading_uncertainty,type); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(gps_time),std::ref(gps_week),std::ref(heading),std::ref(heading_uncertainty),std::ref(type)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const ExternalHeadingUpdateWithTime& self); -void extract(::microstrain::Serializer& serializer, ExternalHeadingUpdateWithTime& self); - TypedResult externalHeadingUpdateWithTime(C::mip_interface& device, double gpsTime, uint16_t gpsWeek, float heading, float headingUncertainty, uint8_t type); ///@} @@ -568,6 +561,7 @@ struct TareOrientation { struct MipTareAxes : Bitfield { + typedef uint8_t Type; enum _enumType : uint8_t { NONE = 0x0, @@ -586,41 +580,27 @@ struct TareOrientation MipTareAxes& operator|=(uint8_t val) { return *this = value | val; } MipTareAxes& operator&=(uint8_t val) { return *this = value & val; } - bool roll() const { return (value & ROLL) > 0; } - void roll(bool val) { if(val) value |= ROLL; else value &= ~ROLL; } - bool pitch() const { return (value & PITCH) > 0; } - void pitch(bool val) { if(val) value |= PITCH; else value &= ~PITCH; } - bool yaw() const { return (value & YAW) > 0; } - void yaw(bool val) { if(val) value |= YAW; else value &= ~YAW; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters FunctionSelector function = static_cast(0); MipTareAxes axes; ///< Axes to tare + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_TARE_ORIENTATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "TareOrientation"; static constexpr const char* DOC_NAME = "Tare Sensor Orientation"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(axes); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(axes)); } @@ -632,31 +612,39 @@ struct TareOrientation return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + MipTareAxes axes; ///< Axes to tare + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_TARE_ORIENTATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "TareOrientation::Response"; static constexpr const char* DOC_NAME = "Tare Sensor Orientation Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - MipTareAxes axes; ///< Axes to tare - + auto asTuple() const + { + return std::make_tuple(axes); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(axes)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const TareOrientation& self); -void extract(::microstrain::Serializer& serializer, TareOrientation& self); - -void insert(::microstrain::Serializer& serializer, const TareOrientation::Response& self); -void extract(::microstrain::Serializer& serializer, TareOrientation::Response& self); - TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes); TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut); TypedResult saveTareOrientation(C::mip_interface& device); @@ -681,30 +669,24 @@ struct VehicleDynamicsMode AIRBORNE_HIGH_G = 4, ///< }; + /// Parameters FunctionSelector function = static_cast(0); DynamicsMode mode = static_cast(0); + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_VEHICLE_DYNAMICS_MODE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "VehicleDynamicsMode"; static constexpr const char* DOC_NAME = "Vehicle Dynamics Mode"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(mode); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(mode)); } @@ -716,31 +698,39 @@ struct VehicleDynamicsMode return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + DynamicsMode mode = static_cast(0); + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_VEHICLE_DYNAMICS_MODE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "VehicleDynamicsMode::Response"; static constexpr const char* DOC_NAME = "Vehicle Dynamics Mode Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - DynamicsMode mode = static_cast(0); - + auto asTuple() const + { + return std::make_tuple(mode); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(mode)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const VehicleDynamicsMode& self); -void extract(::microstrain::Serializer& serializer, VehicleDynamicsMode& self); - -void insert(::microstrain::Serializer& serializer, const VehicleDynamicsMode::Response& self); -void extract(::microstrain::Serializer& serializer, VehicleDynamicsMode::Response& self); - TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode); TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut); TypedResult saveVehicleDynamicsMode(C::mip_interface& device); @@ -779,32 +769,26 @@ TypedResult defaultVehicleDynamicsMode(C::mip_interface& de struct SensorToVehicleRotationEuler { + /// Parameters FunctionSelector function = static_cast(0); float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SENSOR2VEHICLE_ROTATION_EULER; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorToVehicleRotationEuler"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Rotation Euler"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8007; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(roll,pitch,yaw); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); } @@ -816,33 +800,41 @@ struct SensorToVehicleRotationEuler return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + float roll = 0; ///< [radians] + float pitch = 0; ///< [radians] + float yaw = 0; ///< [radians] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SENSOR2VEHICLE_ROTATION_EULER; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorToVehicleRotationEuler::Response"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Rotation Euler Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - float roll = 0; ///< [radians] - float pitch = 0; ///< [radians] - float yaw = 0; ///< [radians] - + auto asTuple() const + { + return std::make_tuple(roll,pitch,yaw); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationEuler& self); -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationEuler& self); - -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationEuler::Response& self); -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationEuler::Response& self); - TypedResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw); TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut); TypedResult saveSensorToVehicleRotationEuler(C::mip_interface& device); @@ -887,30 +879,24 @@ TypedResult defaultSensorToVehicleRotationEuler(C: struct SensorToVehicleRotationDcm { + /// Parameters FunctionSelector function = static_cast(0); Matrix3f dcm; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SENSOR2VEHICLE_ROTATION_DCM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorToVehicleRotationDcm"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Rotation DCM"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(dcm); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(dcm)); } @@ -922,31 +908,39 @@ struct SensorToVehicleRotationDcm return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Matrix3f dcm; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SENSOR2VEHICLE_ROTATION_DCM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorToVehicleRotationDcm::Response"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Rotation DCM Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Matrix3f dcm; - + auto asTuple() const + { + return std::make_tuple(dcm); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(dcm)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationDcm& self); -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationDcm& self); - -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationDcm::Response& self); -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationDcm::Response& self); - TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm); TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut); TypedResult saveSensorToVehicleRotationDcm(C::mip_interface& device); @@ -990,30 +984,24 @@ TypedResult defaultSensorToVehicleRotationDcm(C::mip struct SensorToVehicleRotationQuaternion { + /// Parameters FunctionSelector function = static_cast(0); Quatf quat; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SENSOR2VEHICLE_ROTATION_QUATERNION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorToVehicleRotationQuaternion"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Rotation Quaternion"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(quat); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(quat)); } @@ -1025,31 +1013,39 @@ struct SensorToVehicleRotationQuaternion return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Quatf quat; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorToVehicleRotationQuaternion::Response"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Rotation Quaternion Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Quatf quat; - + auto asTuple() const + { + return std::make_tuple(quat); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(quat)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationQuaternion& self); -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationQuaternion& self); - -void insert(::microstrain::Serializer& serializer, const SensorToVehicleRotationQuaternion::Response& self); -void extract(::microstrain::Serializer& serializer, SensorToVehicleRotationQuaternion::Response& self); - TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat); TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut); TypedResult saveSensorToVehicleRotationQuaternion(C::mip_interface& device); @@ -1074,30 +1070,24 @@ TypedResult defaultSensorToVehicleRotationQua struct SensorToVehicleOffset { + /// Parameters FunctionSelector function = static_cast(0); Vector3f offset; ///< [meters] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SENSOR2VEHICLE_OFFSET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorToVehicleOffset"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Offset"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(offset); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset)); } @@ -1109,31 +1099,39 @@ struct SensorToVehicleOffset return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f offset; ///< [meters] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SENSOR2VEHICLE_OFFSET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SensorToVehicleOffset::Response"; static constexpr const char* DOC_NAME = "Sensor to Vehicle Frame Offset Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f offset; ///< [meters] - + auto asTuple() const + { + return std::make_tuple(offset); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const SensorToVehicleOffset& self); -void extract(::microstrain::Serializer& serializer, SensorToVehicleOffset& self); - -void insert(::microstrain::Serializer& serializer, const SensorToVehicleOffset::Response& self); -void extract(::microstrain::Serializer& serializer, SensorToVehicleOffset::Response& self); - TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset); TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut); TypedResult saveSensorToVehicleOffset(C::mip_interface& device); @@ -1155,30 +1153,24 @@ TypedResult defaultSensorToVehicleOffset(C::mip_interface struct AntennaOffset { + /// Parameters FunctionSelector function = static_cast(0); Vector3f offset; ///< [meters] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ANTENNA_OFFSET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AntennaOffset"; static constexpr const char* DOC_NAME = "GNSS Antenna Offset Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(offset); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset)); } @@ -1190,31 +1182,39 @@ struct AntennaOffset return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f offset; ///< [meters] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ANTENNA_OFFSET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AntennaOffset::Response"; static constexpr const char* DOC_NAME = "GNSS Antenna Offset Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f offset; ///< [meters] - + auto asTuple() const + { + return std::make_tuple(offset); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AntennaOffset& self); -void extract(::microstrain::Serializer& serializer, AntennaOffset& self); - -void insert(::microstrain::Serializer& serializer, const AntennaOffset::Response& self); -void extract(::microstrain::Serializer& serializer, AntennaOffset::Response& self); - TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset); TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut); TypedResult saveAntennaOffset(C::mip_interface& device); @@ -1243,30 +1243,24 @@ struct GnssSource INT_2 = 4, ///< Internal GNSS Receiver 2 only }; + /// Parameters FunctionSelector function = static_cast(0); Source source = static_cast(0); + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_GNSS_SOURCE_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssSource"; static constexpr const char* DOC_NAME = "GNSS Aiding Source Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source)); } @@ -1278,31 +1272,39 @@ struct GnssSource return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Source source = static_cast(0); + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_GNSS_SOURCE_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssSource::Response"; static constexpr const char* DOC_NAME = "GNSS Aiding Source Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Source source = static_cast(0); - + auto asTuple() const + { + return std::make_tuple(source); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GnssSource& self); -void extract(::microstrain::Serializer& serializer, GnssSource& self); - -void insert(::microstrain::Serializer& serializer, const GnssSource::Response& self); -void extract(::microstrain::Serializer& serializer, GnssSource::Response& self); - TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source); TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut); TypedResult saveGnssSource(C::mip_interface& device); @@ -1342,30 +1344,24 @@ struct HeadingSource GNSS_VEL_AND_MAG_AND_EXTERNAL = 7, ///< }; + /// Parameters FunctionSelector function = static_cast(0); Source source = static_cast(0); + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_HEADING_UPDATE_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "HeadingSource"; static constexpr const char* DOC_NAME = "Heading Aiding Source Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source)); } @@ -1377,31 +1373,39 @@ struct HeadingSource return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Source source = static_cast(0); + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_HEADING_UPDATE_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "HeadingSource::Response"; static constexpr const char* DOC_NAME = "Heading Aiding Source Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Source source = static_cast(0); - + auto asTuple() const + { + return std::make_tuple(source); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const HeadingSource& self); -void extract(::microstrain::Serializer& serializer, HeadingSource& self); - -void insert(::microstrain::Serializer& serializer, const HeadingSource::Response& self); -void extract(::microstrain::Serializer& serializer, HeadingSource::Response& self); - TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source); TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut); TypedResult saveHeadingSource(C::mip_interface& device); @@ -1426,30 +1430,24 @@ TypedResult defaultHeadingSource(C::mip_interface& device); struct AutoInitControl { + /// Parameters FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< See above + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_AUTOINIT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AutoInitControl"; static constexpr const char* DOC_NAME = "Auto-initialization Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } @@ -1461,31 +1459,39 @@ struct AutoInitControl return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t enable = 0; ///< See above + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_AUTOINIT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AutoInitControl::Response"; static constexpr const char* DOC_NAME = "Auto-initialization Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t enable = 0; ///< See above - + auto asTuple() const + { + return std::make_tuple(enable); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AutoInitControl& self); -void extract(::microstrain::Serializer& serializer, AutoInitControl& self); - -void insert(::microstrain::Serializer& serializer, const AutoInitControl::Response& self); -void extract(::microstrain::Serializer& serializer, AutoInitControl::Response& self); - TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable); TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut); TypedResult saveAutoInitControl(C::mip_interface& device); @@ -1508,30 +1514,24 @@ TypedResult defaultAutoInitControl(C::mip_interface& device); struct AccelNoise { + /// Parameters FunctionSelector function = static_cast(0); Vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ACCEL_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelNoise"; static constexpr const char* DOC_NAME = "Accelerometer Noise Standard Deviation"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(noise); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } @@ -1543,31 +1543,39 @@ struct AccelNoise return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ACCEL_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelNoise::Response"; static constexpr const char* DOC_NAME = "Accelerometer Noise Standard Deviation Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] - + auto asTuple() const + { + return std::make_tuple(noise); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AccelNoise& self); -void extract(::microstrain::Serializer& serializer, AccelNoise& self); - -void insert(::microstrain::Serializer& serializer, const AccelNoise::Response& self); -void extract(::microstrain::Serializer& serializer, AccelNoise::Response& self); - TypedResult writeAccelNoise(C::mip_interface& device, const float* noise); TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut); TypedResult saveAccelNoise(C::mip_interface& device); @@ -1590,30 +1598,24 @@ TypedResult defaultAccelNoise(C::mip_interface& device); struct GyroNoise { + /// Parameters FunctionSelector function = static_cast(0); Vector3f noise; ///< Gyro Noise 1-sigma [rad/second] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_GYRO_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroNoise"; static constexpr const char* DOC_NAME = "Gyroscope Noise Standard Deviation"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(noise); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } @@ -1625,31 +1627,39 @@ struct GyroNoise return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f noise; ///< Gyro Noise 1-sigma [rad/second] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_GYRO_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroNoise::Response"; static constexpr const char* DOC_NAME = "Gyroscope Noise Standard Deviation Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f noise; ///< Gyro Noise 1-sigma [rad/second] - + auto asTuple() const + { + return std::make_tuple(noise); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GyroNoise& self); -void extract(::microstrain::Serializer& serializer, GyroNoise& self); - -void insert(::microstrain::Serializer& serializer, const GyroNoise::Response& self); -void extract(::microstrain::Serializer& serializer, GyroNoise::Response& self); - TypedResult writeGyroNoise(C::mip_interface& device, const float* noise); TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut); TypedResult saveGyroNoise(C::mip_interface& device); @@ -1669,31 +1679,25 @@ TypedResult defaultGyroNoise(C::mip_interface& device); struct AccelBiasModel { + /// Parameters FunctionSelector function = static_cast(0); Vector3f beta; ///< Accel Bias Beta [1/second] Vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ACCEL_BIAS_MODEL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelBiasModel"; static constexpr const char* DOC_NAME = "Accelerometer Bias Model Parameters"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(beta,noise); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(beta),std::ref(noise)); } @@ -1705,32 +1709,40 @@ struct AccelBiasModel return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f beta; ///< Accel Bias Beta [1/second] + Vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ACCEL_BIAS_MODEL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelBiasModel::Response"; static constexpr const char* DOC_NAME = "Accelerometer Bias Model Parameters Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f beta; ///< Accel Bias Beta [1/second] - Vector3f noise; ///< Accel Noise 1-sigma [meters/second^2] - + auto asTuple() const + { + return std::make_tuple(beta,noise); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(beta),std::ref(noise)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AccelBiasModel& self); -void extract(::microstrain::Serializer& serializer, AccelBiasModel& self); - -void insert(::microstrain::Serializer& serializer, const AccelBiasModel::Response& self); -void extract(::microstrain::Serializer& serializer, AccelBiasModel::Response& self); - TypedResult writeAccelBiasModel(C::mip_interface& device, const float* beta, const float* noise); TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut); TypedResult saveAccelBiasModel(C::mip_interface& device); @@ -1750,31 +1762,25 @@ TypedResult defaultAccelBiasModel(C::mip_interface& device); struct GyroBiasModel { + /// Parameters FunctionSelector function = static_cast(0); Vector3f beta; ///< Gyro Bias Beta [1/second] Vector3f noise; ///< Gyro Noise 1-sigma [rad/second] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_GYRO_BIAS_MODEL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroBiasModel"; static constexpr const char* DOC_NAME = "Gyroscope Bias Model Parameters"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(beta,noise); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(beta),std::ref(noise)); } @@ -1786,32 +1792,40 @@ struct GyroBiasModel return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f beta; ///< Gyro Bias Beta [1/second] + Vector3f noise; ///< Gyro Noise 1-sigma [rad/second] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_GYRO_BIAS_MODEL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroBiasModel::Response"; static constexpr const char* DOC_NAME = "Gyroscope Bias Model Parameters Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f beta; ///< Gyro Bias Beta [1/second] - Vector3f noise; ///< Gyro Noise 1-sigma [rad/second] - + auto asTuple() const + { + return std::make_tuple(beta,noise); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(beta),std::ref(noise)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GyroBiasModel& self); -void extract(::microstrain::Serializer& serializer, GyroBiasModel& self); - -void insert(::microstrain::Serializer& serializer, const GyroBiasModel::Response& self); -void extract(::microstrain::Serializer& serializer, GyroBiasModel::Response& self); - TypedResult writeGyroBiasModel(C::mip_interface& device, const float* beta, const float* noise); TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut); TypedResult saveGyroBiasModel(C::mip_interface& device); @@ -1838,30 +1852,24 @@ struct AltitudeAiding PRESURE = 1, ///< Enable pressure sensor aiding }; + /// Parameters FunctionSelector function = static_cast(0); AidingSelector selector = static_cast(0); ///< See above + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ALTITUDE_AIDING_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AltitudeAiding"; static constexpr const char* DOC_NAME = "Altitude Aiding Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(selector); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(selector)); } @@ -1873,31 +1881,39 @@ struct AltitudeAiding return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + AidingSelector selector = static_cast(0); ///< See above + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ALTITUDE_AIDING_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AltitudeAiding::Response"; static constexpr const char* DOC_NAME = "Altitude Aiding Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - AidingSelector selector = static_cast(0); ///< See above - + auto asTuple() const + { + return std::make_tuple(selector); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(selector)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AltitudeAiding& self); -void extract(::microstrain::Serializer& serializer, AltitudeAiding& self); - -void insert(::microstrain::Serializer& serializer, const AltitudeAiding::Response& self); -void extract(::microstrain::Serializer& serializer, AltitudeAiding::Response& self); - TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector); TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut); TypedResult saveAltitudeAiding(C::mip_interface& device); @@ -1921,30 +1937,24 @@ struct PitchRollAiding GRAVITY_VEC = 1, ///< Enable gravity vector aiding }; + /// Parameters FunctionSelector function = static_cast(0); AidingSource source = static_cast(0); ///< Controls the aiding source + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PitchRollAiding"; static constexpr const char* DOC_NAME = "Pitch/Roll Aiding Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source)); } @@ -1956,31 +1966,39 @@ struct PitchRollAiding return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + AidingSource source = static_cast(0); ///< Controls the aiding source + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PitchRollAiding::Response"; static constexpr const char* DOC_NAME = "Pitch/Roll Aiding Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - AidingSource source = static_cast(0); ///< Controls the aiding source - + auto asTuple() const + { + return std::make_tuple(source); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const PitchRollAiding& self); -void extract(::microstrain::Serializer& serializer, PitchRollAiding& self); - -void insert(::microstrain::Serializer& serializer, const PitchRollAiding::Response& self); -void extract(::microstrain::Serializer& serializer, PitchRollAiding::Response& self); - TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source); TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut); TypedResult savePitchRollAiding(C::mip_interface& device); @@ -1998,31 +2016,25 @@ TypedResult defaultPitchRollAiding(C::mip_interface& device); struct AutoZupt { + /// Parameters FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< 0 - Disable, 1 - Enable float threshold = 0; ///< [meters/second] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ZUPT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AutoZupt"; static constexpr const char* DOC_NAME = "Zero Velocity Update Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable,threshold); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(threshold)); } @@ -2034,32 +2046,40 @@ struct AutoZupt return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + float threshold = 0; ///< [meters/second] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ZUPT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AutoZupt::Response"; static constexpr const char* DOC_NAME = "Zero Velocity Update Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t enable = 0; ///< 0 - Disable, 1 - Enable - float threshold = 0; ///< [meters/second] - + auto asTuple() const + { + return std::make_tuple(enable,threshold); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(threshold)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AutoZupt& self); -void extract(::microstrain::Serializer& serializer, AutoZupt& self); - -void insert(::microstrain::Serializer& serializer, const AutoZupt::Response& self); -void extract(::microstrain::Serializer& serializer, AutoZupt::Response& self); - TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold); TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut); TypedResult saveAutoZupt(C::mip_interface& device); @@ -2078,31 +2098,25 @@ TypedResult defaultAutoZupt(C::mip_interface& device); struct AutoAngularZupt { + /// Parameters FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< 0 - Disable, 1 - Enable float threshold = 0; ///< [radians/second] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ANGULAR_ZUPT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AutoAngularZupt"; static constexpr const char* DOC_NAME = "Zero Angular Rate Update Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable,threshold); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(threshold)); } @@ -2114,32 +2128,40 @@ struct AutoAngularZupt return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { - static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ANGULAR_ZUPT_CONTROL; + /// Parameters + uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + float threshold = 0; ///< [radians/second] + + /// Descriptors + static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ANGULAR_ZUPT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AutoAngularZupt::Response"; static constexpr const char* DOC_NAME = "Zero Angular Rate Update Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t enable = 0; ///< 0 - Disable, 1 - Enable - float threshold = 0; ///< [radians/second] - + auto asTuple() const + { + return std::make_tuple(enable,threshold); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(threshold)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AutoAngularZupt& self); -void extract(::microstrain::Serializer& serializer, AutoAngularZupt& self); - -void insert(::microstrain::Serializer& serializer, const AutoAngularZupt::Response& self); -void extract(::microstrain::Serializer& serializer, AutoAngularZupt::Response& self); - TypedResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold); TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut); TypedResult saveAutoAngularZupt(C::mip_interface& device); @@ -2156,30 +2178,30 @@ TypedResult defaultAutoAngularZupt(C::mip_interface& device); struct CommandedZupt { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_COMMANDED_ZUPT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CommandedZupt"; static constexpr const char* DOC_NAME = "Commanded Zero Velocity Update"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const CommandedZupt& self); -void extract(::microstrain::Serializer& serializer, CommandedZupt& self); - TypedResult commandedZupt(C::mip_interface& device); ///@} @@ -2192,30 +2214,30 @@ TypedResult commandedZupt(C::mip_interface& device); struct CommandedAngularZupt { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_COMMANDED_ANGULAR_ZUPT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CommandedAngularZupt"; static constexpr const char* DOC_NAME = "Commanded Zero Angular Rate Update"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const CommandedAngularZupt& self); -void extract(::microstrain::Serializer& serializer, CommandedAngularZupt& self); - TypedResult commandedAngularZupt(C::mip_interface& device); ///@} @@ -2230,28 +2252,23 @@ TypedResult commandedAngularZupt(C::mip_interface& device) struct MagCaptureAutoCal { + /// Parameters FunctionSelector function = static_cast(0); + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_MAG_CAPTURE_AUTO_CALIBRATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagCaptureAutoCal"; static constexpr const char* DOC_NAME = "Magnetometer Capture Auto Calibration"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8000; - static constexpr const uint32_t READ_PARAMS = 0x0000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x0000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } @@ -2263,11 +2280,12 @@ struct MagCaptureAutoCal return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const MagCaptureAutoCal& self); -void extract(::microstrain::Serializer& serializer, MagCaptureAutoCal& self); - TypedResult writeMagCaptureAutoCal(C::mip_interface& device); TypedResult saveMagCaptureAutoCal(C::mip_interface& device); @@ -2286,30 +2304,24 @@ TypedResult saveMagCaptureAutoCal(C::mip_interface& device); struct GravityNoise { + /// Parameters FunctionSelector function = static_cast(0); Vector3f noise; ///< Gravity Noise 1-sigma [gauss] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_GRAVITY_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GravityNoise"; static constexpr const char* DOC_NAME = "Gravity Noise Standard Deviation"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(noise); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } @@ -2321,31 +2333,39 @@ struct GravityNoise return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f noise; ///< Gravity Noise 1-sigma [gauss] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_GRAVITY_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GravityNoise::Response"; static constexpr const char* DOC_NAME = "Gravity Noise Standard Deviation Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f noise; ///< Gravity Noise 1-sigma [gauss] - + auto asTuple() const + { + return std::make_tuple(noise); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GravityNoise& self); -void extract(::microstrain::Serializer& serializer, GravityNoise& self); - -void insert(::microstrain::Serializer& serializer, const GravityNoise::Response& self); -void extract(::microstrain::Serializer& serializer, GravityNoise::Response& self); - TypedResult writeGravityNoise(C::mip_interface& device, const float* noise); TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut); TypedResult saveGravityNoise(C::mip_interface& device); @@ -2367,30 +2387,24 @@ TypedResult defaultGravityNoise(C::mip_interface& device); struct PressureAltitudeNoise { + /// Parameters FunctionSelector function = static_cast(0); float noise = 0; ///< Pressure Altitude Noise 1-sigma [m] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_PRESSURE_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PressureAltitudeNoise"; static constexpr const char* DOC_NAME = "Pressure Altitude Noise Standard Deviation"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(noise); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } @@ -2402,31 +2416,39 @@ struct PressureAltitudeNoise return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + float noise = 0; ///< Pressure Altitude Noise 1-sigma [m] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_PRESSURE_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PressureAltitudeNoise::Response"; static constexpr const char* DOC_NAME = "Pressure Altitude Noise Standard Deviation Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - float noise = 0; ///< Pressure Altitude Noise 1-sigma [m] - + auto asTuple() const + { + return std::make_tuple(noise); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const PressureAltitudeNoise& self); -void extract(::microstrain::Serializer& serializer, PressureAltitudeNoise& self); - -void insert(::microstrain::Serializer& serializer, const PressureAltitudeNoise::Response& self); -void extract(::microstrain::Serializer& serializer, PressureAltitudeNoise::Response& self); - TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise); TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut); TypedResult savePressureAltitudeNoise(C::mip_interface& device); @@ -2450,30 +2472,24 @@ TypedResult defaultPressureAltitudeNoise(C::mip_interface struct HardIronOffsetNoise { + /// Parameters FunctionSelector function = static_cast(0); Vector3f noise; ///< Hard Iron Offset Noise 1-sigma [gauss] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_HARD_IRON_OFFSET_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "HardIronOffsetNoise"; static constexpr const char* DOC_NAME = "Hard Iron Offset Process Noise"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(noise); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } @@ -2485,31 +2501,39 @@ struct HardIronOffsetNoise return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f noise; ///< Hard Iron Offset Noise 1-sigma [gauss] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_HARD_IRON_OFFSET_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "HardIronOffsetNoise::Response"; static constexpr const char* DOC_NAME = "Hard Iron Offset Process Noise Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f noise; ///< Hard Iron Offset Noise 1-sigma [gauss] - + auto asTuple() const + { + return std::make_tuple(noise); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const HardIronOffsetNoise& self); -void extract(::microstrain::Serializer& serializer, HardIronOffsetNoise& self); - -void insert(::microstrain::Serializer& serializer, const HardIronOffsetNoise::Response& self); -void extract(::microstrain::Serializer& serializer, HardIronOffsetNoise::Response& self); - TypedResult writeHardIronOffsetNoise(C::mip_interface& device, const float* noise); TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut); TypedResult saveHardIronOffsetNoise(C::mip_interface& device); @@ -2532,30 +2556,24 @@ TypedResult defaultHardIronOffsetNoise(C::mip_interface& de struct SoftIronMatrixNoise { + /// Parameters FunctionSelector function = static_cast(0); Matrix3f noise; ///< Soft Iron Matrix Noise 1-sigma [dimensionless] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SOFT_IRON_MATRIX_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SoftIronMatrixNoise"; static constexpr const char* DOC_NAME = "Soft Iron Offset Process Noise"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(noise); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } @@ -2567,31 +2585,39 @@ struct SoftIronMatrixNoise return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Matrix3f noise; ///< Soft Iron Matrix Noise 1-sigma [dimensionless] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SOFT_IRON_MATRIX_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SoftIronMatrixNoise::Response"; static constexpr const char* DOC_NAME = "Soft Iron Offset Process Noise Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Matrix3f noise; ///< Soft Iron Matrix Noise 1-sigma [dimensionless] - + auto asTuple() const + { + return std::make_tuple(noise); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const SoftIronMatrixNoise& self); -void extract(::microstrain::Serializer& serializer, SoftIronMatrixNoise& self); - -void insert(::microstrain::Serializer& serializer, const SoftIronMatrixNoise::Response& self); -void extract(::microstrain::Serializer& serializer, SoftIronMatrixNoise::Response& self); - TypedResult writeSoftIronMatrixNoise(C::mip_interface& device, const float* noise); TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut); TypedResult saveSoftIronMatrixNoise(C::mip_interface& device); @@ -2614,30 +2640,24 @@ TypedResult defaultSoftIronMatrixNoise(C::mip_interface& de struct MagNoise { + /// Parameters FunctionSelector function = static_cast(0); Vector3f noise; ///< Mag Noise 1-sigma [gauss] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_MAG_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagNoise"; static constexpr const char* DOC_NAME = "Magnetometer Noise Standard Deviation"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(noise); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } @@ -2649,31 +2669,39 @@ struct MagNoise return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Vector3f noise; ///< Mag Noise 1-sigma [gauss] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_MAG_NOISE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagNoise::Response"; static constexpr const char* DOC_NAME = "Magnetometer Noise Standard Deviation Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Vector3f noise; ///< Mag Noise 1-sigma [gauss] - + auto asTuple() const + { + return std::make_tuple(noise); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(noise)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const MagNoise& self); -void extract(::microstrain::Serializer& serializer, MagNoise& self); - -void insert(::microstrain::Serializer& serializer, const MagNoise::Response& self); -void extract(::microstrain::Serializer& serializer, MagNoise::Response& self); - TypedResult writeMagNoise(C::mip_interface& device, const float* noise); TypedResult readMagNoise(C::mip_interface& device, float* noiseOut); TypedResult saveMagNoise(C::mip_interface& device); @@ -2694,31 +2722,25 @@ TypedResult defaultMagNoise(C::mip_interface& device); struct InclinationSource { + /// Parameters FunctionSelector function = static_cast(0); FilterMagParamSource source = static_cast(0); ///< Inclination Source float inclination = 0; ///< Inclination angle [radians] (only required if source = MANUAL) + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_INCLINATION_SOURCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "InclinationSource"; static constexpr const char* DOC_NAME = "Inclination Source"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source,inclination); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(inclination)); } @@ -2730,32 +2752,40 @@ struct InclinationSource return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + FilterMagParamSource source = static_cast(0); ///< Inclination Source + float inclination = 0; ///< Inclination angle [radians] (only required if source = MANUAL) + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_INCLINATION_SOURCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "InclinationSource::Response"; static constexpr const char* DOC_NAME = "Inclination Source Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - FilterMagParamSource source = static_cast(0); ///< Inclination Source - float inclination = 0; ///< Inclination angle [radians] (only required if source = MANUAL) - + auto asTuple() const + { + return std::make_tuple(source,inclination); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(inclination)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const InclinationSource& self); -void extract(::microstrain::Serializer& serializer, InclinationSource& self); - -void insert(::microstrain::Serializer& serializer, const InclinationSource::Response& self); -void extract(::microstrain::Serializer& serializer, InclinationSource::Response& self); - TypedResult writeInclinationSource(C::mip_interface& device, FilterMagParamSource source, float inclination); TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut); TypedResult saveInclinationSource(C::mip_interface& device); @@ -2776,31 +2806,25 @@ TypedResult defaultInclinationSource(C::mip_interface& device struct MagneticDeclinationSource { + /// Parameters FunctionSelector function = static_cast(0); FilterMagParamSource source = static_cast(0); ///< Magnetic field declination angle source float declination = 0; ///< Declination angle [radians] (only required if source = MANUAL) + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_DECLINATION_SOURCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagneticDeclinationSource"; static constexpr const char* DOC_NAME = "Magnetic Field Declination Source Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source,declination); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(declination)); } @@ -2812,32 +2836,40 @@ struct MagneticDeclinationSource return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + FilterMagParamSource source = static_cast(0); ///< Magnetic field declination angle source + float declination = 0; ///< Declination angle [radians] (only required if source = MANUAL) + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_DECLINATION_SOURCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagneticDeclinationSource::Response"; static constexpr const char* DOC_NAME = "Magnetic Field Declination Source Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - FilterMagParamSource source = static_cast(0); ///< Magnetic field declination angle source - float declination = 0; ///< Declination angle [radians] (only required if source = MANUAL) - + auto asTuple() const + { + return std::make_tuple(source,declination); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(declination)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const MagneticDeclinationSource& self); -void extract(::microstrain::Serializer& serializer, MagneticDeclinationSource& self); - -void insert(::microstrain::Serializer& serializer, const MagneticDeclinationSource::Response& self); -void extract(::microstrain::Serializer& serializer, MagneticDeclinationSource::Response& self); - TypedResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource source, float declination); TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut); TypedResult saveMagneticDeclinationSource(C::mip_interface& device); @@ -2857,31 +2889,25 @@ TypedResult defaultMagneticDeclinationSource(C::mip_i struct MagFieldMagnitudeSource { + /// Parameters FunctionSelector function = static_cast(0); FilterMagParamSource source = static_cast(0); ///< Magnetic Field Magnitude Source float magnitude = 0; ///< Magnitude [gauss] (only required if source = MANUAL) + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_MAGNETIC_MAGNITUDE_SOURCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagFieldMagnitudeSource"; static constexpr const char* DOC_NAME = "Magnetic Field Magnitude Source"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source,magnitude); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(magnitude)); } @@ -2893,32 +2919,40 @@ struct MagFieldMagnitudeSource return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + FilterMagParamSource source = static_cast(0); ///< Magnetic Field Magnitude Source + float magnitude = 0; ///< Magnitude [gauss] (only required if source = MANUAL) + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_MAGNETIC_MAGNITUDE_SOURCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagFieldMagnitudeSource::Response"; static constexpr const char* DOC_NAME = "Magnetic Field Magnitude Source Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - FilterMagParamSource source = static_cast(0); ///< Magnetic Field Magnitude Source - float magnitude = 0; ///< Magnitude [gauss] (only required if source = MANUAL) - + auto asTuple() const + { + return std::make_tuple(source,magnitude); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(magnitude)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const MagFieldMagnitudeSource& self); -void extract(::microstrain::Serializer& serializer, MagFieldMagnitudeSource& self); - -void insert(::microstrain::Serializer& serializer, const MagFieldMagnitudeSource::Response& self); -void extract(::microstrain::Serializer& serializer, MagFieldMagnitudeSource::Response& self); - TypedResult writeMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource source, float magnitude); TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut); TypedResult saveMagFieldMagnitudeSource(C::mip_interface& device); @@ -2938,33 +2972,27 @@ TypedResult defaultMagFieldMagnitudeSource(C::mip_inter struct ReferencePosition { + /// Parameters FunctionSelector function = static_cast(0); bool enable = 0; ///< enable/disable double latitude = 0; ///< [degrees] double longitude = 0; ///< [degrees] double altitude = 0; ///< [meters] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_REFERENCE_POSITION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ReferencePosition"; static constexpr const char* DOC_NAME = "Set Reference Position"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x800F; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable,latitude,longitude,altitude); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(latitude),std::ref(longitude),std::ref(altitude)); } @@ -2976,34 +3004,42 @@ struct ReferencePosition return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + bool enable = 0; ///< enable/disable + double latitude = 0; ///< [degrees] + double longitude = 0; ///< [degrees] + double altitude = 0; ///< [meters] + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_REFERENCE_POSITION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ReferencePosition::Response"; static constexpr const char* DOC_NAME = "Set Reference Position Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - bool enable = 0; ///< enable/disable - double latitude = 0; ///< [degrees] - double longitude = 0; ///< [degrees] - double altitude = 0; ///< [meters] - + auto asTuple() const + { + return std::make_tuple(enable,latitude,longitude,altitude); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(latitude),std::ref(longitude),std::ref(altitude)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ReferencePosition& self); -void extract(::microstrain::Serializer& serializer, ReferencePosition& self); - -void insert(::microstrain::Serializer& serializer, const ReferencePosition::Response& self); -void extract(::microstrain::Serializer& serializer, ReferencePosition::Response& self); - TypedResult writeReferencePosition(C::mip_interface& device, bool enable, double latitude, double longitude, double altitude); TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut); TypedResult saveReferencePosition(C::mip_interface& device); @@ -3033,6 +3069,7 @@ TypedResult defaultReferencePosition(C::mip_interface& device struct AccelMagnitudeErrorAdaptiveMeasurement { + /// Parameters FunctionSelector function = static_cast(0); FilterAdaptiveMeasurement adaptive_measurement = static_cast(0); ///< Adaptive measurement selector float frequency = 0; ///< Low-pass filter curoff frequency [hertz] @@ -3042,27 +3079,20 @@ struct AccelMagnitudeErrorAdaptiveMeasurement float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelMagnitudeErrorAdaptiveMeasurement"; static constexpr const char* DOC_NAME = "Gravity Magnitude Error Adaptive Measurement"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x807F; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(adaptive_measurement,frequency,low_limit,high_limit,low_limit_uncertainty,high_limit_uncertainty,minimum_uncertainty); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(adaptive_measurement),std::ref(frequency),std::ref(low_limit),std::ref(high_limit),std::ref(low_limit_uncertainty),std::ref(high_limit_uncertainty),std::ref(minimum_uncertainty)); } @@ -3074,16 +3104,13 @@ struct AccelMagnitudeErrorAdaptiveMeasurement return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { - static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL; - static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "AccelMagnitudeErrorAdaptiveMeasurement::Response"; - static constexpr const char* DOC_NAME = "Gravity Magnitude Error Adaptive Measurement Response"; - - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + /// Parameters FilterAdaptiveMeasurement adaptive_measurement = static_cast(0); ///< Adaptive measurement selector float frequency = 0; ///< Low-pass filter curoff frequency [hertz] float low_limit = 0; ///< [meters/second^2] @@ -3092,19 +3119,30 @@ struct AccelMagnitudeErrorAdaptiveMeasurement float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + /// Descriptors + static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL; + static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "AccelMagnitudeErrorAdaptiveMeasurement::Response"; + static constexpr const char* DOC_NAME = "Gravity Magnitude Error Adaptive Measurement Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + + auto asTuple() const + { + return std::make_tuple(adaptive_measurement,frequency,low_limit,high_limit,low_limit_uncertainty,high_limit_uncertainty,minimum_uncertainty); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(adaptive_measurement),std::ref(frequency),std::ref(low_limit),std::ref(high_limit),std::ref(low_limit_uncertainty),std::ref(high_limit_uncertainty),std::ref(minimum_uncertainty)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement& self); -void extract(::microstrain::Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement& self); - -void insert(::microstrain::Serializer& serializer, const AccelMagnitudeErrorAdaptiveMeasurement::Response& self); -void extract(::microstrain::Serializer& serializer, AccelMagnitudeErrorAdaptiveMeasurement::Response& self); - TypedResult writeAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty); TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut); TypedResult saveAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device); @@ -3129,6 +3167,7 @@ TypedResult defaultAccelMagnitudeErrorAd struct MagMagnitudeErrorAdaptiveMeasurement { + /// Parameters FunctionSelector function = static_cast(0); FilterAdaptiveMeasurement adaptive_measurement = static_cast(0); ///< Adaptive measurement selector float frequency = 0; ///< Low-pass filter curoff frequency [hertz] @@ -3138,27 +3177,20 @@ struct MagMagnitudeErrorAdaptiveMeasurement float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagMagnitudeErrorAdaptiveMeasurement"; static constexpr const char* DOC_NAME = "Magnetometer Magnitude Error Adaptive Measurement"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x807F; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(adaptive_measurement,frequency,low_limit,high_limit,low_limit_uncertainty,high_limit_uncertainty,minimum_uncertainty); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(adaptive_measurement),std::ref(frequency),std::ref(low_limit),std::ref(high_limit),std::ref(low_limit_uncertainty),std::ref(high_limit_uncertainty),std::ref(minimum_uncertainty)); } @@ -3170,16 +3202,13 @@ struct MagMagnitudeErrorAdaptiveMeasurement return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { - static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL; - static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "MagMagnitudeErrorAdaptiveMeasurement::Response"; - static constexpr const char* DOC_NAME = "Magnetometer Magnitude Error Adaptive Measurement Response"; - - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + /// Parameters FilterAdaptiveMeasurement adaptive_measurement = static_cast(0); ///< Adaptive measurement selector float frequency = 0; ///< Low-pass filter curoff frequency [hertz] float low_limit = 0; ///< [meters/second^2] @@ -3188,19 +3217,30 @@ struct MagMagnitudeErrorAdaptiveMeasurement float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + /// Descriptors + static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL; + static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "MagMagnitudeErrorAdaptiveMeasurement::Response"; + static constexpr const char* DOC_NAME = "Magnetometer Magnitude Error Adaptive Measurement Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - auto as_tuple() + auto asTuple() const + { + return std::make_tuple(adaptive_measurement,frequency,low_limit,high_limit,low_limit_uncertainty,high_limit_uncertainty,minimum_uncertainty); + } + + auto asTuple() { return std::make_tuple(std::ref(adaptive_measurement),std::ref(frequency),std::ref(low_limit),std::ref(high_limit),std::ref(low_limit_uncertainty),std::ref(high_limit_uncertainty),std::ref(minimum_uncertainty)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement& self); -void extract(::microstrain::Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement& self); - -void insert(::microstrain::Serializer& serializer, const MagMagnitudeErrorAdaptiveMeasurement::Response& self); -void extract(::microstrain::Serializer& serializer, MagMagnitudeErrorAdaptiveMeasurement::Response& self); - TypedResult writeMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty); TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut); TypedResult saveMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device); @@ -3227,6 +3267,7 @@ TypedResult defaultMagMagnitudeErrorAdapti struct MagDipAngleErrorAdaptiveMeasurement { + /// Parameters FunctionSelector function = static_cast(0); bool enable = 0; ///< Enable/Disable float frequency = 0; ///< Low-pass filter curoff frequency [hertz] @@ -3234,27 +3275,20 @@ struct MagDipAngleErrorAdaptiveMeasurement float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagDipAngleErrorAdaptiveMeasurement"; static constexpr const char* DOC_NAME = "Magnetometer Dig Angle Error Adaptive Measurement"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x801F; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable,frequency,high_limit,high_limit_uncertainty,minimum_uncertainty); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(frequency),std::ref(high_limit),std::ref(high_limit_uncertainty),std::ref(minimum_uncertainty)); } @@ -3266,35 +3300,43 @@ struct MagDipAngleErrorAdaptiveMeasurement return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { - static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL; - static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "MagDipAngleErrorAdaptiveMeasurement::Response"; - static constexpr const char* DOC_NAME = "Magnetometer Dig Angle Error Adaptive Measurement Response"; - - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + /// Parameters bool enable = 0; ///< Enable/Disable float frequency = 0; ///< Low-pass filter curoff frequency [hertz] float high_limit = 0; ///< [meters/second^2] float high_limit_uncertainty = 0; ///< 1-Sigma [meters/second^2] float minimum_uncertainty = 0; ///< 1-Sigma [meters/second^2] + /// Descriptors + static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL; + static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "MagDipAngleErrorAdaptiveMeasurement::Response"; + static constexpr const char* DOC_NAME = "Magnetometer Dig Angle Error Adaptive Measurement Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + + auto asTuple() const + { + return std::make_tuple(enable,frequency,high_limit,high_limit_uncertainty,minimum_uncertainty); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(frequency),std::ref(high_limit),std::ref(high_limit_uncertainty),std::ref(minimum_uncertainty)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement& self); -void extract(::microstrain::Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement& self); - -void insert(::microstrain::Serializer& serializer, const MagDipAngleErrorAdaptiveMeasurement::Response& self); -void extract(::microstrain::Serializer& serializer, MagDipAngleErrorAdaptiveMeasurement::Response& self); - TypedResult writeMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool enable, float frequency, float highLimit, float highLimitUncertainty, float minimumUncertainty); TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut); TypedResult saveMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device); @@ -3327,31 +3369,25 @@ struct AidingMeasurementEnable ALL = 65535, ///< Save/load/reset all options }; + /// Parameters FunctionSelector function = static_cast(0); AidingSource aiding_source = static_cast(0); ///< Aiding measurement source bool enable = 0; ///< Controls the aiding source + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_AIDING_MEASUREMENT_ENABLE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AidingMeasurementEnable"; static constexpr const char* DOC_NAME = "Aiding Measurement Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(aiding_source,enable); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(aiding_source),std::ref(enable)); } @@ -3364,32 +3400,40 @@ struct AidingMeasurementEnable return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + AidingSource aiding_source = static_cast(0); ///< Aiding measurement source + bool enable = 0; ///< Controls the aiding source + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_AIDING_MEASUREMENT_ENABLE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AidingMeasurementEnable::Response"; static constexpr const char* DOC_NAME = "Aiding Measurement Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - AidingSource aiding_source = static_cast(0); ///< Aiding measurement source - bool enable = 0; ///< Controls the aiding source - + auto asTuple() const + { + return std::make_tuple(aiding_source,enable); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(aiding_source),std::ref(enable)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AidingMeasurementEnable& self); -void extract(::microstrain::Serializer& serializer, AidingMeasurementEnable& self); - -void insert(::microstrain::Serializer& serializer, const AidingMeasurementEnable::Response& self); -void extract(::microstrain::Serializer& serializer, AidingMeasurementEnable::Response& self); - TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable); TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut); TypedResult saveAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource); @@ -3408,30 +3452,30 @@ TypedResult defaultAidingMeasurementEnable(C::mip_inter struct Run { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_RUN; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Run"; static constexpr const char* DOC_NAME = "Run Navigation Filter"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const Run& self); -void extract(::microstrain::Serializer& serializer, Run& self); - TypedResult run(C::mip_interface& device); ///@} @@ -3446,32 +3490,26 @@ TypedResult run(C::mip_interface& device); struct KinematicConstraint { + /// Parameters FunctionSelector function = static_cast(0); uint8_t acceleration_constraint_selection = 0; ///< Acceleration constraint:
0=None (default),
1=Zero-acceleration. uint8_t velocity_constraint_selection = 0; ///< 0=None (default),
1=Zero-velocity,
2=Wheeled-vehicle.
uint8_t angular_constraint_selection = 0; ///< 0=None (default), 1=Zero-angular rate (ZUPT). + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_KINEMATIC_CONSTRAINT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "KinematicConstraint"; static constexpr const char* DOC_NAME = "Kinematic Constraint Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8007; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(acceleration_constraint_selection,velocity_constraint_selection,angular_constraint_selection); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(acceleration_constraint_selection),std::ref(velocity_constraint_selection),std::ref(angular_constraint_selection)); } @@ -3483,33 +3521,41 @@ struct KinematicConstraint return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t acceleration_constraint_selection = 0; ///< Acceleration constraint:
0=None (default),
1=Zero-acceleration. + uint8_t velocity_constraint_selection = 0; ///< 0=None (default),
1=Zero-velocity,
2=Wheeled-vehicle.
+ uint8_t angular_constraint_selection = 0; ///< 0=None (default), 1=Zero-angular rate (ZUPT). + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_KINEMATIC_CONSTRAINT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "KinematicConstraint::Response"; static constexpr const char* DOC_NAME = "Kinematic Constraint Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t acceleration_constraint_selection = 0; ///< Acceleration constraint:
0=None (default),
1=Zero-acceleration. - uint8_t velocity_constraint_selection = 0; ///< 0=None (default),
1=Zero-velocity,
2=Wheeled-vehicle.
- uint8_t angular_constraint_selection = 0; ///< 0=None (default), 1=Zero-angular rate (ZUPT). - + auto asTuple() const + { + return std::make_tuple(acceleration_constraint_selection,velocity_constraint_selection,angular_constraint_selection); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(acceleration_constraint_selection),std::ref(velocity_constraint_selection),std::ref(angular_constraint_selection)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const KinematicConstraint& self); -void extract(::microstrain::Serializer& serializer, KinematicConstraint& self); - -void insert(::microstrain::Serializer& serializer, const KinematicConstraint::Response& self); -void extract(::microstrain::Serializer& serializer, KinematicConstraint::Response& self); - TypedResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection); TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut); TypedResult saveKinematicConstraint(C::mip_interface& device); @@ -3532,6 +3578,7 @@ struct InitializationConfiguration { struct AlignmentSelector : Bitfield { + typedef uint8_t Type; enum _enumType : uint8_t { NONE = 0x00, @@ -3551,19 +3598,9 @@ struct InitializationConfiguration AlignmentSelector& operator|=(uint8_t val) { return *this = value | val; } AlignmentSelector& operator&=(uint8_t val) { return *this = value & val; } - bool dualAntenna() const { return (value & DUAL_ANTENNA) > 0; } - void dualAntenna(bool val) { if(val) value |= DUAL_ANTENNA; else value &= ~DUAL_ANTENNA; } - bool kinematic() const { return (value & KINEMATIC) > 0; } - void kinematic(bool val) { if(val) value |= KINEMATIC; else value &= ~KINEMATIC; } - bool magnetometer() const { return (value & MAGNETOMETER) > 0; } - void magnetometer(bool val) { if(val) value |= MAGNETOMETER; else value &= ~MAGNETOMETER; } - bool external() const { return (value & EXTERNAL) > 0; } - void external(bool val) { if(val) value |= EXTERNAL; else value &= ~EXTERNAL; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - enum class InitialConditionSource : uint8_t { AUTO_POS_VEL_ATT = 0, ///< Automatic position, velocity and attitude @@ -3572,6 +3609,7 @@ struct InitializationConfiguration MANUAL = 3, ///< User-specified position, velocity, and attitude. }; + /// Parameters FunctionSelector function = static_cast(0); uint8_t wait_for_run_command = 0; ///< Initialize filter only after receiving "run" command InitialConditionSource initial_cond_src = static_cast(0); ///< Initial condition source: @@ -3583,27 +3621,20 @@ struct InitializationConfiguration Vector3f initial_velocity; ///< User-specified initial platform velocity (units determined by reference frame selector, see note.) FilterReferenceFrame reference_frame_selector = static_cast(0); ///< User-specified initial position/velocity reference frames + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_INITIALIZATION_CONFIGURATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "InitializationConfiguration"; static constexpr const char* DOC_NAME = "Navigation Filter Initialization"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x81FF; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(wait_for_run_command,initial_cond_src,auto_heading_alignment_selector,initial_heading,initial_pitch,initial_roll,initial_position,initial_velocity,reference_frame_selector); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(wait_for_run_command),std::ref(initial_cond_src),std::ref(auto_heading_alignment_selector),std::ref(initial_heading),std::ref(initial_pitch),std::ref(initial_roll),std::ref(initial_position),std::ref(initial_velocity),std::ref(reference_frame_selector)); } @@ -3615,16 +3646,13 @@ struct InitializationConfiguration return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { - static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_INITIALIZATION_CONFIGURATION; - static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "InitializationConfiguration::Response"; - static constexpr const char* DOC_NAME = "Navigation Filter Initialization Response"; - - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + /// Parameters uint8_t wait_for_run_command = 0; ///< Initialize filter only after receiving "run" command InitialConditionSource initial_cond_src = static_cast(0); ///< Initial condition source: AlignmentSelector auto_heading_alignment_selector; ///< Bitfield specifying the allowed automatic heading alignment methods for automatic initial conditions. Bits are set to 1 to enable, and the correspond to the following:
@@ -3635,19 +3663,30 @@ struct InitializationConfiguration Vector3f initial_velocity; ///< User-specified initial platform velocity (units determined by reference frame selector, see note.) FilterReferenceFrame reference_frame_selector = static_cast(0); ///< User-specified initial position/velocity reference frames + /// Descriptors + static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_INITIALIZATION_CONFIGURATION; + static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "InitializationConfiguration::Response"; + static constexpr const char* DOC_NAME = "Navigation Filter Initialization Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; + + auto asTuple() const + { + return std::make_tuple(wait_for_run_command,initial_cond_src,auto_heading_alignment_selector,initial_heading,initial_pitch,initial_roll,initial_position,initial_velocity,reference_frame_selector); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(wait_for_run_command),std::ref(initial_cond_src),std::ref(auto_heading_alignment_selector),std::ref(initial_heading),std::ref(initial_pitch),std::ref(initial_roll),std::ref(initial_position),std::ref(initial_velocity),std::ref(reference_frame_selector)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const InitializationConfiguration& self); -void extract(::microstrain::Serializer& serializer, InitializationConfiguration& self); - -void insert(::microstrain::Serializer& serializer, const InitializationConfiguration::Response& self); -void extract(::microstrain::Serializer& serializer, InitializationConfiguration::Response& self); - TypedResult writeInitializationConfiguration(C::mip_interface& device, uint8_t waitForRunCommand, InitializationConfiguration::InitialConditionSource initialCondSrc, InitializationConfiguration::AlignmentSelector autoHeadingAlignmentSelector, float initialHeading, float initialPitch, float initialRoll, const float* initialPosition, const float* initialVelocity, FilterReferenceFrame referenceFrameSelector); TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut); TypedResult saveInitializationConfiguration(C::mip_interface& device); @@ -3664,31 +3703,25 @@ TypedResult defaultInitializationConfiguration(C::m struct AdaptiveFilterOptions { + /// Parameters FunctionSelector function = static_cast(0); uint8_t level = 0; ///< Auto-adaptive operating level:
0=Off,
1=Conservative,
2=Moderate (default),
3=Aggressive. uint16_t time_limit = 0; ///< Maximum duration of measurement rejection before entering recovery mode (ms) + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ADAPTIVE_FILTER_OPTIONS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AdaptiveFilterOptions"; static constexpr const char* DOC_NAME = "Adaptive Filter Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(level,time_limit); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(level),std::ref(time_limit)); } @@ -3700,32 +3733,40 @@ struct AdaptiveFilterOptions return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t level = 0; ///< Auto-adaptive operating level:
0=Off,
1=Conservative,
2=Moderate (default),
3=Aggressive. + uint16_t time_limit = 0; ///< Maximum duration of measurement rejection before entering recovery mode (ms) + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ADAPTIVE_FILTER_OPTIONS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AdaptiveFilterOptions::Response"; static constexpr const char* DOC_NAME = "Adaptive Filter Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t level = 0; ///< Auto-adaptive operating level:
0=Off,
1=Conservative,
2=Moderate (default),
3=Aggressive. - uint16_t time_limit = 0; ///< Maximum duration of measurement rejection before entering recovery mode (ms) - + auto asTuple() const + { + return std::make_tuple(level,time_limit); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(level),std::ref(time_limit)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const AdaptiveFilterOptions& self); -void extract(::microstrain::Serializer& serializer, AdaptiveFilterOptions& self); - -void insert(::microstrain::Serializer& serializer, const AdaptiveFilterOptions::Response& self); -void extract(::microstrain::Serializer& serializer, AdaptiveFilterOptions::Response& self); - TypedResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit); TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut); TypedResult saveAdaptiveFilterOptions(C::mip_interface& device); @@ -3745,31 +3786,25 @@ TypedResult defaultAdaptiveFilterOptions(C::mip_interface struct MultiAntennaOffset { + /// Parameters FunctionSelector function = static_cast(0); uint8_t receiver_id = 0; ///< Receiver: 1, 2, etc... Vector3f antenna_offset; ///< Antenna lever arm offset vector in the vehicle frame (m) + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_MULTI_ANTENNA_OFFSET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MultiAntennaOffset"; static constexpr const char* DOC_NAME = "GNSS Multi-Antenna Offset Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(receiver_id,antenna_offset); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(receiver_id),std::ref(antenna_offset)); } @@ -3782,32 +3817,40 @@ struct MultiAntennaOffset return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t receiver_id = 0; + Vector3f antenna_offset; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_MULTI_ANTENNA_OFFSET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MultiAntennaOffset::Response"; static constexpr const char* DOC_NAME = "GNSS Multi-Antenna Offset Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t receiver_id = 0; - Vector3f antenna_offset; - + auto asTuple() const + { + return std::make_tuple(receiver_id,antenna_offset); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(receiver_id),std::ref(antenna_offset)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const MultiAntennaOffset& self); -void extract(::microstrain::Serializer& serializer, MultiAntennaOffset& self); - -void insert(::microstrain::Serializer& serializer, const MultiAntennaOffset::Response& self); -void extract(::microstrain::Serializer& serializer, MultiAntennaOffset::Response& self); - TypedResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset); TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut); TypedResult saveMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId); @@ -3824,32 +3867,26 @@ TypedResult defaultMultiAntennaOffset(C::mip_interface& devi struct RelPosConfiguration { + /// Parameters FunctionSelector function = static_cast(0); uint8_t source = 0; ///< 0 - auto (RTK base station), 1 - manual FilterReferenceFrame reference_frame_selector = static_cast(0); ///< ECEF or LLH Vector3d reference_coordinates; ///< reference coordinates, units determined by source selection + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_REL_POS_CONFIGURATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RelPosConfiguration"; static constexpr const char* DOC_NAME = "Relative Position Configuration"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8007; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source,reference_frame_selector,reference_coordinates); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(reference_frame_selector),std::ref(reference_coordinates)); } @@ -3861,33 +3898,41 @@ struct RelPosConfiguration return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t source = 0; ///< 0 - auto (RTK base station), 1 - manual + FilterReferenceFrame reference_frame_selector = static_cast(0); ///< ECEF or LLH + Vector3d reference_coordinates; ///< reference coordinates, units determined by source selection + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_REL_POS_CONFIGURATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RelPosConfiguration::Response"; static constexpr const char* DOC_NAME = "Relative Position Configuration Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t source = 0; ///< 0 - auto (RTK base station), 1 - manual - FilterReferenceFrame reference_frame_selector = static_cast(0); ///< ECEF or LLH - Vector3d reference_coordinates; ///< reference coordinates, units determined by source selection - + auto asTuple() const + { + return std::make_tuple(source,reference_frame_selector,reference_coordinates); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(reference_frame_selector),std::ref(reference_coordinates)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const RelPosConfiguration& self); -void extract(::microstrain::Serializer& serializer, RelPosConfiguration& self); - -void insert(::microstrain::Serializer& serializer, const RelPosConfiguration::Response& self); -void extract(::microstrain::Serializer& serializer, RelPosConfiguration::Response& self); - TypedResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates); TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut); TypedResult saveRelPosConfiguration(C::mip_interface& device); @@ -3916,31 +3961,25 @@ struct RefPointLeverArm VEH = 1, ///< Defines the origin of the vehicle }; + /// Parameters FunctionSelector function = static_cast(0); ReferencePointSelector ref_point_sel = static_cast(0); ///< Reserved, must be 1 Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_REF_POINT_LEVER_ARM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RefPointLeverArm"; static constexpr const char* DOC_NAME = "Reference point lever arm"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(ref_point_sel,lever_arm_offset); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(ref_point_sel),std::ref(lever_arm_offset)); } @@ -3952,32 +3991,40 @@ struct RefPointLeverArm return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + ReferencePointSelector ref_point_sel = static_cast(0); ///< Reserved, must be 1 + Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_REF_POINT_LEVER_ARM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RefPointLeverArm::Response"; static constexpr const char* DOC_NAME = "Reference point lever arm Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - ReferencePointSelector ref_point_sel = static_cast(0); ///< Reserved, must be 1 - Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. - + auto asTuple() const + { + return std::make_tuple(ref_point_sel,lever_arm_offset); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(ref_point_sel),std::ref(lever_arm_offset)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const RefPointLeverArm& self); -void extract(::microstrain::Serializer& serializer, RefPointLeverArm& self); - -void insert(::microstrain::Serializer& serializer, const RefPointLeverArm::Response& self); -void extract(::microstrain::Serializer& serializer, RefPointLeverArm::Response& self); - TypedResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset); TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut); TypedResult saveRefPointLeverArm(C::mip_interface& device); @@ -3996,34 +4043,36 @@ TypedResult defaultRefPointLeverArm(C::mip_interface& device); struct SpeedMeasurement { + /// Parameters uint8_t source = 0; ///< Reserved, must be 1. float time_of_week = 0; ///< GPS time of week when speed was sampled float speed = 0; ///< Estimated speed along vehicle's x-axis (may be positive or negative) [meters/second] float speed_uncertainty = 0; ///< Estimated uncertainty in the speed measurement (1-sigma value) [meters/second] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SPEED_MEASUREMENT; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SpeedMeasurement"; static constexpr const char* DOC_NAME = "Input speed measurement"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source,time_of_week,speed,speed_uncertainty); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(time_of_week),std::ref(speed),std::ref(speed_uncertainty)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const SpeedMeasurement& self); -void extract(::microstrain::Serializer& serializer, SpeedMeasurement& self); - TypedResult speedMeasurement(C::mip_interface& device, uint8_t source, float timeOfWeek, float speed, float speedUncertainty); ///@} @@ -4042,31 +4091,25 @@ TypedResult speedMeasurement(C::mip_interface& device, uint8_t struct SpeedLeverArm { + /// Parameters FunctionSelector function = static_cast(0); uint8_t source = 0; ///< Reserved, must be 1. Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SPEED_LEVER_ARM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SpeedLeverArm"; static constexpr const char* DOC_NAME = "Measurement speed lever arm"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8001; - static constexpr const uint32_t SAVE_PARAMS = 0x8001; - static constexpr const uint32_t LOAD_PARAMS = 0x8001; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8001; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(source,lever_arm_offset); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(lever_arm_offset)); } @@ -4079,32 +4122,40 @@ struct SpeedLeverArm return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t source = 0; ///< Reserved, must be 1. + Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_SPEED_LEVER_ARM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SpeedLeverArm::Response"; static constexpr const char* DOC_NAME = "Measurement speed lever arm Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0001; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t source = 0; ///< Reserved, must be 1. - Vector3f lever_arm_offset; ///< [m] Lever arm offset vector in the vehicle's reference frame. - + auto asTuple() const + { + return std::make_tuple(source,lever_arm_offset); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(source),std::ref(lever_arm_offset)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const SpeedLeverArm& self); -void extract(::microstrain::Serializer& serializer, SpeedLeverArm& self); - -void insert(::microstrain::Serializer& serializer, const SpeedLeverArm::Response& self); -void extract(::microstrain::Serializer& serializer, SpeedLeverArm::Response& self); - TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset); TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut); TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t source); @@ -4127,30 +4178,24 @@ TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_ struct WheeledVehicleConstraintControl { + /// Parameters FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_VEHICLE_CONSTRAINT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "WheeledVehicleConstraintControl"; static constexpr const char* DOC_NAME = "Wheeled Vehicle Constraint Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } @@ -4162,31 +4207,39 @@ struct WheeledVehicleConstraintControl return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_VEHICLE_CONSTRAINT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "WheeledVehicleConstraintControl::Response"; static constexpr const char* DOC_NAME = "Wheeled Vehicle Constraint Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t enable = 0; ///< 0 - Disable, 1 - Enable - + auto asTuple() const + { + return std::make_tuple(enable); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const WheeledVehicleConstraintControl& self); -void extract(::microstrain::Serializer& serializer, WheeledVehicleConstraintControl& self); - -void insert(::microstrain::Serializer& serializer, const WheeledVehicleConstraintControl::Response& self); -void extract(::microstrain::Serializer& serializer, WheeledVehicleConstraintControl::Response& self); - TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable); TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut); TypedResult saveWheeledVehicleConstraintControl(C::mip_interface& device); @@ -4207,30 +4260,24 @@ TypedResult defaultWheeledVehicleConstraintCont struct VerticalGyroConstraintControl { + /// Parameters FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_GYRO_CONSTRAINT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "VerticalGyroConstraintControl"; static constexpr const char* DOC_NAME = "Vertical Gyro Constraint Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } @@ -4242,31 +4289,39 @@ struct VerticalGyroConstraintControl return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_GYRO_CONSTRAINT_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "VerticalGyroConstraintControl::Response"; static constexpr const char* DOC_NAME = "Vertical Gyro Constraint Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t enable = 0; ///< 0 - Disable, 1 - Enable - + auto asTuple() const + { + return std::make_tuple(enable); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const VerticalGyroConstraintControl& self); -void extract(::microstrain::Serializer& serializer, VerticalGyroConstraintControl& self); - -void insert(::microstrain::Serializer& serializer, const VerticalGyroConstraintControl::Response& self); -void extract(::microstrain::Serializer& serializer, VerticalGyroConstraintControl::Response& self); - TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable); TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut); TypedResult saveVerticalGyroConstraintControl(C::mip_interface& device); @@ -4285,31 +4340,25 @@ TypedResult defaultVerticalGyroConstraintControl( struct GnssAntennaCalControl { + /// Parameters FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< 0 - Disable, 1 - Enable float max_offset = 0; ///< Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_ANTENNA_CALIBRATION_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssAntennaCalControl"; static constexpr const char* DOC_NAME = "GNSS Antenna Offset Calibration Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable,max_offset); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(max_offset)); } @@ -4321,32 +4370,40 @@ struct GnssAntennaCalControl return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t enable = 0; ///< 0 - Disable, 1 - Enable + float max_offset = 0; ///< Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::REPLY_ANTENNA_CALIBRATION_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssAntennaCalControl::Response"; static constexpr const char* DOC_NAME = "GNSS Antenna Offset Calibration Control Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t enable = 0; ///< 0 - Disable, 1 - Enable - float max_offset = 0; ///< Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter. - + auto asTuple() const + { + return std::make_tuple(enable,max_offset); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(max_offset)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GnssAntennaCalControl& self); -void extract(::microstrain::Serializer& serializer, GnssAntennaCalControl& self); - -void insert(::microstrain::Serializer& serializer, const GnssAntennaCalControl::Response& self); -void extract(::microstrain::Serializer& serializer, GnssAntennaCalControl::Response& self); - TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset); TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut); TypedResult saveGnssAntennaCalControl(C::mip_interface& device); @@ -4366,31 +4423,33 @@ TypedResult defaultGnssAntennaCalControl(C::mip_interface struct SetInitialHeading { + /// Parameters float heading = 0; ///< Initial heading in radians [-pi, pi] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_filter::CMD_SET_INITIAL_HEADING; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SetInitialHeading"; static constexpr const char* DOC_NAME = "Set Initial Heading Control"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(heading); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(heading)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const SetInitialHeading& self); -void extract(::microstrain::Serializer& serializer, SetInitialHeading& self); - TypedResult setInitialHeading(C::mip_interface& device, float heading); ///@} diff --git a/src/cpp/mip/definitions/commands_gnss.cpp b/src/cpp/mip/definitions/commands_gnss.cpp index 6a866fd6c..4434bf7ff 100644 --- a/src/cpp/mip/definitions/commands_gnss.cpp +++ b/src/cpp/mip/definitions/commands_gnss.cpp @@ -1,188 +1,111 @@ #include "commands_gnss.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace commands_gnss { -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const ReceiverInfo& self) +void ReceiverInfo::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, ReceiverInfo& self) +void ReceiverInfo::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const ReceiverInfo::Response& self) -{ - insert(serializer, self.num_receivers); - - for(unsigned int i=0; i < self.num_receivers; i++) - insert(serializer, self.receiver_info[i]); - -} -void extract(::microstrain::Serializer& serializer, ReceiverInfo::Response& self) -{ - extract_count(serializer, &self.num_receivers, sizeof(self.receiver_info)/sizeof(self.receiver_info[0])); - for(unsigned int i=0; i < self.num_receivers; i++) - extract(serializer, self.receiver_info[i]); - -} - -void insert(::microstrain::Serializer& serializer, const ReceiverInfo::Info& self) -{ - insert(serializer, self.receiver_id); - - insert(serializer, self.mip_data_descriptor_set); - - for(unsigned int i=0; i < 32; i++) - insert(serializer, self.description[i]); - -} -void extract(::microstrain::Serializer& serializer, ReceiverInfo::Info& self) -{ - extract(serializer, self.receiver_id); - - extract(serializer, self.mip_data_descriptor_set); - - for(unsigned int i=0; i < 32; i++) - extract(serializer, self.description[i]); - } TypedResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8_t numReceiversOutMax, ReceiverInfo::Info* receiverInfoOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LIST_RECEIVERS, NULL, 0, REPLY_LIST_RECEIVERS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - extract_count(deserializer, numReceiversOut, numReceiversOutMax); + deserializer.extract_count(*numReceiversOut, numReceiversOutMax); assert(receiverInfoOut || (numReceiversOut == 0)); for(unsigned int i=0; i < *numReceiversOut; i++) - extract(deserializer, receiverInfoOut[i]); + deserializer.extract(receiverInfoOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const SignalConfiguration& self) +void SignalConfiguration::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.gps_enable); + serializer.insert(gps_enable); - insert(serializer, self.glonass_enable); + serializer.insert(glonass_enable); - insert(serializer, self.galileo_enable); + serializer.insert(galileo_enable); - insert(serializer, self.beidou_enable); + serializer.insert(beidou_enable); for(unsigned int i=0; i < 4; i++) - insert(serializer, self.reserved[i]); + serializer.insert(reserved[i]); } } -void extract(::microstrain::Serializer& serializer, SignalConfiguration& self) +void SignalConfiguration::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.gps_enable); + serializer.extract(gps_enable); - extract(serializer, self.glonass_enable); + serializer.extract(glonass_enable); - extract(serializer, self.galileo_enable); + serializer.extract(galileo_enable); - extract(serializer, self.beidou_enable); + serializer.extract(beidou_enable); for(unsigned int i=0; i < 4; i++) - extract(serializer, self.reserved[i]); + serializer.extract(reserved[i]); } } -void insert(::microstrain::Serializer& serializer, const SignalConfiguration::Response& self) -{ - insert(serializer, self.gps_enable); - - insert(serializer, self.glonass_enable); - - insert(serializer, self.galileo_enable); - - insert(serializer, self.beidou_enable); - - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.reserved[i]); - -} -void extract(::microstrain::Serializer& serializer, SignalConfiguration::Response& self) -{ - extract(serializer, self.gps_enable); - - extract(serializer, self.glonass_enable); - - extract(serializer, self.galileo_enable); - - extract(serializer, self.beidou_enable); - - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.reserved[i]); - -} - TypedResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, gpsEnable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(gpsEnable); - insert(serializer, glonassEnable); + serializer.insert(glonassEnable); - insert(serializer, galileoEnable); + serializer.insert(galileoEnable); - insert(serializer, beidouEnable); + serializer.insert(beidouEnable); - assert(reserved || (4 == 0)); + assert(reserved); for(unsigned int i=0; i < 4; i++) - insert(serializer, reserved[i]); + serializer.insert(reserved[i]); assert(serializer.isOk()); @@ -190,125 +113,108 @@ TypedResult writeSignalConfiguration(C::mip_interface& devi } TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_SIGNAL_CONFIGURATION, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(gpsEnableOut); - extract(deserializer, *gpsEnableOut); + deserializer.extract(*gpsEnableOut); assert(glonassEnableOut); - extract(deserializer, *glonassEnableOut); + deserializer.extract(*glonassEnableOut); assert(galileoEnableOut); - extract(deserializer, *galileoEnableOut); + deserializer.extract(*galileoEnableOut); assert(beidouEnableOut); - extract(deserializer, *beidouEnableOut); + deserializer.extract(*beidouEnableOut); - assert(reservedOut || (4 == 0)); + assert(reservedOut); for(unsigned int i=0; i < 4; i++) - extract(deserializer, reservedOut[i]); + deserializer.extract(reservedOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveSignalConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult loadSignalConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultSignalConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const RtkDongleConfiguration& self) +void RtkDongleConfiguration::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.enable); + serializer.insert(enable); for(unsigned int i=0; i < 3; i++) - insert(serializer, self.reserved[i]); + serializer.insert(reserved[i]); } } -void extract(::microstrain::Serializer& serializer, RtkDongleConfiguration& self) +void RtkDongleConfiguration::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.enable); + serializer.extract(enable); for(unsigned int i=0; i < 3; i++) - extract(serializer, self.reserved[i]); + serializer.extract(reserved[i]); } } -void insert(::microstrain::Serializer& serializer, const RtkDongleConfiguration::Response& self) -{ - insert(serializer, self.enable); - - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.reserved[i]); - -} -void extract(::microstrain::Serializer& serializer, RtkDongleConfiguration::Response& self) -{ - extract(serializer, self.enable); - - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.reserved[i]); - -} - TypedResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, enable); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(enable); - assert(reserved || (3 == 0)); + assert(reserved); for(unsigned int i=0; i < 3; i++) - insert(serializer, reserved[i]); + serializer.insert(reserved[i]); assert(serializer.isOk()); @@ -316,57 +222,57 @@ TypedResult writeRtkDongleConfiguration(C::mip_interface } TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - ::microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(enableOut); - extract(deserializer, *enableOut); + deserializer.extract(*enableOut); - assert(reservedOut || (3 == 0)); + assert(reservedOut); for(unsigned int i=0; i < 3; i++) - extract(deserializer, reservedOut[i]); + deserializer.extract(reservedOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveRtkDongleConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult loadRtkDongleConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); } TypedResult defaultRtkDongleConfiguration(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - ::microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); diff --git a/src/cpp/mip/definitions/commands_gnss.hpp b/src/cpp/mip/definitions/commands_gnss.hpp index 998aa5420..5823b8f59 100644 --- a/src/cpp/mip/definitions/commands_gnss.hpp +++ b/src/cpp/mip/definitions/commands_gnss.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -69,60 +67,68 @@ struct ReceiverInfo { struct Info { + /// Parameters uint8_t receiver_id = 0; ///< Receiver id: e.g. 1, 2, etc. uint8_t mip_data_descriptor_set = 0; ///< MIP descriptor set associated with this receiver char description[32] = {0}; ///< Ascii description of receiver. Contains the following info (comma-delimited):
Module name/model
Firmware version info + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::CMD_LIST_RECEIVERS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ReceiverInfo"; static constexpr const char* DOC_NAME = "ReceiverInfo"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t num_receivers = 0; ///< Number of physical receivers in the device + Info receiver_info[5]; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::REPLY_LIST_RECEIVERS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ReceiverInfo::Response"; static constexpr const char* DOC_NAME = "ReceiverInfo Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x0000000C; - uint8_t num_receivers = 0; ///< Number of physical receivers in the device - Info receiver_info[5]; - + auto asTuple() const + { + return std::make_tuple(num_receivers,receiver_info); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(num_receivers),std::ref(receiver_info)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ReceiverInfo& self); -void extract(::microstrain::Serializer& serializer, ReceiverInfo& self); - -void insert(::microstrain::Serializer& serializer, const ReceiverInfo::Info& self); -void extract(::microstrain::Serializer& serializer, ReceiverInfo::Info& self); - -void insert(::microstrain::Serializer& serializer, const ReceiverInfo::Response& self); -void extract(::microstrain::Serializer& serializer, ReceiverInfo::Response& self); - TypedResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8_t numReceiversOutMax, ReceiverInfo::Info* receiverInfoOut); ///@} @@ -136,6 +142,7 @@ TypedResult receiverInfo(C::mip_interface& device, uint8_t* numRec struct SignalConfiguration { + /// Parameters FunctionSelector function = static_cast(0); uint8_t gps_enable = 0; ///< Bitfield 0: Enable L1CA, 1: Enable L2C uint8_t glonass_enable = 0; ///< Bitfield 0: Enable L1OF, 1: Enable L2OF @@ -143,27 +150,20 @@ struct SignalConfiguration uint8_t beidou_enable = 0; ///< Bitfield 0: Enable B1, 1: Enable B2 uint8_t reserved[4] = {0}; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::CMD_SIGNAL_CONFIGURATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SignalConfiguration"; static constexpr const char* DOC_NAME = "SignalConfiguration"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x801F; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(gps_enable,glonass_enable,galileo_enable,beidou_enable,reserved); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(gps_enable),std::ref(glonass_enable),std::ref(galileo_enable),std::ref(beidou_enable),std::ref(reserved)); } @@ -175,35 +175,43 @@ struct SignalConfiguration return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { - static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::REPLY_SIGNAL_CONFIGURATION; - static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "SignalConfiguration::Response"; - static constexpr const char* DOC_NAME = "SignalConfiguration Response"; - - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; + /// Parameters uint8_t gps_enable = 0; ///< Bitfield 0: Enable L1CA, 1: Enable L2C uint8_t glonass_enable = 0; ///< Bitfield 0: Enable L1OF, 1: Enable L2OF uint8_t galileo_enable = 0; ///< Bitfield 0: Enable E1, 1: Enable E5B uint8_t beidou_enable = 0; ///< Bitfield 0: Enable B1, 1: Enable B2 uint8_t reserved[4] = {0}; + /// Descriptors + static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::REPLY_SIGNAL_CONFIGURATION; + static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + static constexpr const char* NAME = "SignalConfiguration::Response"; + static constexpr const char* DOC_NAME = "SignalConfiguration Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - auto as_tuple() + auto asTuple() const + { + return std::make_tuple(gps_enable,glonass_enable,galileo_enable,beidou_enable,reserved); + } + + auto asTuple() { return std::make_tuple(std::ref(gps_enable),std::ref(glonass_enable),std::ref(galileo_enable),std::ref(beidou_enable),std::ref(reserved)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const SignalConfiguration& self); -void extract(::microstrain::Serializer& serializer, SignalConfiguration& self); - -void insert(::microstrain::Serializer& serializer, const SignalConfiguration::Response& self); -void extract(::microstrain::Serializer& serializer, SignalConfiguration::Response& self); - TypedResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved); TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut); TypedResult saveSignalConfiguration(C::mip_interface& device); @@ -221,31 +229,25 @@ TypedResult defaultSignalConfiguration(C::mip_interface& de struct RtkDongleConfiguration { + /// Parameters FunctionSelector function = static_cast(0); uint8_t enable = 0; ///< 0 - Disabled, 1- Enabled uint8_t reserved[3] = {0}; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::CMD_RTK_DONGLE_CONFIGURATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RtkDongleConfiguration"; static constexpr const char* DOC_NAME = "RtkDongleConfiguration"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8003; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(enable,reserved); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(reserved)); } @@ -257,32 +259,40 @@ struct RtkDongleConfiguration return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t enable = 0; + uint8_t reserved[3] = {0}; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_gnss::REPLY_RTK_DONGLE_CONFIGURATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RtkDongleConfiguration::Response"; static constexpr const char* DOC_NAME = "RtkDongleConfiguration Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t enable = 0; - uint8_t reserved[3] = {0}; - + auto asTuple() const + { + return std::make_tuple(enable,reserved); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(enable),std::ref(reserved)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const RtkDongleConfiguration& self); -void extract(::microstrain::Serializer& serializer, RtkDongleConfiguration& self); - -void insert(::microstrain::Serializer& serializer, const RtkDongleConfiguration::Response& self); -void extract(::microstrain::Serializer& serializer, RtkDongleConfiguration::Response& self); - TypedResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved); TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut); TypedResult saveRtkDongleConfiguration(C::mip_interface& device); diff --git a/src/cpp/mip/definitions/commands_rtk.cpp b/src/cpp/mip/definitions/commands_rtk.cpp index 85287fd75..8fb96bff5 100644 --- a/src/cpp/mip/definitions/commands_rtk.cpp +++ b/src/cpp/mip/definitions/commands_rtk.cpp @@ -1,246 +1,168 @@ #include "commands_rtk.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace commands_rtk { -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const GetStatusFlags& self) +void GetStatusFlags::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetStatusFlags& self) +void GetStatusFlags::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetStatusFlags::Response& self) -{ - insert(serializer, self.flags); - -} -void extract(::microstrain::Serializer& serializer, GetStatusFlags::Response& self) -{ - extract(serializer, self.flags); - } TypedResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_STATUS_FLAGS, NULL, 0, REPLY_GET_STATUS_FLAGS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(flagsOut); - extract(deserializer, *flagsOut); + deserializer.extract(*flagsOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const GetImei& self) +void GetImei::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetImei& self) +void GetImei::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetImei::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - insert(serializer, self.IMEI[i]); - -} -void extract(::microstrain::Serializer& serializer, GetImei::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - extract(serializer, self.IMEI[i]); - } TypedResult getImei(C::mip_interface& device, char* imeiOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_IMEI, NULL, 0, REPLY_GET_IMEI, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(imeiOut || (32 == 0)); + assert(imeiOut); for(unsigned int i=0; i < 32; i++) - extract(deserializer, imeiOut[i]); + deserializer.extract(imeiOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const GetImsi& self) +void GetImsi::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetImsi& self) +void GetImsi::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetImsi::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - insert(serializer, self.IMSI[i]); - -} -void extract(::microstrain::Serializer& serializer, GetImsi::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - extract(serializer, self.IMSI[i]); - } TypedResult getImsi(C::mip_interface& device, char* imsiOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_IMSI, NULL, 0, REPLY_GET_IMSI, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(imsiOut || (32 == 0)); + assert(imsiOut); for(unsigned int i=0; i < 32; i++) - extract(deserializer, imsiOut[i]); + deserializer.extract(imsiOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const GetIccid& self) +void GetIccid::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetIccid& self) +void GetIccid::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetIccid::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - insert(serializer, self.ICCID[i]); - -} -void extract(::microstrain::Serializer& serializer, GetIccid::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - extract(serializer, self.ICCID[i]); - } TypedResult getIccid(C::mip_interface& device, char* iccidOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_ICCID, NULL, 0, REPLY_GET_ICCID, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(iccidOut || (32 == 0)); + assert(iccidOut); for(unsigned int i=0; i < 32; i++) - extract(deserializer, iccidOut[i]); + deserializer.extract(iccidOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const ConnectedDeviceType& self) +void ConnectedDeviceType::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.devType); + serializer.insert(devType); } } -void extract(::microstrain::Serializer& serializer, ConnectedDeviceType& self) +void ConnectedDeviceType::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.devType); + serializer.extract(devType); } } -void insert(::microstrain::Serializer& serializer, const ConnectedDeviceType::Response& self) -{ - insert(serializer, self.devType); - -} -void extract(::microstrain::Serializer& serializer, ConnectedDeviceType::Response& self) -{ - extract(serializer, self.devType); - -} - TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, devtype); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(devtype); assert(serializer.isOk()); @@ -248,352 +170,276 @@ TypedResult writeConnectedDeviceType(C::mip_interface& devi } TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length(), REPLY_CONNECTED_DEVICE_TYPE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(devtypeOut); - extract(deserializer, *devtypeOut); + deserializer.extract(*devtypeOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult saveConnectedDeviceType(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::SAVE); + serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); } TypedResult loadConnectedDeviceType(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::LOAD); + serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); } TypedResult defaultConnectedDeviceType(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const GetActCode& self) +void GetActCode::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetActCode& self) +void GetActCode::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetActCode::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - insert(serializer, self.ActivationCode[i]); - -} -void extract(::microstrain::Serializer& serializer, GetActCode::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - extract(serializer, self.ActivationCode[i]); - } TypedResult getActCode(C::mip_interface& device, char* activationcodeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_ACT_CODE, NULL, 0, REPLY_GET_ACT_CODE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(activationcodeOut || (32 == 0)); + assert(activationcodeOut); for(unsigned int i=0; i < 32; i++) - extract(deserializer, activationcodeOut[i]); + deserializer.extract(activationcodeOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const GetModemFirmwareVersion& self) +void GetModemFirmwareVersion::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetModemFirmwareVersion& self) +void GetModemFirmwareVersion::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetModemFirmwareVersion::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - insert(serializer, self.ModemFirmwareVersion[i]); - -} -void extract(::microstrain::Serializer& serializer, GetModemFirmwareVersion::Response& self) -{ - for(unsigned int i=0; i < 32; i++) - extract(serializer, self.ModemFirmwareVersion[i]); - } TypedResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_MODEM_FIRMWARE_VERSION, NULL, 0, REPLY_GET_MODEM_FIRMWARE_VERSION, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); - assert(modemfirmwareversionOut || (32 == 0)); + assert(modemfirmwareversionOut); for(unsigned int i=0; i < 32; i++) - extract(deserializer, modemfirmwareversionOut[i]); + deserializer.extract(modemfirmwareversionOut[i]); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const GetRssi& self) +void GetRssi::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, GetRssi& self) +void GetRssi::extract(Serializer& serializer) { (void)serializer; - (void)self; -} - -void insert(::microstrain::Serializer& serializer, const GetRssi::Response& self) -{ - insert(serializer, self.valid); - - insert(serializer, self.rssi); - - insert(serializer, self.signalQuality); - -} -void extract(::microstrain::Serializer& serializer, GetRssi::Response& self) -{ - extract(serializer, self.valid); - - extract(serializer, self.rssi); - - extract(serializer, self.signalQuality); - } TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_RSSI, NULL, 0, REPLY_GET_RSSI, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(validOut); - extract(deserializer, *validOut); + deserializer.extract(*validOut); assert(rssiOut); - extract(deserializer, *rssiOut); + deserializer.extract(*rssiOut); assert(signalqualityOut); - extract(deserializer, *signalqualityOut); + deserializer.extract(*signalqualityOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const ServiceStatus& self) +void ServiceStatus::insert(Serializer& serializer) const { - insert(serializer, self.reserved1); + serializer.insert(reserved1); - insert(serializer, self.reserved2); + serializer.insert(reserved2); } -void extract(::microstrain::Serializer& serializer, ServiceStatus& self) +void ServiceStatus::extract(Serializer& serializer) { - extract(serializer, self.reserved1); - - extract(serializer, self.reserved2); - -} - -void insert(::microstrain::Serializer& serializer, const ServiceStatus::Response& self) -{ - insert(serializer, self.flags); - - insert(serializer, self.receivedBytes); - - insert(serializer, self.lastBytes); - - insert(serializer, self.lastBytesTime); - -} -void extract(::microstrain::Serializer& serializer, ServiceStatus::Response& self) -{ - extract(serializer, self.flags); - - extract(serializer, self.receivedBytes); - - extract(serializer, self.lastBytes); + serializer.extract(reserved1); - extract(serializer, self.lastBytesTime); + serializer.extract(reserved2); } TypedResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* receivedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, reserved1); + serializer.insert(reserved1); - insert(serializer, reserved2); + serializer.insert(reserved2); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SERVICE_STATUS, buffer, (uint8_t)serializer.length(), REPLY_SERVICE_STATUS, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(flagsOut); - extract(deserializer, *flagsOut); + deserializer.extract(*flagsOut); assert(receivedbytesOut); - extract(deserializer, *receivedbytesOut); + deserializer.extract(*receivedbytesOut); assert(lastbytesOut); - extract(deserializer, *lastbytesOut); + deserializer.extract(*lastbytesOut); assert(lastbytestimeOut); - extract(deserializer, *lastbytestimeOut); + deserializer.extract(*lastbytestimeOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } -void insert(::microstrain::Serializer& serializer, const ProdEraseStorage& self) +void ProdEraseStorage::insert(Serializer& serializer) const { - insert(serializer, self.media); + serializer.insert(media); } -void extract(::microstrain::Serializer& serializer, ProdEraseStorage& self) +void ProdEraseStorage::extract(Serializer& serializer) { - extract(serializer, self.media); + serializer.extract(media); } TypedResult prodEraseStorage(C::mip_interface& device, MediaSelector media) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, media); + serializer.insert(media); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PROD_ERASE_STORAGE, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const LedControl& self) +void LedControl::insert(Serializer& serializer) const { for(unsigned int i=0; i < 3; i++) - insert(serializer, self.primaryColor[i]); + serializer.insert(primaryColor[i]); for(unsigned int i=0; i < 3; i++) - insert(serializer, self.altColor[i]); + serializer.insert(altColor[i]); - insert(serializer, self.act); + serializer.insert(act); - insert(serializer, self.period); + serializer.insert(period); } -void extract(::microstrain::Serializer& serializer, LedControl& self) +void LedControl::extract(Serializer& serializer) { for(unsigned int i=0; i < 3; i++) - extract(serializer, self.primaryColor[i]); + serializer.extract(primaryColor[i]); for(unsigned int i=0; i < 3; i++) - extract(serializer, self.altColor[i]); + serializer.extract(altColor[i]); - extract(serializer, self.act); + serializer.extract(act); - extract(serializer, self.period); + serializer.extract(period); } TypedResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - assert(primarycolor || (3 == 0)); + assert(primarycolor); for(unsigned int i=0; i < 3; i++) - insert(serializer, primarycolor[i]); + serializer.insert(primarycolor[i]); - assert(altcolor || (3 == 0)); + assert(altcolor); for(unsigned int i=0; i < 3; i++) - insert(serializer, altcolor[i]); + serializer.insert(altcolor[i]); - insert(serializer, act); + serializer.insert(act); - insert(serializer, period); + serializer.insert(period); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL, buffer, (uint8_t)serializer.length()); } -void insert(::microstrain::Serializer& serializer, const ModemHardReset& self) +void ModemHardReset::insert(Serializer& serializer) const { (void)serializer; - (void)self; } -void extract(::microstrain::Serializer& serializer, ModemHardReset& self) +void ModemHardReset::extract(Serializer& serializer) { (void)serializer; - (void)self; } TypedResult modemHardReset(C::mip_interface& device) diff --git a/src/cpp/mip/definitions/commands_rtk.hpp b/src/cpp/mip/definitions/commands_rtk.hpp index e28b2fa10..144a6839c 100644 --- a/src/cpp/mip/definitions/commands_rtk.hpp +++ b/src/cpp/mip/definitions/commands_rtk.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -87,6 +85,7 @@ struct GetStatusFlags { struct StatusFlagsLegacy : Bitfield { + typedef uint32_t Type; enum _enumType : uint32_t { NONE = 0x00000000, @@ -113,35 +112,12 @@ struct GetStatusFlags StatusFlagsLegacy& operator|=(uint32_t val) { return *this = value | val; } StatusFlagsLegacy& operator&=(uint32_t val) { return *this = value & val; } - uint32_t controllerstate() const { return (value & CONTROLLERSTATE) >> 0; } - void controllerstate(uint32_t val) { value = (value & ~CONTROLLERSTATE) | (val << 0); } - uint32_t platformstate() const { return (value & PLATFORMSTATE) >> 3; } - void platformstate(uint32_t val) { value = (value & ~PLATFORMSTATE) | (val << 3); } - uint32_t controllerstatuscode() const { return (value & CONTROLLERSTATUSCODE) >> 8; } - void controllerstatuscode(uint32_t val) { value = (value & ~CONTROLLERSTATUSCODE) | (val << 8); } - uint32_t platformstatuscode() const { return (value & PLATFORMSTATUSCODE) >> 11; } - void platformstatuscode(uint32_t val) { value = (value & ~PLATFORMSTATUSCODE) | (val << 11); } - uint32_t resetcode() const { return (value & RESETCODE) >> 14; } - void resetcode(uint32_t val) { value = (value & ~RESETCODE) | (val << 14); } - uint32_t signalquality() const { return (value & SIGNALQUALITY) >> 16; } - void signalquality(uint32_t val) { value = (value & ~SIGNALQUALITY) | (val << 16); } - uint32_t reserved() const { return (value & RESERVED) >> 20; } - void reserved(uint32_t val) { value = (value & ~RESERVED) | (val << 20); } - uint32_t rssi() const { return (value & RSSI) >> 20; } - void rssi(uint32_t val) { value = (value & ~RSSI) | (val << 20); } - uint32_t rsrp() const { return (value & RSRP) >> 26; } - void rsrp(uint32_t val) { value = (value & ~RSRP) | (val << 26); } - uint32_t rsrq() const { return (value & RSRQ) >> 28; } - void rsrq(uint32_t val) { value = (value & ~RSRQ) | (val << 28); } - uint32_t sinr() const { return (value & SINR) >> 30; } - void sinr(uint32_t val) { value = (value & ~SINR) | (val << 30); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - struct StatusFlags : Bitfield { + typedef uint32_t Type; enum _enumType : uint32_t { NONE = 0x00000000, @@ -169,80 +145,60 @@ struct GetStatusFlags StatusFlags& operator|=(uint32_t val) { return *this = value | val; } StatusFlags& operator&=(uint32_t val) { return *this = value & val; } - uint32_t modemState() const { return (value & MODEM_STATE) >> 0; } - void modemState(uint32_t val) { value = (value & ~MODEM_STATE) | (val << 0); } - uint32_t connectionType() const { return (value & CONNECTION_TYPE) >> 4; } - void connectionType(uint32_t val) { value = (value & ~CONNECTION_TYPE) | (val << 4); } - uint32_t rssi() const { return (value & RSSI) >> 8; } - void rssi(uint32_t val) { value = (value & ~RSSI) | (val << 8); } - uint32_t signalQuality() const { return (value & SIGNAL_QUALITY) >> 16; } - void signalQuality(uint32_t val) { value = (value & ~SIGNAL_QUALITY) | (val << 16); } - uint32_t towerChangeIndicator() const { return (value & TOWER_CHANGE_INDICATOR) >> 20; } - void towerChangeIndicator(uint32_t val) { value = (value & ~TOWER_CHANGE_INDICATOR) | (val << 20); } - bool nmeaTimeout() const { return (value & NMEA_TIMEOUT) > 0; } - void nmeaTimeout(bool val) { if(val) value |= NMEA_TIMEOUT; else value &= ~NMEA_TIMEOUT; } - bool serverTimeout() const { return (value & SERVER_TIMEOUT) > 0; } - void serverTimeout(bool val) { if(val) value |= SERVER_TIMEOUT; else value &= ~SERVER_TIMEOUT; } - bool correctionsTimeout() const { return (value & CORRECTIONS_TIMEOUT) > 0; } - void correctionsTimeout(bool val) { if(val) value |= CORRECTIONS_TIMEOUT; else value &= ~CORRECTIONS_TIMEOUT; } - bool deviceOutOfRange() const { return (value & DEVICE_OUT_OF_RANGE) > 0; } - void deviceOutOfRange(bool val) { if(val) value |= DEVICE_OUT_OF_RANGE; else value &= ~DEVICE_OUT_OF_RANGE; } - bool correctionsUnavailable() const { return (value & CORRECTIONS_UNAVAILABLE) > 0; } - void correctionsUnavailable(bool val) { if(val) value |= CORRECTIONS_UNAVAILABLE; else value &= ~CORRECTIONS_UNAVAILABLE; } - bool reserved() const { return (value & RESERVED) > 0; } - void reserved(bool val) { if(val) value |= RESERVED; else value &= ~RESERVED; } - uint32_t version() const { return (value & VERSION) >> 30; } - void version(uint32_t val) { value = (value & ~VERSION) | (val << 30); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_STATUS_FLAGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetStatusFlags"; static constexpr const char* DOC_NAME = "Get RTK Device Status Flags"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + StatusFlags flags; ///< Model number dependent. See above structures. + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_STATUS_FLAGS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetStatusFlags::Response"; static constexpr const char* DOC_NAME = "Get RTK Device Status Flags Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - StatusFlags flags; ///< Model number dependent. See above structures. - + auto asTuple() const + { + return std::make_tuple(flags); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetStatusFlags& self); -void extract(::microstrain::Serializer& serializer, GetStatusFlags& self); - -void insert(::microstrain::Serializer& serializer, const GetStatusFlags::Response& self); -void extract(::microstrain::Serializer& serializer, GetStatusFlags::Response& self); - TypedResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut); ///@} @@ -254,51 +210,57 @@ TypedResult getStatusFlags(C::mip_interface& device, GetStatusFl struct GetImei { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_IMEI; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetImei"; static constexpr const char* DOC_NAME = "Get RTK Device IMEI (International Mobile Equipment Identifier)"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + char IMEI[32] = {0}; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_IMEI; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetImei::Response"; static constexpr const char* DOC_NAME = "Get RTK Device IMEI (International Mobile Equipment Identifier) Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - char IMEI[32] = {0}; - + auto asTuple() const + { + return std::make_tuple(IMEI); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(IMEI)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetImei& self); -void extract(::microstrain::Serializer& serializer, GetImei& self); - -void insert(::microstrain::Serializer& serializer, const GetImei::Response& self); -void extract(::microstrain::Serializer& serializer, GetImei::Response& self); - TypedResult getImei(C::mip_interface& device, char* imeiOut); ///@} @@ -310,51 +272,57 @@ TypedResult getImei(C::mip_interface& device, char* imeiOut); struct GetImsi { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_IMSI; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetImsi"; static constexpr const char* DOC_NAME = "Get RTK Device IMSI (International Mobile Subscriber Identifier)"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + char IMSI[32] = {0}; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_IMSI; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetImsi::Response"; static constexpr const char* DOC_NAME = "Get RTK Device IMSI (International Mobile Subscriber Identifier) Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - char IMSI[32] = {0}; - + auto asTuple() const + { + return std::make_tuple(IMSI); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(IMSI)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetImsi& self); -void extract(::microstrain::Serializer& serializer, GetImsi& self); - -void insert(::microstrain::Serializer& serializer, const GetImsi::Response& self); -void extract(::microstrain::Serializer& serializer, GetImsi::Response& self); - TypedResult getImsi(C::mip_interface& device, char* imsiOut); ///@} @@ -366,51 +334,57 @@ TypedResult getImsi(C::mip_interface& device, char* imsiOut); struct GetIccid { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_ICCID; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetIccid"; static constexpr const char* DOC_NAME = "Get RTK Device ICCID (Integrated Circuit Card Identification [SIM Number])"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + char ICCID[32] = {0}; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_ICCID; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetIccid::Response"; static constexpr const char* DOC_NAME = "Get RTK Device ICCID (Integrated Circuit Card Identification [SIM Number]) Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - char ICCID[32] = {0}; - + auto asTuple() const + { + return std::make_tuple(ICCID); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(ICCID)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetIccid& self); -void extract(::microstrain::Serializer& serializer, GetIccid& self); - -void insert(::microstrain::Serializer& serializer, const GetIccid::Response& self); -void extract(::microstrain::Serializer& serializer, GetIccid::Response& self); - TypedResult getIccid(C::mip_interface& device, char* iccidOut); ///@} @@ -428,30 +402,24 @@ struct ConnectedDeviceType GQ7 = 1, ///< }; + /// Parameters FunctionSelector function = static_cast(0); Type devType = static_cast(0); + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_CONNECTED_DEVICE_TYPE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ConnectedDeviceType"; static constexpr const char* DOC_NAME = "Configure or read the type of the connected device"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x8000; - static constexpr const uint32_t LOAD_PARAMS = 0x8000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(devType); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(devType)); } @@ -463,31 +431,39 @@ struct ConnectedDeviceType return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + Type devType = static_cast(0); + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_CONNECTED_DEVICE_TYPE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ConnectedDeviceType::Response"; static constexpr const char* DOC_NAME = "Configure or read the type of the connected device Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - Type devType = static_cast(0); - + auto asTuple() const + { + return std::make_tuple(devType); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(devType)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ConnectedDeviceType& self); -void extract(::microstrain::Serializer& serializer, ConnectedDeviceType& self); - -void insert(::microstrain::Serializer& serializer, const ConnectedDeviceType::Response& self); -void extract(::microstrain::Serializer& serializer, ConnectedDeviceType::Response& self); - TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype); TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut); TypedResult saveConnectedDeviceType(C::mip_interface& device); @@ -503,51 +479,57 @@ TypedResult defaultConnectedDeviceType(C::mip_interface& de struct GetActCode { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_ACT_CODE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetActCode"; static constexpr const char* DOC_NAME = "Get RTK Device Activation Code"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + char ActivationCode[32] = {0}; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_ACT_CODE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetActCode::Response"; static constexpr const char* DOC_NAME = "Get RTK Device Activation Code Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - char ActivationCode[32] = {0}; - + auto asTuple() const + { + return std::make_tuple(ActivationCode); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(ActivationCode)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetActCode& self); -void extract(::microstrain::Serializer& serializer, GetActCode& self); - -void insert(::microstrain::Serializer& serializer, const GetActCode::Response& self); -void extract(::microstrain::Serializer& serializer, GetActCode::Response& self); - TypedResult getActCode(C::mip_interface& device, char* activationcodeOut); ///@} @@ -559,51 +541,57 @@ TypedResult getActCode(C::mip_interface& device, char* activationcod struct GetModemFirmwareVersion { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_MODEM_FIRMWARE_VERSION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetModemFirmwareVersion"; static constexpr const char* DOC_NAME = "Get RTK Device's Cell Modem Firmware version number"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + char ModemFirmwareVersion[32] = {0}; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_MODEM_FIRMWARE_VERSION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetModemFirmwareVersion::Response"; static constexpr const char* DOC_NAME = "Get RTK Device's Cell Modem Firmware version number Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - char ModemFirmwareVersion[32] = {0}; - + auto asTuple() const + { + return std::make_tuple(ModemFirmwareVersion); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(ModemFirmwareVersion)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetModemFirmwareVersion& self); -void extract(::microstrain::Serializer& serializer, GetModemFirmwareVersion& self); - -void insert(::microstrain::Serializer& serializer, const GetModemFirmwareVersion::Response& self); -void extract(::microstrain::Serializer& serializer, GetModemFirmwareVersion::Response& self); - TypedResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut); ///@} @@ -616,53 +604,59 @@ TypedResult getModemFirmwareVersion(C::mip_interface& d struct GetRssi { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_GET_RSSI; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetRssi"; static constexpr const char* DOC_NAME = "GetRssi"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + bool valid = 0; + int32_t rssi = 0; + int32_t signalQuality = 0; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_GET_RSSI; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GetRssi::Response"; static constexpr const char* DOC_NAME = "GetRssi Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - bool valid = 0; - int32_t rssi = 0; - int32_t signalQuality = 0; - + auto asTuple() const + { + return std::make_tuple(valid,rssi,signalQuality); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(valid),std::ref(rssi),std::ref(signalQuality)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const GetRssi& self); -void extract(::microstrain::Serializer& serializer, GetRssi& self); - -void insert(::microstrain::Serializer& serializer, const GetRssi::Response& self); -void extract(::microstrain::Serializer& serializer, GetRssi::Response& self); - TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut); ///@} @@ -677,6 +671,7 @@ struct ServiceStatus { struct ServiceFlags : Bitfield { + typedef uint8_t Type; enum _enumType : uint8_t { NONE = 0x00, @@ -695,67 +690,67 @@ struct ServiceStatus ServiceFlags& operator|=(uint8_t val) { return *this = value | val; } ServiceFlags& operator&=(uint8_t val) { return *this = value & val; } - bool throttle() const { return (value & THROTTLE) > 0; } - void throttle(bool val) { if(val) value |= THROTTLE; else value &= ~THROTTLE; } - bool correctionsUnavailable() const { return (value & CORRECTIONS_UNAVAILABLE) > 0; } - void correctionsUnavailable(bool val) { if(val) value |= CORRECTIONS_UNAVAILABLE; else value &= ~CORRECTIONS_UNAVAILABLE; } - uint8_t reserved() const { return (value & RESERVED) >> 2; } - void reserved(uint8_t val) { value = (value & ~RESERVED) | (val << 2); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint32_t reserved1 = 0; uint32_t reserved2 = 0; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_SERVICE_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ServiceStatus"; static constexpr const char* DOC_NAME = "ServiceStatus"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(reserved1,reserved2); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(reserved1),std::ref(reserved2)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + ServiceFlags flags; + uint32_t receivedBytes = 0; + uint32_t lastBytes = 0; + uint64_t lastBytesTime = 0; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::REPLY_SERVICE_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ServiceStatus::Response"; static constexpr const char* DOC_NAME = "ServiceStatus Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - ServiceFlags flags; - uint32_t receivedBytes = 0; - uint32_t lastBytes = 0; - uint64_t lastBytesTime = 0; - + auto asTuple() const + { + return std::make_tuple(flags,receivedBytes,lastBytes,lastBytesTime); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(flags),std::ref(receivedBytes),std::ref(lastBytes),std::ref(lastBytesTime)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const ServiceStatus& self); -void extract(::microstrain::Serializer& serializer, ServiceStatus& self); - -void insert(::microstrain::Serializer& serializer, const ServiceStatus::Response& self); -void extract(::microstrain::Serializer& serializer, ServiceStatus::Response& self); - TypedResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* receivedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut); ///@} @@ -769,31 +764,33 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese struct ProdEraseStorage { + /// Parameters MediaSelector media = static_cast(0); + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_PROD_ERASE_STORAGE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ProdEraseStorage"; static constexpr const char* DOC_NAME = "ProdEraseStorage"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(media); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(media)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const ProdEraseStorage& self); -void extract(::microstrain::Serializer& serializer, ProdEraseStorage& self); - TypedResult prodEraseStorage(C::mip_interface& device, MediaSelector media); ///@} @@ -806,34 +803,36 @@ TypedResult prodEraseStorage(C::mip_interface& device, MediaSe struct LedControl { + /// Parameters uint8_t primaryColor[3] = {0}; uint8_t altColor[3] = {0}; LedAction act = static_cast(0); uint32_t period = 0; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "LedControl"; static constexpr const char* DOC_NAME = "LedControl"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(primaryColor,altColor,act,period); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(primaryColor),std::ref(altColor),std::ref(act),std::ref(period)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const LedControl& self); -void extract(::microstrain::Serializer& serializer, LedControl& self); - TypedResult ledControl(C::mip_interface& device, const uint8_t* primarycolor, const uint8_t* altcolor, LedAction act, uint32_t period); ///@} @@ -847,30 +846,30 @@ TypedResult ledControl(C::mip_interface& device, const uint8_t* prim struct ModemHardReset { - + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_rtk::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_rtk::CMD_MODEM_HARD_RESET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ModemHardReset"; static constexpr const char* DOC_NAME = "ModemHardReset"; - static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(); } - auto as_tuple() + auto asTuple() { return std::make_tuple(); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + typedef void Response; }; -void insert(::microstrain::Serializer& serializer, const ModemHardReset& self); -void extract(::microstrain::Serializer& serializer, ModemHardReset& self); - TypedResult modemHardReset(C::mip_interface& device); ///@} diff --git a/src/cpp/mip/definitions/commands_system.cpp b/src/cpp/mip/definitions/commands_system.cpp index bbb5756c1..10133c89d 100644 --- a/src/cpp/mip/definitions/commands_system.cpp +++ b/src/cpp/mip/definitions/commands_system.cpp @@ -1,73 +1,53 @@ #include "commands_system.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace commands_system { -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const CommMode& self) +void CommMode::insert(Serializer& serializer) const { - insert(serializer, self.function); + serializer.insert(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - insert(serializer, self.mode); + serializer.insert(mode); } } -void extract(::microstrain::Serializer& serializer, CommMode& self) +void CommMode::extract(Serializer& serializer) { - extract(serializer, self.function); + serializer.extract(function); - if( self.function == FunctionSelector::WRITE ) + if( function == FunctionSelector::WRITE ) { - extract(serializer, self.mode); + serializer.extract(mode); } } -void insert(::microstrain::Serializer& serializer, const CommMode::Response& self) -{ - insert(serializer, self.mode); - -} -void extract(::microstrain::Serializer& serializer, CommMode::Response& self) -{ - extract(serializer, self.mode); - -} - TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::WRITE); - insert(serializer, mode); + serializer.insert(FunctionSelector::WRITE); + serializer.insert(mode); assert(serializer.isOk()); @@ -75,33 +55,33 @@ TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) } TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::READ); + serializer.insert(FunctionSelector::READ); assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.length(), REPLY_COM_MODE, buffer, &responseLength); - if( result == CmdResult::ACK_OK ) + if( result == MIP_ACK_OK ) { - microstrain::Serializer deserializer(buffer, responseLength); + Serializer deserializer(buffer, responseLength); assert(modeOut); - extract(deserializer, *modeOut); + deserializer.extract(*modeOut); if( deserializer.remaining() != 0 ) - result = CmdResult::STATUS_ERROR; + result = MIP_STATUS_ERROR; } return result; } TypedResult defaultCommMode(C::mip_interface& device) { - uint8_t buffer[C::MIP_FIELD_PAYLOAD_LENGTH_MAX]; - microstrain::Serializer serializer(buffer, sizeof(buffer)); + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); - insert(serializer, FunctionSelector::RESET); + serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.length()); diff --git a/src/cpp/mip/definitions/commands_system.hpp b/src/cpp/mip/definitions/commands_system.hpp index f9b296976..786bce982 100644 --- a/src/cpp/mip/definitions/commands_system.hpp +++ b/src/cpp/mip/definitions/commands_system.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -71,30 +69,24 @@ static constexpr const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_GPS = 0x03; struct CommMode { + /// Parameters FunctionSelector function = static_cast(0); uint8_t mode = 0; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_system::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_system::CMD_COM_MODE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CommMode"; static constexpr const char* DOC_NAME = "CommMode"; - static constexpr const bool HAS_FUNCTION_SELECTOR = true; - static constexpr const uint32_t WRITE_PARAMS = 0x8001; - static constexpr const uint32_t READ_PARAMS = 0x8000; - static constexpr const uint32_t SAVE_PARAMS = 0x0000; - static constexpr const uint32_t LOAD_PARAMS = 0x0000; - static constexpr const uint32_t DEFAULT_PARAMS = 0x8000; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - auto as_tuple() const + auto asTuple() const { return std::make_tuple(mode); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(mode)); } @@ -106,31 +98,39 @@ struct CommMode return cmd; } + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + struct Response { + /// Parameters + uint8_t mode = 0; + + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_system::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_system::REPLY_COM_MODE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CommMode::Response"; static constexpr const char* DOC_NAME = "CommMode Response"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - static constexpr const uint32_t ECHOED_PARAMS = 0x0000; - static constexpr const uint32_t COUNTER_PARAMS = 0x00000000; - uint8_t mode = 0; - + auto asTuple() const + { + return std::make_tuple(mode); + } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(mode)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; }; -void insert(::microstrain::Serializer& serializer, const CommMode& self); -void extract(::microstrain::Serializer& serializer, CommMode& self); - -void insert(::microstrain::Serializer& serializer, const CommMode::Response& self); -void extract(::microstrain::Serializer& serializer, CommMode::Response& self); - TypedResult writeCommMode(C::mip_interface& device, uint8_t mode); TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut); TypedResult defaultCommMode(C::mip_interface& device); diff --git a/src/cpp/mip/definitions/common.hpp b/src/cpp/mip/definitions/common.hpp index c5a96240a..990893277 100644 --- a/src/cpp/mip/definitions/common.hpp +++ b/src/cpp/mip/definitions/common.hpp @@ -1,6 +1,6 @@ #pragma once -#include +#include namespace mip @@ -13,10 +13,10 @@ struct DescriptorRate { uint8_t descriptor; uint16_t decimation; -}; -inline size_t insert(microstrain::Serializer& buffer, const DescriptorRate& self) { return buffer.insert(self.descriptor, self.decimation); } -inline size_t extract(microstrain::Serializer& buffer, DescriptorRate& self) { return buffer.extract(self.descriptor, self.decimation); } + size_t insert(Serializer& buffer) const { return buffer.insert(descriptor, decimation); } + size_t extract(Serializer& buffer) { return buffer.extract(descriptor, decimation); } +}; ////////////////////////////////////////////////////////////////////////////////// @@ -100,6 +100,10 @@ struct Vector /// Get the size of the array size_t size() const { return N; } + /// Pack vector into a raw byte buffer. + size_t insert(Serializer& serializer) const { return serializer.insert(m_data); } + size_t extract(Serializer& serializer) { return serializer.extract(m_data); } + private: T m_data[N]; }; @@ -113,11 +117,11 @@ using Matrix3d = Vector; using Quatf = Vector4f; -template -void insert(::microstrain::Serializer& serializer, const Vector& v) { for(size_t i =0; i -void extract(::microstrain::Serializer& serializer, Vector& v) { for(size_t i =0; i +//void insert(Serializer& serializer, const Vector& v) { for(size_t i =0; i +//void extract(Serializer& serializer, Vector& v) { for(size_t i =0; i +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace data_filter { -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const PositionLlh& self) +void PositionLlh::insert(Serializer& serializer) const { - insert(serializer, self.latitude); + serializer.insert(latitude); - insert(serializer, self.longitude); + serializer.insert(longitude); - insert(serializer, self.ellipsoid_height); + serializer.insert(ellipsoid_height); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, PositionLlh& self) +void PositionLlh::extract(Serializer& serializer) { - extract(serializer, self.latitude); + serializer.extract(latitude); - extract(serializer, self.longitude); + serializer.extract(longitude); - extract(serializer, self.ellipsoid_height); + serializer.extract(ellipsoid_height); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const VelocityNed& self) +void VelocityNed::insert(Serializer& serializer) const { - insert(serializer, self.north); + serializer.insert(north); - insert(serializer, self.east); + serializer.insert(east); - insert(serializer, self.down); + serializer.insert(down); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, VelocityNed& self) +void VelocityNed::extract(Serializer& serializer) { - extract(serializer, self.north); + serializer.extract(north); - extract(serializer, self.east); + serializer.extract(east); - extract(serializer, self.down); + serializer.extract(down); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AttitudeQuaternion& self) +void AttitudeQuaternion::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.q[i]); + serializer.insert(q); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, AttitudeQuaternion& self) +void AttitudeQuaternion::extract(Serializer& serializer) { - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.q[i]); + serializer.extract(q); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AttitudeDcm& self) +void AttitudeDcm::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.dcm[i]); + serializer.insert(dcm); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, AttitudeDcm& self) +void AttitudeDcm::extract(Serializer& serializer) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.dcm[i]); + serializer.extract(dcm); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const EulerAngles& self) +void EulerAngles::insert(Serializer& serializer) const { - insert(serializer, self.roll); + serializer.insert(roll); - insert(serializer, self.pitch); + serializer.insert(pitch); - insert(serializer, self.yaw); + serializer.insert(yaw); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, EulerAngles& self) +void EulerAngles::extract(Serializer& serializer) { - extract(serializer, self.roll); + serializer.extract(roll); - extract(serializer, self.pitch); + serializer.extract(pitch); - extract(serializer, self.yaw); + serializer.extract(yaw); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GyroBias& self) +void GyroBias::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias[i]); + serializer.insert(bias); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GyroBias& self) +void GyroBias::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias[i]); + serializer.extract(bias); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AccelBias& self) +void AccelBias::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias[i]); + serializer.insert(bias); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, AccelBias& self) +void AccelBias::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias[i]); + serializer.extract(bias); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const PositionLlhUncertainty& self) +void PositionLlhUncertainty::insert(Serializer& serializer) const { - insert(serializer, self.north); + serializer.insert(north); - insert(serializer, self.east); + serializer.insert(east); - insert(serializer, self.down); + serializer.insert(down); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, PositionLlhUncertainty& self) +void PositionLlhUncertainty::extract(Serializer& serializer) { - extract(serializer, self.north); + serializer.extract(north); - extract(serializer, self.east); + serializer.extract(east); - extract(serializer, self.down); + serializer.extract(down); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const VelocityNedUncertainty& self) +void VelocityNedUncertainty::insert(Serializer& serializer) const { - insert(serializer, self.north); + serializer.insert(north); - insert(serializer, self.east); + serializer.insert(east); - insert(serializer, self.down); + serializer.insert(down); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, VelocityNedUncertainty& self) +void VelocityNedUncertainty::extract(Serializer& serializer) { - extract(serializer, self.north); + serializer.extract(north); - extract(serializer, self.east); + serializer.extract(east); - extract(serializer, self.down); + serializer.extract(down); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const EulerAnglesUncertainty& self) +void EulerAnglesUncertainty::insert(Serializer& serializer) const { - insert(serializer, self.roll); + serializer.insert(roll); - insert(serializer, self.pitch); + serializer.insert(pitch); - insert(serializer, self.yaw); + serializer.insert(yaw); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, EulerAnglesUncertainty& self) +void EulerAnglesUncertainty::extract(Serializer& serializer) { - extract(serializer, self.roll); + serializer.extract(roll); - extract(serializer, self.pitch); + serializer.extract(pitch); - extract(serializer, self.yaw); + serializer.extract(yaw); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GyroBiasUncertainty& self) +void GyroBiasUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias_uncert[i]); + serializer.insert(bias_uncert); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GyroBiasUncertainty& self) +void GyroBiasUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias_uncert[i]); + serializer.extract(bias_uncert); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AccelBiasUncertainty& self) +void AccelBiasUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias_uncert[i]); + serializer.insert(bias_uncert); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, AccelBiasUncertainty& self) +void AccelBiasUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias_uncert[i]); + serializer.extract(bias_uncert); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const Timestamp& self) +void Timestamp::insert(Serializer& serializer) const { - insert(serializer, self.tow); + serializer.insert(tow); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, Timestamp& self) +void Timestamp::extract(Serializer& serializer) { - extract(serializer, self.tow); + serializer.extract(tow); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const Status& self) +void Status::insert(Serializer& serializer) const { - insert(serializer, self.filter_state); + serializer.insert(filter_state); - insert(serializer, self.dynamics_mode); + serializer.insert(dynamics_mode); - insert(serializer, self.status_flags); + serializer.insert(status_flags); } -void extract(::microstrain::Serializer& serializer, Status& self) +void Status::extract(Serializer& serializer) { - extract(serializer, self.filter_state); + serializer.extract(filter_state); - extract(serializer, self.dynamics_mode); + serializer.extract(dynamics_mode); - extract(serializer, self.status_flags); + serializer.extract(status_flags); } -void insert(::microstrain::Serializer& serializer, const LinearAccel& self) +void LinearAccel::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.accel[i]); + serializer.insert(accel); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, LinearAccel& self) +void LinearAccel::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.accel[i]); + serializer.extract(accel); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GravityVector& self) +void GravityVector::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.gravity[i]); + serializer.insert(gravity); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GravityVector& self) +void GravityVector::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.gravity[i]); + serializer.extract(gravity); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const CompAccel& self) +void CompAccel::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.accel[i]); + serializer.insert(accel); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, CompAccel& self) +void CompAccel::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.accel[i]); + serializer.extract(accel); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const CompAngularRate& self) +void CompAngularRate::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.gyro[i]); + serializer.insert(gyro); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, CompAngularRate& self) +void CompAngularRate::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.gyro[i]); + serializer.extract(gyro); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const QuaternionAttitudeUncertainty& self) +void QuaternionAttitudeUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.q[i]); + serializer.insert(q); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, QuaternionAttitudeUncertainty& self) +void QuaternionAttitudeUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.q[i]); + serializer.extract(q); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const Wgs84GravityMag& self) +void Wgs84GravityMag::insert(Serializer& serializer) const { - insert(serializer, self.magnitude); + serializer.insert(magnitude); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, Wgs84GravityMag& self) +void Wgs84GravityMag::extract(Serializer& serializer) { - extract(serializer, self.magnitude); + serializer.extract(magnitude); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const HeadingUpdateState& self) +void HeadingUpdateState::insert(Serializer& serializer) const { - insert(serializer, self.heading); + serializer.insert(heading); - insert(serializer, self.heading_1sigma); + serializer.insert(heading_1sigma); - insert(serializer, self.source); + serializer.insert(source); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, HeadingUpdateState& self) +void HeadingUpdateState::extract(Serializer& serializer) { - extract(serializer, self.heading); + serializer.extract(heading); - extract(serializer, self.heading_1sigma); + serializer.extract(heading_1sigma); - extract(serializer, self.source); + serializer.extract(source); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MagneticModel& self) +void MagneticModel::insert(Serializer& serializer) const { - insert(serializer, self.intensity_north); + serializer.insert(intensity_north); - insert(serializer, self.intensity_east); + serializer.insert(intensity_east); - insert(serializer, self.intensity_down); + serializer.insert(intensity_down); - insert(serializer, self.inclination); + serializer.insert(inclination); - insert(serializer, self.declination); + serializer.insert(declination); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagneticModel& self) +void MagneticModel::extract(Serializer& serializer) { - extract(serializer, self.intensity_north); + serializer.extract(intensity_north); - extract(serializer, self.intensity_east); + serializer.extract(intensity_east); - extract(serializer, self.intensity_down); + serializer.extract(intensity_down); - extract(serializer, self.inclination); + serializer.extract(inclination); - extract(serializer, self.declination); + serializer.extract(declination); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AccelScaleFactor& self) +void AccelScaleFactor::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.scale_factor[i]); + serializer.insert(scale_factor); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, AccelScaleFactor& self) +void AccelScaleFactor::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.scale_factor[i]); + serializer.extract(scale_factor); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AccelScaleFactorUncertainty& self) +void AccelScaleFactorUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.scale_factor_uncert[i]); + serializer.insert(scale_factor_uncert); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, AccelScaleFactorUncertainty& self) +void AccelScaleFactorUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.scale_factor_uncert[i]); + serializer.extract(scale_factor_uncert); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GyroScaleFactor& self) +void GyroScaleFactor::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.scale_factor[i]); + serializer.insert(scale_factor); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GyroScaleFactor& self) +void GyroScaleFactor::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.scale_factor[i]); + serializer.extract(scale_factor); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GyroScaleFactorUncertainty& self) +void GyroScaleFactorUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.scale_factor_uncert[i]); + serializer.insert(scale_factor_uncert); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GyroScaleFactorUncertainty& self) +void GyroScaleFactorUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.scale_factor_uncert[i]); + serializer.extract(scale_factor_uncert); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MagBias& self) +void MagBias::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias[i]); + serializer.insert(bias); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagBias& self) +void MagBias::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias[i]); + serializer.extract(bias); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MagBiasUncertainty& self) +void MagBiasUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.bias_uncert[i]); + serializer.insert(bias_uncert); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagBiasUncertainty& self) +void MagBiasUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.bias_uncert[i]); + serializer.extract(bias_uncert); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const StandardAtmosphere& self) +void StandardAtmosphere::insert(Serializer& serializer) const { - insert(serializer, self.geometric_altitude); + serializer.insert(geometric_altitude); - insert(serializer, self.geopotential_altitude); + serializer.insert(geopotential_altitude); - insert(serializer, self.standard_temperature); + serializer.insert(standard_temperature); - insert(serializer, self.standard_pressure); + serializer.insert(standard_pressure); - insert(serializer, self.standard_density); + serializer.insert(standard_density); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, StandardAtmosphere& self) +void StandardAtmosphere::extract(Serializer& serializer) { - extract(serializer, self.geometric_altitude); + serializer.extract(geometric_altitude); - extract(serializer, self.geopotential_altitude); + serializer.extract(geopotential_altitude); - extract(serializer, self.standard_temperature); + serializer.extract(standard_temperature); - extract(serializer, self.standard_pressure); + serializer.extract(standard_pressure); - extract(serializer, self.standard_density); + serializer.extract(standard_density); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const PressureAltitude& self) +void PressureAltitude::insert(Serializer& serializer) const { - insert(serializer, self.pressure_altitude); + serializer.insert(pressure_altitude); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, PressureAltitude& self) +void PressureAltitude::extract(Serializer& serializer) { - extract(serializer, self.pressure_altitude); + serializer.extract(pressure_altitude); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const DensityAltitude& self) +void DensityAltitude::insert(Serializer& serializer) const { - insert(serializer, self.density_altitude); + serializer.insert(density_altitude); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, DensityAltitude& self) +void DensityAltitude::extract(Serializer& serializer) { - extract(serializer, self.density_altitude); + serializer.extract(density_altitude); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AntennaOffsetCorrection& self) +void AntennaOffsetCorrection::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset[i]); + serializer.insert(offset); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrection& self) +void AntennaOffsetCorrection::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset[i]); + serializer.extract(offset); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AntennaOffsetCorrectionUncertainty& self) +void AntennaOffsetCorrectionUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset_uncert[i]); + serializer.insert(offset_uncert); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrectionUncertainty& self) +void AntennaOffsetCorrectionUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset_uncert[i]); + serializer.extract(offset_uncert); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MultiAntennaOffsetCorrection& self) +void MultiAntennaOffsetCorrection::insert(Serializer& serializer) const { - insert(serializer, self.receiver_id); + serializer.insert(receiver_id); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset[i]); + serializer.insert(offset); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrection& self) +void MultiAntennaOffsetCorrection::extract(Serializer& serializer) { - extract(serializer, self.receiver_id); + serializer.extract(receiver_id); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset[i]); + serializer.extract(offset); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self) +void MultiAntennaOffsetCorrectionUncertainty::insert(Serializer& serializer) const { - insert(serializer, self.receiver_id); + serializer.insert(receiver_id); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.offset_uncert[i]); + serializer.insert(offset_uncert); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrectionUncertainty& self) +void MultiAntennaOffsetCorrectionUncertainty::extract(Serializer& serializer) { - extract(serializer, self.receiver_id); + serializer.extract(receiver_id); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.offset_uncert[i]); + serializer.extract(offset_uncert); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MagnetometerOffset& self) +void MagnetometerOffset::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.hard_iron[i]); + serializer.insert(hard_iron); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagnetometerOffset& self) +void MagnetometerOffset::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.hard_iron[i]); + serializer.extract(hard_iron); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MagnetometerMatrix& self) +void MagnetometerMatrix::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.soft_iron[i]); + serializer.insert(soft_iron); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagnetometerMatrix& self) +void MagnetometerMatrix::extract(Serializer& serializer) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.soft_iron[i]); + serializer.extract(soft_iron); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MagnetometerOffsetUncertainty& self) +void MagnetometerOffsetUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.hard_iron_uncertainty[i]); + serializer.insert(hard_iron_uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagnetometerOffsetUncertainty& self) +void MagnetometerOffsetUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.hard_iron_uncertainty[i]); + serializer.extract(hard_iron_uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MagnetometerMatrixUncertainty& self) +void MagnetometerMatrixUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.soft_iron_uncertainty[i]); + serializer.insert(soft_iron_uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagnetometerMatrixUncertainty& self) +void MagnetometerMatrixUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.soft_iron_uncertainty[i]); + serializer.extract(soft_iron_uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MagnetometerCovarianceMatrix& self) +void MagnetometerCovarianceMatrix::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.covariance[i]); + serializer.insert(covariance); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagnetometerCovarianceMatrix& self) +void MagnetometerCovarianceMatrix::extract(Serializer& serializer) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.covariance[i]); + serializer.extract(covariance); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const MagnetometerResidualVector& self) +void MagnetometerResidualVector::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.residual[i]); + serializer.insert(residual); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, MagnetometerResidualVector& self) +void MagnetometerResidualVector::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.residual[i]); + serializer.extract(residual); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const ClockCorrection& self) +void ClockCorrection::insert(Serializer& serializer) const { - insert(serializer, self.receiver_id); + serializer.insert(receiver_id); - insert(serializer, self.bias); + serializer.insert(bias); - insert(serializer, self.bias_drift); + serializer.insert(bias_drift); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, ClockCorrection& self) +void ClockCorrection::extract(Serializer& serializer) { - extract(serializer, self.receiver_id); + serializer.extract(receiver_id); - extract(serializer, self.bias); + serializer.extract(bias); - extract(serializer, self.bias_drift); + serializer.extract(bias_drift); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const ClockCorrectionUncertainty& self) +void ClockCorrectionUncertainty::insert(Serializer& serializer) const { - insert(serializer, self.receiver_id); + serializer.insert(receiver_id); - insert(serializer, self.bias_uncertainty); + serializer.insert(bias_uncertainty); - insert(serializer, self.bias_drift_uncertainty); + serializer.insert(bias_drift_uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, ClockCorrectionUncertainty& self) +void ClockCorrectionUncertainty::extract(Serializer& serializer) { - extract(serializer, self.receiver_id); + serializer.extract(receiver_id); - extract(serializer, self.bias_uncertainty); + serializer.extract(bias_uncertainty); - extract(serializer, self.bias_drift_uncertainty); + serializer.extract(bias_drift_uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GnssPosAidStatus& self) +void GnssPosAidStatus::insert(Serializer& serializer) const { - insert(serializer, self.receiver_id); + serializer.insert(receiver_id); - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.status); + serializer.insert(status); for(unsigned int i=0; i < 8; i++) - insert(serializer, self.reserved[i]); + serializer.insert(reserved[i]); } -void extract(::microstrain::Serializer& serializer, GnssPosAidStatus& self) +void GnssPosAidStatus::extract(Serializer& serializer) { - extract(serializer, self.receiver_id); + serializer.extract(receiver_id); - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.status); + serializer.extract(status); for(unsigned int i=0; i < 8; i++) - extract(serializer, self.reserved[i]); + serializer.extract(reserved[i]); } -void insert(::microstrain::Serializer& serializer, const GnssAttAidStatus& self) +void GnssAttAidStatus::insert(Serializer& serializer) const { - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.status); + serializer.insert(status); for(unsigned int i=0; i < 8; i++) - insert(serializer, self.reserved[i]); + serializer.insert(reserved[i]); } -void extract(::microstrain::Serializer& serializer, GnssAttAidStatus& self) +void GnssAttAidStatus::extract(Serializer& serializer) { - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.status); + serializer.extract(status); for(unsigned int i=0; i < 8; i++) - extract(serializer, self.reserved[i]); + serializer.extract(reserved[i]); } -void insert(::microstrain::Serializer& serializer, const HeadAidStatus& self) +void HeadAidStatus::insert(Serializer& serializer) const { - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.type); + serializer.insert(type); for(unsigned int i=0; i < 2; i++) - insert(serializer, self.reserved[i]); + serializer.insert(reserved[i]); } -void extract(::microstrain::Serializer& serializer, HeadAidStatus& self) +void HeadAidStatus::extract(Serializer& serializer) { - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.type); + serializer.extract(type); for(unsigned int i=0; i < 2; i++) - extract(serializer, self.reserved[i]); + serializer.extract(reserved[i]); } -void insert(::microstrain::Serializer& serializer, const RelPosNed& self) +void RelPosNed::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.relative_position[i]); + serializer.insert(relative_position); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, RelPosNed& self) +void RelPosNed::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.relative_position[i]); + serializer.extract(relative_position); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const EcefPos& self) +void EcefPos::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.position_ecef[i]); + serializer.insert(position_ecef); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, EcefPos& self) +void EcefPos::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.position_ecef[i]); + serializer.extract(position_ecef); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const EcefVel& self) +void EcefVel::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.velocity_ecef[i]); + serializer.insert(velocity_ecef); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, EcefVel& self) +void EcefVel::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.velocity_ecef[i]); + serializer.extract(velocity_ecef); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const EcefPosUncertainty& self) +void EcefPosUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.pos_uncertainty[i]); + serializer.insert(pos_uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, EcefPosUncertainty& self) +void EcefPosUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.pos_uncertainty[i]); + serializer.extract(pos_uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const EcefVelUncertainty& self) +void EcefVelUncertainty::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.vel_uncertainty[i]); + serializer.insert(vel_uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, EcefVelUncertainty& self) +void EcefVelUncertainty::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.vel_uncertainty[i]); + serializer.extract(vel_uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AidingMeasurementSummary& self) +void AidingMeasurementSummary::insert(Serializer& serializer) const { - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.source); + serializer.insert(source); - insert(serializer, self.type); + serializer.insert(type); - insert(serializer, self.indicator); + serializer.insert(indicator); } -void extract(::microstrain::Serializer& serializer, AidingMeasurementSummary& self) +void AidingMeasurementSummary::extract(Serializer& serializer) { - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.source); + serializer.extract(source); - extract(serializer, self.type); + serializer.extract(type); - extract(serializer, self.indicator); + serializer.extract(indicator); } -void insert(::microstrain::Serializer& serializer, const OdometerScaleFactorError& self) +void OdometerScaleFactorError::insert(Serializer& serializer) const { - insert(serializer, self.scale_factor_error); + serializer.insert(scale_factor_error); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, OdometerScaleFactorError& self) +void OdometerScaleFactorError::extract(Serializer& serializer) { - extract(serializer, self.scale_factor_error); + serializer.extract(scale_factor_error); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const OdometerScaleFactorErrorUncertainty& self) +void OdometerScaleFactorErrorUncertainty::insert(Serializer& serializer) const { - insert(serializer, self.scale_factor_error_uncertainty); + serializer.insert(scale_factor_error_uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, OdometerScaleFactorErrorUncertainty& self) +void OdometerScaleFactorErrorUncertainty::extract(Serializer& serializer) { - extract(serializer, self.scale_factor_error_uncertainty); + serializer.extract(scale_factor_error_uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GnssDualAntennaStatus& self) +void GnssDualAntennaStatus::insert(Serializer& serializer) const { - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.heading); + serializer.insert(heading); - insert(serializer, self.heading_unc); + serializer.insert(heading_unc); - insert(serializer, self.fix_type); + serializer.insert(fix_type); - insert(serializer, self.status_flags); + serializer.insert(status_flags); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GnssDualAntennaStatus& self) +void GnssDualAntennaStatus::extract(Serializer& serializer) { - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.heading); + serializer.extract(heading); - extract(serializer, self.heading_unc); + serializer.extract(heading_unc); - extract(serializer, self.fix_type); + serializer.extract(fix_type); - extract(serializer, self.status_flags); + serializer.extract(status_flags); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const AidingFrameConfigError& self) +void AidingFrameConfigError::insert(Serializer& serializer) const { - insert(serializer, self.frame_id); + serializer.insert(frame_id); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.translation[i]); + serializer.insert(translation); - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.attitude[i]); + serializer.insert(attitude); } -void extract(::microstrain::Serializer& serializer, AidingFrameConfigError& self) +void AidingFrameConfigError::extract(Serializer& serializer) { - extract(serializer, self.frame_id); + serializer.extract(frame_id); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.translation[i]); + serializer.extract(translation); - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.attitude[i]); + serializer.extract(attitude); } -void insert(::microstrain::Serializer& serializer, const AidingFrameConfigErrorUncertainty& self) +void AidingFrameConfigErrorUncertainty::insert(Serializer& serializer) const { - insert(serializer, self.frame_id); + serializer.insert(frame_id); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.translation_unc[i]); + serializer.insert(translation_unc); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.attitude_unc[i]); + serializer.insert(attitude_unc); } -void extract(::microstrain::Serializer& serializer, AidingFrameConfigErrorUncertainty& self) +void AidingFrameConfigErrorUncertainty::extract(Serializer& serializer) { - extract(serializer, self.frame_id); + serializer.extract(frame_id); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.translation_unc[i]); + serializer.extract(translation_unc); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.attitude_unc[i]); + serializer.extract(attitude_unc); } diff --git a/src/cpp/mip/definitions/data_filter.hpp b/src/cpp/mip/definitions/data_filter.hpp index a9290b52c..e44d145ee 100644 --- a/src/cpp/mip/definitions/data_filter.hpp +++ b/src/cpp/mip/definitions/data_filter.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -123,6 +121,7 @@ enum class FilterDynamicsMode : uint16_t struct FilterStatusFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -166,67 +165,9 @@ struct FilterStatusFlags : Bitfield FilterStatusFlags& operator|=(uint16_t val) { return *this = value | val; } FilterStatusFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gx5InitNoAttitude() const { return (value & GX5_INIT_NO_ATTITUDE) > 0; } - void gx5InitNoAttitude(bool val) { if(val) value |= GX5_INIT_NO_ATTITUDE; else value &= ~GX5_INIT_NO_ATTITUDE; } - bool gx5InitNoPositionVelocity() const { return (value & GX5_INIT_NO_POSITION_VELOCITY) > 0; } - void gx5InitNoPositionVelocity(bool val) { if(val) value |= GX5_INIT_NO_POSITION_VELOCITY; else value &= ~GX5_INIT_NO_POSITION_VELOCITY; } - bool gx5RunImuUnavailable() const { return (value & GX5_RUN_IMU_UNAVAILABLE) > 0; } - void gx5RunImuUnavailable(bool val) { if(val) value |= GX5_RUN_IMU_UNAVAILABLE; else value &= ~GX5_RUN_IMU_UNAVAILABLE; } - bool gx5RunGpsUnavailable() const { return (value & GX5_RUN_GPS_UNAVAILABLE) > 0; } - void gx5RunGpsUnavailable(bool val) { if(val) value |= GX5_RUN_GPS_UNAVAILABLE; else value &= ~GX5_RUN_GPS_UNAVAILABLE; } - bool gx5RunMatrixSingularity() const { return (value & GX5_RUN_MATRIX_SINGULARITY) > 0; } - void gx5RunMatrixSingularity(bool val) { if(val) value |= GX5_RUN_MATRIX_SINGULARITY; else value &= ~GX5_RUN_MATRIX_SINGULARITY; } - bool gx5RunPositionCovarianceWarning() const { return (value & GX5_RUN_POSITION_COVARIANCE_WARNING) > 0; } - void gx5RunPositionCovarianceWarning(bool val) { if(val) value |= GX5_RUN_POSITION_COVARIANCE_WARNING; else value &= ~GX5_RUN_POSITION_COVARIANCE_WARNING; } - bool gx5RunVelocityCovarianceWarning() const { return (value & GX5_RUN_VELOCITY_COVARIANCE_WARNING) > 0; } - void gx5RunVelocityCovarianceWarning(bool val) { if(val) value |= GX5_RUN_VELOCITY_COVARIANCE_WARNING; else value &= ~GX5_RUN_VELOCITY_COVARIANCE_WARNING; } - bool gx5RunAttitudeCovarianceWarning() const { return (value & GX5_RUN_ATTITUDE_COVARIANCE_WARNING) > 0; } - void gx5RunAttitudeCovarianceWarning(bool val) { if(val) value |= GX5_RUN_ATTITUDE_COVARIANCE_WARNING; else value &= ~GX5_RUN_ATTITUDE_COVARIANCE_WARNING; } - bool gx5RunNanInSolutionWarning() const { return (value & GX5_RUN_NAN_IN_SOLUTION_WARNING) > 0; } - void gx5RunNanInSolutionWarning(bool val) { if(val) value |= GX5_RUN_NAN_IN_SOLUTION_WARNING; else value &= ~GX5_RUN_NAN_IN_SOLUTION_WARNING; } - bool gx5RunGyroBiasEstHighWarning() const { return (value & GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING) > 0; } - void gx5RunGyroBiasEstHighWarning(bool val) { if(val) value |= GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING; else value &= ~GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING; } - bool gx5RunAccelBiasEstHighWarning() const { return (value & GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING) > 0; } - void gx5RunAccelBiasEstHighWarning(bool val) { if(val) value |= GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING; else value &= ~GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING; } - bool gx5RunGyroScaleFactorEstHighWarning() const { return (value & GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING) > 0; } - void gx5RunGyroScaleFactorEstHighWarning(bool val) { if(val) value |= GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING; else value &= ~GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING; } - bool gx5RunAccelScaleFactorEstHighWarning() const { return (value & GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING) > 0; } - void gx5RunAccelScaleFactorEstHighWarning(bool val) { if(val) value |= GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING; else value &= ~GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING; } - bool gx5RunMagBiasEstHighWarning() const { return (value & GX5_RUN_MAG_BIAS_EST_HIGH_WARNING) > 0; } - void gx5RunMagBiasEstHighWarning(bool val) { if(val) value |= GX5_RUN_MAG_BIAS_EST_HIGH_WARNING; else value &= ~GX5_RUN_MAG_BIAS_EST_HIGH_WARNING; } - bool gx5RunAntOffsetCorrectionEstHighWarning() const { return (value & GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING) > 0; } - void gx5RunAntOffsetCorrectionEstHighWarning(bool val) { if(val) value |= GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING; else value &= ~GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING; } - bool gx5RunMagHardIronEstHighWarning() const { return (value & GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING) > 0; } - void gx5RunMagHardIronEstHighWarning(bool val) { if(val) value |= GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING; else value &= ~GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING; } - bool gx5RunMagSoftIronEstHighWarning() const { return (value & GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING) > 0; } - void gx5RunMagSoftIronEstHighWarning(bool val) { if(val) value |= GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING; else value &= ~GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING; } - uint16_t gq7FilterCondition() const { return (value & GQ7_FILTER_CONDITION) >> 0; } - void gq7FilterCondition(uint16_t val) { value = (value & ~GQ7_FILTER_CONDITION) | (val << 0); } - bool gq7RollPitchWarning() const { return (value & GQ7_ROLL_PITCH_WARNING) > 0; } - void gq7RollPitchWarning(bool val) { if(val) value |= GQ7_ROLL_PITCH_WARNING; else value &= ~GQ7_ROLL_PITCH_WARNING; } - bool gq7HeadingWarning() const { return (value & GQ7_HEADING_WARNING) > 0; } - void gq7HeadingWarning(bool val) { if(val) value |= GQ7_HEADING_WARNING; else value &= ~GQ7_HEADING_WARNING; } - bool gq7PositionWarning() const { return (value & GQ7_POSITION_WARNING) > 0; } - void gq7PositionWarning(bool val) { if(val) value |= GQ7_POSITION_WARNING; else value &= ~GQ7_POSITION_WARNING; } - bool gq7VelocityWarning() const { return (value & GQ7_VELOCITY_WARNING) > 0; } - void gq7VelocityWarning(bool val) { if(val) value |= GQ7_VELOCITY_WARNING; else value &= ~GQ7_VELOCITY_WARNING; } - bool gq7ImuBiasWarning() const { return (value & GQ7_IMU_BIAS_WARNING) > 0; } - void gq7ImuBiasWarning(bool val) { if(val) value |= GQ7_IMU_BIAS_WARNING; else value &= ~GQ7_IMU_BIAS_WARNING; } - bool gq7GnssClkWarning() const { return (value & GQ7_GNSS_CLK_WARNING) > 0; } - void gq7GnssClkWarning(bool val) { if(val) value |= GQ7_GNSS_CLK_WARNING; else value &= ~GQ7_GNSS_CLK_WARNING; } - bool gq7AntennaLeverArmWarning() const { return (value & GQ7_ANTENNA_LEVER_ARM_WARNING) > 0; } - void gq7AntennaLeverArmWarning(bool val) { if(val) value |= GQ7_ANTENNA_LEVER_ARM_WARNING; else value &= ~GQ7_ANTENNA_LEVER_ARM_WARNING; } - bool gq7MountingTransformWarning() const { return (value & GQ7_MOUNTING_TRANSFORM_WARNING) > 0; } - void gq7MountingTransformWarning(bool val) { if(val) value |= GQ7_MOUNTING_TRANSFORM_WARNING; else value &= ~GQ7_MOUNTING_TRANSFORM_WARNING; } - bool gq7TimeSyncWarning() const { return (value & GQ7_TIME_SYNC_WARNING) > 0; } - void gq7TimeSyncWarning(bool val) { if(val) value |= GQ7_TIME_SYNC_WARNING; else value &= ~GQ7_TIME_SYNC_WARNING; } - uint16_t gq7SolutionError() const { return (value & GQ7_SOLUTION_ERROR) >> 12; } - void gq7SolutionError(uint16_t val) { value = (value & ~GQ7_SOLUTION_ERROR) | (val << 12); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - enum class FilterAidingMeasurementType : uint8_t { GNSS = 1, ///< @@ -245,6 +186,7 @@ enum class FilterAidingMeasurementType : uint8_t struct FilterMeasurementIndicator : Bitfield { + typedef uint8_t Type; enum _enumType : uint8_t { NONE = 0x00, @@ -266,25 +208,12 @@ struct FilterMeasurementIndicator : Bitfield FilterMeasurementIndicator& operator|=(uint8_t val) { return *this = value | val; } FilterMeasurementIndicator& operator&=(uint8_t val) { return *this = value & val; } - bool enabled() const { return (value & ENABLED) > 0; } - void enabled(bool val) { if(val) value |= ENABLED; else value &= ~ENABLED; } - bool used() const { return (value & USED) > 0; } - void used(bool val) { if(val) value |= USED; else value &= ~USED; } - bool residualHighWarning() const { return (value & RESIDUAL_HIGH_WARNING) > 0; } - void residualHighWarning(bool val) { if(val) value |= RESIDUAL_HIGH_WARNING; else value &= ~RESIDUAL_HIGH_WARNING; } - bool sampleTimeWarning() const { return (value & SAMPLE_TIME_WARNING) > 0; } - void sampleTimeWarning(bool val) { if(val) value |= SAMPLE_TIME_WARNING; else value &= ~SAMPLE_TIME_WARNING; } - bool configurationError() const { return (value & CONFIGURATION_ERROR) > 0; } - void configurationError(bool val) { if(val) value |= CONFIGURATION_ERROR; else value &= ~CONFIGURATION_ERROR; } - bool maxNumMeasExceeded() const { return (value & MAX_NUM_MEAS_EXCEEDED) > 0; } - void maxNumMeasExceeded(bool val) { if(val) value |= MAX_NUM_MEAS_EXCEEDED; else value &= ~MAX_NUM_MEAS_EXCEEDED; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - struct GnssAidStatusFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -316,44 +245,10 @@ struct GnssAidStatusFlags : Bitfield GnssAidStatusFlags& operator|=(uint16_t val) { return *this = value | val; } GnssAidStatusFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tightCoupling() const { return (value & TIGHT_COUPLING) > 0; } - void tightCoupling(bool val) { if(val) value |= TIGHT_COUPLING; else value &= ~TIGHT_COUPLING; } - bool differential() const { return (value & DIFFERENTIAL) > 0; } - void differential(bool val) { if(val) value |= DIFFERENTIAL; else value &= ~DIFFERENTIAL; } - bool integerFix() const { return (value & INTEGER_FIX) > 0; } - void integerFix(bool val) { if(val) value |= INTEGER_FIX; else value &= ~INTEGER_FIX; } - bool gpsL1() const { return (value & GPS_L1) > 0; } - void gpsL1(bool val) { if(val) value |= GPS_L1; else value &= ~GPS_L1; } - bool gpsL2() const { return (value & GPS_L2) > 0; } - void gpsL2(bool val) { if(val) value |= GPS_L2; else value &= ~GPS_L2; } - bool gpsL5() const { return (value & GPS_L5) > 0; } - void gpsL5(bool val) { if(val) value |= GPS_L5; else value &= ~GPS_L5; } - bool gloL1() const { return (value & GLO_L1) > 0; } - void gloL1(bool val) { if(val) value |= GLO_L1; else value &= ~GLO_L1; } - bool gloL2() const { return (value & GLO_L2) > 0; } - void gloL2(bool val) { if(val) value |= GLO_L2; else value &= ~GLO_L2; } - bool galE1() const { return (value & GAL_E1) > 0; } - void galE1(bool val) { if(val) value |= GAL_E1; else value &= ~GAL_E1; } - bool galE5() const { return (value & GAL_E5) > 0; } - void galE5(bool val) { if(val) value |= GAL_E5; else value &= ~GAL_E5; } - bool galE6() const { return (value & GAL_E6) > 0; } - void galE6(bool val) { if(val) value |= GAL_E6; else value &= ~GAL_E6; } - bool beiB1() const { return (value & BEI_B1) > 0; } - void beiB1(bool val) { if(val) value |= BEI_B1; else value &= ~BEI_B1; } - bool beiB2() const { return (value & BEI_B2) > 0; } - void beiB2(bool val) { if(val) value |= BEI_B2; else value &= ~BEI_B2; } - bool beiB3() const { return (value & BEI_B3) > 0; } - void beiB3(bool val) { if(val) value |= BEI_B3; else value &= ~BEI_B3; } - bool noFix() const { return (value & NO_FIX) > 0; } - void noFix(bool val) { if(val) value |= NO_FIX; else value &= ~NO_FIX; } - bool configError() const { return (value & CONFIG_ERROR) > 0; } - void configError(bool val) { if(val) value |= CONFIG_ERROR; else value &= ~CONFIG_ERROR; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// @@ -366,31 +261,35 @@ struct GnssAidStatusFlags : Bitfield struct PositionLlh { + /// Parameters double latitude = 0; ///< [degrees] double longitude = 0; ///< [degrees] double ellipsoid_height = 0; ///< [meters] uint16_t valid_flags = 0; ///< 0 - Invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_POS_LLH; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PositionLlh"; static constexpr const char* DOC_NAME = "LLH Position"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(latitude,longitude,ellipsoid_height,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(latitude),std::ref(longitude),std::ref(ellipsoid_height),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const PositionLlh& self); -void extract(::microstrain::Serializer& serializer, PositionLlh& self); - ///@} /// @@ -402,31 +301,35 @@ void extract(::microstrain::Serializer& serializer, PositionLlh& self); struct VelocityNed { + /// Parameters float north = 0; ///< [meters/second] float east = 0; ///< [meters/second] float down = 0; ///< [meters/second] uint16_t valid_flags = 0; ///< 0 - Invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_VEL_NED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "VelocityNed"; static constexpr const char* DOC_NAME = "VelocityNed"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(north,east,down,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(north),std::ref(east),std::ref(down),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const VelocityNed& self); -void extract(::microstrain::Serializer& serializer, VelocityNed& self); - ///@} /// @@ -446,29 +349,33 @@ void extract(::microstrain::Serializer& serializer, VelocityNed& self); struct AttitudeQuaternion { + /// Parameters Quatf q; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_QUATERNION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AttitudeQuaternion"; static constexpr const char* DOC_NAME = "AttitudeQuaternion"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(q[0],q[1],q[2],q[3],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(q[0]),std::ref(q[1]),std::ref(q[2]),std::ref(q[3]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AttitudeQuaternion& self); -void extract(::microstrain::Serializer& serializer, AttitudeQuaternion& self); - ///@} /// @@ -490,29 +397,33 @@ void extract(::microstrain::Serializer& serializer, AttitudeQuaternion& self); struct AttitudeDcm { + /// Parameters Matrix3f dcm; ///< Matrix elements in row-major order. uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_MATRIX; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AttitudeDcm"; static constexpr const char* DOC_NAME = "AttitudeDcm"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(dcm[0],dcm[1],dcm[2],dcm[3],dcm[4],dcm[5],dcm[6],dcm[7],dcm[8],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(dcm[0]),std::ref(dcm[1]),std::ref(dcm[2]),std::ref(dcm[3]),std::ref(dcm[4]),std::ref(dcm[5]),std::ref(dcm[6]),std::ref(dcm[7]),std::ref(dcm[8]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AttitudeDcm& self); -void extract(::microstrain::Serializer& serializer, AttitudeDcm& self); - ///@} /// @@ -525,31 +436,35 @@ void extract(::microstrain::Serializer& serializer, AttitudeDcm& self); struct EulerAngles { + /// Parameters float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_EULER_ANGLES; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EulerAngles"; static constexpr const char* DOC_NAME = "EulerAngles"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(roll,pitch,yaw,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const EulerAngles& self); -void extract(::microstrain::Serializer& serializer, EulerAngles& self); - ///@} /// @@ -561,29 +476,33 @@ void extract(::microstrain::Serializer& serializer, EulerAngles& self); struct GyroBias { + /// Parameters Vector3f bias; ///< (x, y, z) [radians/second] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GYRO_BIAS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroBias"; static constexpr const char* DOC_NAME = "GyroBias"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias[0],bias[1],bias[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias[0]),std::ref(bias[1]),std::ref(bias[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GyroBias& self); -void extract(::microstrain::Serializer& serializer, GyroBias& self); - ///@} /// @@ -595,29 +514,33 @@ void extract(::microstrain::Serializer& serializer, GyroBias& self); struct AccelBias { + /// Parameters Vector3f bias; ///< (x, y, z) [meters/second^2] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ACCEL_BIAS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelBias"; static constexpr const char* DOC_NAME = "AccelBias"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias[0],bias[1],bias[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias[0]),std::ref(bias[1]),std::ref(bias[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AccelBias& self); -void extract(::microstrain::Serializer& serializer, AccelBias& self); - ///@} /// @@ -629,31 +552,35 @@ void extract(::microstrain::Serializer& serializer, AccelBias& self); struct PositionLlhUncertainty { + /// Parameters float north = 0; ///< [meters] float east = 0; ///< [meters] float down = 0; ///< [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_POS_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PositionLlhUncertainty"; static constexpr const char* DOC_NAME = "LLH Position Uncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(north,east,down,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(north),std::ref(east),std::ref(down),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const PositionLlhUncertainty& self); -void extract(::microstrain::Serializer& serializer, PositionLlhUncertainty& self); - ///@} /// @@ -665,31 +592,35 @@ void extract(::microstrain::Serializer& serializer, PositionLlhUncertainty& self struct VelocityNedUncertainty { + /// Parameters float north = 0; ///< [meters/second] float east = 0; ///< [meters/second] float down = 0; ///< [meters/second] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_VEL_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "VelocityNedUncertainty"; static constexpr const char* DOC_NAME = "NED Velocity Uncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(north,east,down,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(north),std::ref(east),std::ref(down),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const VelocityNedUncertainty& self); -void extract(::microstrain::Serializer& serializer, VelocityNedUncertainty& self); - ///@} /// @@ -702,31 +633,35 @@ void extract(::microstrain::Serializer& serializer, VelocityNedUncertainty& self struct EulerAnglesUncertainty { + /// Parameters float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_UNCERTAINTY_EULER; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EulerAnglesUncertainty"; static constexpr const char* DOC_NAME = "EulerAnglesUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(roll,pitch,yaw,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const EulerAnglesUncertainty& self); -void extract(::microstrain::Serializer& serializer, EulerAnglesUncertainty& self); - ///@} /// @@ -738,29 +673,33 @@ void extract(::microstrain::Serializer& serializer, EulerAnglesUncertainty& self struct GyroBiasUncertainty { + /// Parameters Vector3f bias_uncert; ///< (x,y,z) [radians/sec] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GYRO_BIAS_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroBiasUncertainty"; static constexpr const char* DOC_NAME = "GyroBiasUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias_uncert[0],bias_uncert[1],bias_uncert[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias_uncert[0]),std::ref(bias_uncert[1]),std::ref(bias_uncert[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GyroBiasUncertainty& self); -void extract(::microstrain::Serializer& serializer, GyroBiasUncertainty& self); - ///@} /// @@ -772,29 +711,33 @@ void extract(::microstrain::Serializer& serializer, GyroBiasUncertainty& self); struct AccelBiasUncertainty { + /// Parameters Vector3f bias_uncert; ///< (x,y,z) [meters/second^2] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ACCEL_BIAS_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelBiasUncertainty"; static constexpr const char* DOC_NAME = "AccelBiasUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias_uncert[0],bias_uncert[1],bias_uncert[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias_uncert[0]),std::ref(bias_uncert[1]),std::ref(bias_uncert[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AccelBiasUncertainty& self); -void extract(::microstrain::Serializer& serializer, AccelBiasUncertainty& self); - ///@} /// @@ -812,30 +755,34 @@ void extract(::microstrain::Serializer& serializer, AccelBiasUncertainty& self); struct Timestamp { + /// Parameters double tow = 0; ///< GPS Time of Week [seconds] uint16_t week_number = 0; ///< GPS Week Number since 1980 [weeks] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_FILTER_TIMESTAMP; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Timestamp"; static constexpr const char* DOC_NAME = "Timestamp"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(tow,week_number,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const Timestamp& self); -void extract(::microstrain::Serializer& serializer, Timestamp& self); - ///@} /// @@ -847,30 +794,34 @@ void extract(::microstrain::Serializer& serializer, Timestamp& self); struct Status { + /// Parameters FilterMode filter_state = static_cast(0); ///< Device-specific filter state. Please consult the user manual for definition. FilterDynamicsMode dynamics_mode = static_cast(0); ///< Device-specific dynamics mode. Please consult the user manual for definition. FilterStatusFlags status_flags; ///< Device-specific status flags. Please consult the user manual for definition. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_FILTER_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Status"; static constexpr const char* DOC_NAME = "Status"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(filter_state,dynamics_mode,status_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(filter_state),std::ref(dynamics_mode),std::ref(status_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const Status& self); -void extract(::microstrain::Serializer& serializer, Status& self); - ///@} /// @@ -883,29 +834,33 @@ void extract(::microstrain::Serializer& serializer, Status& self); struct LinearAccel { + /// Parameters Vector3f accel; ///< (x,y,z) [meters/second^2] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_LINEAR_ACCELERATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "LinearAccel"; static constexpr const char* DOC_NAME = "LinearAccel"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(accel[0],accel[1],accel[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(accel[0]),std::ref(accel[1]),std::ref(accel[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const LinearAccel& self); -void extract(::microstrain::Serializer& serializer, LinearAccel& self); - ///@} /// @@ -917,29 +872,33 @@ void extract(::microstrain::Serializer& serializer, LinearAccel& self); struct GravityVector { + /// Parameters Vector3f gravity; ///< (x, y, z) [meters/second^2] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GRAVITY_VECTOR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GravityVector"; static constexpr const char* DOC_NAME = "GravityVector"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(gravity[0],gravity[1],gravity[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(gravity[0]),std::ref(gravity[1]),std::ref(gravity[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GravityVector& self); -void extract(::microstrain::Serializer& serializer, GravityVector& self); - ///@} /// @@ -951,29 +910,33 @@ void extract(::microstrain::Serializer& serializer, GravityVector& self); struct CompAccel { + /// Parameters Vector3f accel; ///< (x,y,z) [meters/second^2] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_COMPENSATED_ACCELERATION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CompAccel"; static constexpr const char* DOC_NAME = "Compensated Acceleration"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(accel[0],accel[1],accel[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(accel[0]),std::ref(accel[1]),std::ref(accel[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const CompAccel& self); -void extract(::microstrain::Serializer& serializer, CompAccel& self); - ///@} /// @@ -985,29 +948,33 @@ void extract(::microstrain::Serializer& serializer, CompAccel& self); struct CompAngularRate { + /// Parameters Vector3f gyro; ///< (x, y, z) [radians/second] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_COMPENSATED_ANGULAR_RATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CompAngularRate"; static constexpr const char* DOC_NAME = "CompAngularRate"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(gyro[0],gyro[1],gyro[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(gyro[0]),std::ref(gyro[1]),std::ref(gyro[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const CompAngularRate& self); -void extract(::microstrain::Serializer& serializer, CompAngularRate& self); - ///@} /// @@ -1019,29 +986,33 @@ void extract(::microstrain::Serializer& serializer, CompAngularRate& self); struct QuaternionAttitudeUncertainty { + /// Parameters Quatf q; ///< [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ATT_UNCERTAINTY_QUATERNION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "QuaternionAttitudeUncertainty"; static constexpr const char* DOC_NAME = "QuaternionAttitudeUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(q[0],q[1],q[2],q[3],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(q[0]),std::ref(q[1]),std::ref(q[2]),std::ref(q[3]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const QuaternionAttitudeUncertainty& self); -void extract(::microstrain::Serializer& serializer, QuaternionAttitudeUncertainty& self); - ///@} /// @@ -1053,29 +1024,33 @@ void extract(::microstrain::Serializer& serializer, QuaternionAttitudeUncertaint struct Wgs84GravityMag { + /// Parameters float magnitude = 0; ///< [meters/second^2] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_WGS84_GRAVITY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Wgs84GravityMag"; static constexpr const char* DOC_NAME = "Wgs84GravityMag"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(magnitude,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(magnitude),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const Wgs84GravityMag& self); -void extract(::microstrain::Serializer& serializer, Wgs84GravityMag& self); - ///@} /// @@ -1099,31 +1074,35 @@ struct HeadingUpdateState DUAL_ANTENNA = 8, ///< }; + /// Parameters float heading = 0; ///< [radians] float heading_1sigma = 0; ///< [radians] HeadingSource source = static_cast(0); uint16_t valid_flags = 0; ///< 1 if a valid heading update was received in 2 seconds, 0 otherwise. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_HEADING_UPDATE_STATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "HeadingUpdateState"; static constexpr const char* DOC_NAME = "HeadingUpdateState"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(heading,heading_1sigma,source,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(heading),std::ref(heading_1sigma),std::ref(source),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const HeadingUpdateState& self); -void extract(::microstrain::Serializer& serializer, HeadingUpdateState& self); - ///@} /// @@ -1136,6 +1115,7 @@ void extract(::microstrain::Serializer& serializer, HeadingUpdateState& self); struct MagneticModel { + /// Parameters float intensity_north = 0; ///< [Gauss] float intensity_east = 0; ///< [Gauss] float intensity_down = 0; ///< [Gauss] @@ -1143,26 +1123,29 @@ struct MagneticModel float declination = 0; ///< [radians] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAGNETIC_MODEL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagneticModel"; static constexpr const char* DOC_NAME = "MagneticModel"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(intensity_north,intensity_east,intensity_down,inclination,declination,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(intensity_north),std::ref(intensity_east),std::ref(intensity_down),std::ref(inclination),std::ref(declination),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MagneticModel& self); -void extract(::microstrain::Serializer& serializer, MagneticModel& self); - ///@} /// @@ -1174,29 +1157,33 @@ void extract(::microstrain::Serializer& serializer, MagneticModel& self); struct AccelScaleFactor { + /// Parameters Vector3f scale_factor; ///< (x,y,z) [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ACCEL_SCALE_FACTOR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelScaleFactor"; static constexpr const char* DOC_NAME = "AccelScaleFactor"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scale_factor[0],scale_factor[1],scale_factor[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scale_factor[0]),std::ref(scale_factor[1]),std::ref(scale_factor[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AccelScaleFactor& self); -void extract(::microstrain::Serializer& serializer, AccelScaleFactor& self); - ///@} /// @@ -1208,29 +1195,33 @@ void extract(::microstrain::Serializer& serializer, AccelScaleFactor& self); struct AccelScaleFactorUncertainty { + /// Parameters Vector3f scale_factor_uncert; ///< (x,y,z) [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ACCEL_SCALE_FACTOR_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AccelScaleFactorUncertainty"; static constexpr const char* DOC_NAME = "AccelScaleFactorUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scale_factor_uncert[0],scale_factor_uncert[1],scale_factor_uncert[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scale_factor_uncert[0]),std::ref(scale_factor_uncert[1]),std::ref(scale_factor_uncert[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AccelScaleFactorUncertainty& self); -void extract(::microstrain::Serializer& serializer, AccelScaleFactorUncertainty& self); - ///@} /// @@ -1242,29 +1233,33 @@ void extract(::microstrain::Serializer& serializer, AccelScaleFactorUncertainty& struct GyroScaleFactor { + /// Parameters Vector3f scale_factor; ///< (x,y,z) [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GYRO_SCALE_FACTOR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroScaleFactor"; static constexpr const char* DOC_NAME = "GyroScaleFactor"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scale_factor[0],scale_factor[1],scale_factor[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scale_factor[0]),std::ref(scale_factor[1]),std::ref(scale_factor[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GyroScaleFactor& self); -void extract(::microstrain::Serializer& serializer, GyroScaleFactor& self); - ///@} /// @@ -1276,29 +1271,33 @@ void extract(::microstrain::Serializer& serializer, GyroScaleFactor& self); struct GyroScaleFactorUncertainty { + /// Parameters Vector3f scale_factor_uncert; ///< (x,y,z) [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GYRO_SCALE_FACTOR_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GyroScaleFactorUncertainty"; static constexpr const char* DOC_NAME = "GyroScaleFactorUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scale_factor_uncert[0],scale_factor_uncert[1],scale_factor_uncert[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scale_factor_uncert[0]),std::ref(scale_factor_uncert[1]),std::ref(scale_factor_uncert[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GyroScaleFactorUncertainty& self); -void extract(::microstrain::Serializer& serializer, GyroScaleFactorUncertainty& self); - ///@} /// @@ -1310,29 +1309,33 @@ void extract(::microstrain::Serializer& serializer, GyroScaleFactorUncertainty& struct MagBias { + /// Parameters Vector3f bias; ///< (x,y,z) [Gauss] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_BIAS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagBias"; static constexpr const char* DOC_NAME = "MagBias"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias[0],bias[1],bias[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias[0]),std::ref(bias[1]),std::ref(bias[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MagBias& self); -void extract(::microstrain::Serializer& serializer, MagBias& self); - ///@} /// @@ -1344,29 +1347,33 @@ void extract(::microstrain::Serializer& serializer, MagBias& self); struct MagBiasUncertainty { + /// Parameters Vector3f bias_uncert; ///< (x,y,z) [Gauss] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_BIAS_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagBiasUncertainty"; static constexpr const char* DOC_NAME = "MagBiasUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias_uncert[0],bias_uncert[1],bias_uncert[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias_uncert[0]),std::ref(bias_uncert[1]),std::ref(bias_uncert[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MagBiasUncertainty& self); -void extract(::microstrain::Serializer& serializer, MagBiasUncertainty& self); - ///@} /// @@ -1380,6 +1387,7 @@ void extract(::microstrain::Serializer& serializer, MagBiasUncertainty& self); struct StandardAtmosphere { + /// Parameters float geometric_altitude = 0; ///< Input into calculation [meters] float geopotential_altitude = 0; ///< [meters] float standard_temperature = 0; ///< [degC] @@ -1387,26 +1395,29 @@ struct StandardAtmosphere float standard_density = 0; ///< [kilogram/meter^3] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_STANDARD_ATMOSPHERE_DATA; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "StandardAtmosphere"; static constexpr const char* DOC_NAME = "StandardAtmosphere"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(geometric_altitude,geopotential_altitude,standard_temperature,standard_pressure,standard_density,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(geometric_altitude),std::ref(geopotential_altitude),std::ref(standard_temperature),std::ref(standard_pressure),std::ref(standard_density),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const StandardAtmosphere& self); -void extract(::microstrain::Serializer& serializer, StandardAtmosphere& self); - ///@} /// @@ -1422,29 +1433,33 @@ void extract(::microstrain::Serializer& serializer, StandardAtmosphere& self); struct PressureAltitude { + /// Parameters float pressure_altitude = 0; ///< [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_PRESSURE_ALTITUDE_DATA; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PressureAltitude"; static constexpr const char* DOC_NAME = "PressureAltitude"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(pressure_altitude,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(pressure_altitude),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const PressureAltitude& self); -void extract(::microstrain::Serializer& serializer, PressureAltitude& self); - ///@} /// @@ -1455,29 +1470,33 @@ void extract(::microstrain::Serializer& serializer, PressureAltitude& self); struct DensityAltitude { + /// Parameters float density_altitude = 0; ///< m uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_DENSITY_ALTITUDE_DATA; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DensityAltitude"; static constexpr const char* DOC_NAME = "DensityAltitude"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(density_altitude,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(density_altitude),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const DensityAltitude& self); -void extract(::microstrain::Serializer& serializer, DensityAltitude& self); - ///@} /// @@ -1491,29 +1510,33 @@ void extract(::microstrain::Serializer& serializer, DensityAltitude& self); struct AntennaOffsetCorrection { + /// Parameters Vector3f offset; ///< (x,y,z) [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ANTENNA_OFFSET_CORRECTION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AntennaOffsetCorrection"; static constexpr const char* DOC_NAME = "AntennaOffsetCorrection"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(offset[0],offset[1],offset[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset[0]),std::ref(offset[1]),std::ref(offset[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AntennaOffsetCorrection& self); -void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrection& self); - ///@} /// @@ -1525,29 +1548,33 @@ void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrection& sel struct AntennaOffsetCorrectionUncertainty { + /// Parameters Vector3f offset_uncert; ///< (x,y,z) [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ANTENNA_OFFSET_CORRECTION_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AntennaOffsetCorrectionUncertainty"; static constexpr const char* DOC_NAME = "AntennaOffsetCorrectionUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(offset_uncert[0],offset_uncert[1],offset_uncert[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(offset_uncert[0]),std::ref(offset_uncert[1]),std::ref(offset_uncert[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AntennaOffsetCorrectionUncertainty& self); -void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrectionUncertainty& self); - ///@} /// @@ -1561,30 +1588,34 @@ void extract(::microstrain::Serializer& serializer, AntennaOffsetCorrectionUncer struct MultiAntennaOffsetCorrection { + /// Parameters uint8_t receiver_id = 0; ///< Receiver ID for the receiver to which the antenna is attached Vector3f offset; ///< (x,y,z) [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MULTI_ANTENNA_OFFSET_CORRECTION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MultiAntennaOffsetCorrection"; static constexpr const char* DOC_NAME = "MultiAntennaOffsetCorrection"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(receiver_id,offset[0],offset[1],offset[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(receiver_id),std::ref(offset[0]),std::ref(offset[1]),std::ref(offset[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MultiAntennaOffsetCorrection& self); -void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrection& self); - ///@} /// @@ -1596,30 +1627,34 @@ void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrection struct MultiAntennaOffsetCorrectionUncertainty { + /// Parameters uint8_t receiver_id = 0; ///< Receiver ID for the receiver to which the antenna is attached Vector3f offset_uncert; ///< (x,y,z) [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MULTI_ANTENNA_OFFSET_CORRECTION_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MultiAntennaOffsetCorrectionUncertainty"; static constexpr const char* DOC_NAME = "MultiAntennaOffsetCorrectionUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(receiver_id,offset_uncert[0],offset_uncert[1],offset_uncert[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(receiver_id),std::ref(offset_uncert[0]),std::ref(offset_uncert[1]),std::ref(offset_uncert[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MultiAntennaOffsetCorrectionUncertainty& self); -void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrectionUncertainty& self); - ///@} /// @@ -1633,29 +1668,33 @@ void extract(::microstrain::Serializer& serializer, MultiAntennaOffsetCorrection struct MagnetometerOffset { + /// Parameters Vector3f hard_iron; ///< (x,y,z) [Gauss] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COMPENSATION_OFFSET; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagnetometerOffset"; static constexpr const char* DOC_NAME = "MagnetometerOffset"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(hard_iron[0],hard_iron[1],hard_iron[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(hard_iron[0]),std::ref(hard_iron[1]),std::ref(hard_iron[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MagnetometerOffset& self); -void extract(::microstrain::Serializer& serializer, MagnetometerOffset& self); - ///@} /// @@ -1669,29 +1708,33 @@ void extract(::microstrain::Serializer& serializer, MagnetometerOffset& self); struct MagnetometerMatrix { + /// Parameters Matrix3f soft_iron; ///< Row-major [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COMPENSATION_MATRIX; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagnetometerMatrix"; static constexpr const char* DOC_NAME = "MagnetometerMatrix"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(soft_iron[0],soft_iron[1],soft_iron[2],soft_iron[3],soft_iron[4],soft_iron[5],soft_iron[6],soft_iron[7],soft_iron[8],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(soft_iron[0]),std::ref(soft_iron[1]),std::ref(soft_iron[2]),std::ref(soft_iron[3]),std::ref(soft_iron[4]),std::ref(soft_iron[5]),std::ref(soft_iron[6]),std::ref(soft_iron[7]),std::ref(soft_iron[8]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MagnetometerMatrix& self); -void extract(::microstrain::Serializer& serializer, MagnetometerMatrix& self); - ///@} /// @@ -1703,29 +1746,33 @@ void extract(::microstrain::Serializer& serializer, MagnetometerMatrix& self); struct MagnetometerOffsetUncertainty { + /// Parameters Vector3f hard_iron_uncertainty; ///< (x,y,z) [Gauss] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COMPENSATION_OFFSET_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagnetometerOffsetUncertainty"; static constexpr const char* DOC_NAME = "MagnetometerOffsetUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(hard_iron_uncertainty[0],hard_iron_uncertainty[1],hard_iron_uncertainty[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(hard_iron_uncertainty[0]),std::ref(hard_iron_uncertainty[1]),std::ref(hard_iron_uncertainty[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MagnetometerOffsetUncertainty& self); -void extract(::microstrain::Serializer& serializer, MagnetometerOffsetUncertainty& self); - ///@} /// @@ -1737,29 +1784,33 @@ void extract(::microstrain::Serializer& serializer, MagnetometerOffsetUncertaint struct MagnetometerMatrixUncertainty { + /// Parameters Matrix3f soft_iron_uncertainty; ///< Row-major [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COMPENSATION_MATRIX_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagnetometerMatrixUncertainty"; static constexpr const char* DOC_NAME = "MagnetometerMatrixUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(soft_iron_uncertainty[0],soft_iron_uncertainty[1],soft_iron_uncertainty[2],soft_iron_uncertainty[3],soft_iron_uncertainty[4],soft_iron_uncertainty[5],soft_iron_uncertainty[6],soft_iron_uncertainty[7],soft_iron_uncertainty[8],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(soft_iron_uncertainty[0]),std::ref(soft_iron_uncertainty[1]),std::ref(soft_iron_uncertainty[2]),std::ref(soft_iron_uncertainty[3]),std::ref(soft_iron_uncertainty[4]),std::ref(soft_iron_uncertainty[5]),std::ref(soft_iron_uncertainty[6]),std::ref(soft_iron_uncertainty[7]),std::ref(soft_iron_uncertainty[8]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MagnetometerMatrixUncertainty& self); -void extract(::microstrain::Serializer& serializer, MagnetometerMatrixUncertainty& self); - ///@} /// @@ -1770,29 +1821,33 @@ void extract(::microstrain::Serializer& serializer, MagnetometerMatrixUncertaint struct MagnetometerCovarianceMatrix { + /// Parameters Matrix3f covariance; uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_COVARIANCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagnetometerCovarianceMatrix"; static constexpr const char* DOC_NAME = "MagnetometerCovarianceMatrix"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(covariance[0],covariance[1],covariance[2],covariance[3],covariance[4],covariance[5],covariance[6],covariance[7],covariance[8],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(covariance[0]),std::ref(covariance[1]),std::ref(covariance[2]),std::ref(covariance[3]),std::ref(covariance[4]),std::ref(covariance[5]),std::ref(covariance[6]),std::ref(covariance[7]),std::ref(covariance[8]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MagnetometerCovarianceMatrix& self); -void extract(::microstrain::Serializer& serializer, MagnetometerCovarianceMatrix& self); - ///@} /// @@ -1804,29 +1859,33 @@ void extract(::microstrain::Serializer& serializer, MagnetometerCovarianceMatrix struct MagnetometerResidualVector { + /// Parameters Vector3f residual; ///< (x,y,z) [Gauss] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_MAG_RESIDUAL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "MagnetometerResidualVector"; static constexpr const char* DOC_NAME = "MagnetometerResidualVector"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(residual[0],residual[1],residual[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(residual[0]),std::ref(residual[1]),std::ref(residual[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const MagnetometerResidualVector& self); -void extract(::microstrain::Serializer& serializer, MagnetometerResidualVector& self); - ///@} /// @@ -1838,31 +1897,35 @@ void extract(::microstrain::Serializer& serializer, MagnetometerResidualVector& struct ClockCorrection { + /// Parameters uint8_t receiver_id = 0; ///< 1, 2, etc. float bias = 0; ///< [seconds] float bias_drift = 0; ///< [seconds/second] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_CLOCK_CORRECTION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ClockCorrection"; static constexpr const char* DOC_NAME = "ClockCorrection"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(receiver_id,bias,bias_drift,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(receiver_id),std::ref(bias),std::ref(bias_drift),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ClockCorrection& self); -void extract(::microstrain::Serializer& serializer, ClockCorrection& self); - ///@} /// @@ -1874,31 +1937,35 @@ void extract(::microstrain::Serializer& serializer, ClockCorrection& self); struct ClockCorrectionUncertainty { + /// Parameters uint8_t receiver_id = 0; ///< 1, 2, etc. float bias_uncertainty = 0; ///< [seconds] float bias_drift_uncertainty = 0; ///< [seconds/second] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_CLOCK_CORRECTION_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ClockCorrectionUncertainty"; static constexpr const char* DOC_NAME = "ClockCorrectionUncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(receiver_id,bias_uncertainty,bias_drift_uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(receiver_id),std::ref(bias_uncertainty),std::ref(bias_drift_uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ClockCorrectionUncertainty& self); -void extract(::microstrain::Serializer& serializer, ClockCorrectionUncertainty& self); - ///@} /// @@ -1910,31 +1977,35 @@ void extract(::microstrain::Serializer& serializer, ClockCorrectionUncertainty& struct GnssPosAidStatus { + /// Parameters uint8_t receiver_id = 0; float time_of_week = 0; ///< Last GNSS aiding measurement time of week [seconds] GnssAidStatusFlags status; ///< Aiding measurement status bitfield uint8_t reserved[8] = {0}; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GNSS_POS_AID_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssPosAidStatus"; static constexpr const char* DOC_NAME = "GNSS Position Aiding Status"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(receiver_id,time_of_week,status,reserved); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(receiver_id),std::ref(time_of_week),std::ref(status),std::ref(reserved)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GnssPosAidStatus& self); -void extract(::microstrain::Serializer& serializer, GnssPosAidStatus& self); - ///@} /// @@ -1946,30 +2017,34 @@ void extract(::microstrain::Serializer& serializer, GnssPosAidStatus& self); struct GnssAttAidStatus { + /// Parameters float time_of_week = 0; ///< Last valid aiding measurement time of week [seconds] [processed instead of measured?] GnssAidStatusFlags status; ///< Last valid aiding measurement status bitfield uint8_t reserved[8] = {0}; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GNSS_ATT_AID_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssAttAidStatus"; static constexpr const char* DOC_NAME = "GNSS Attitude Aiding Status"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_of_week,status,reserved); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_of_week),std::ref(status),std::ref(reserved)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GnssAttAidStatus& self); -void extract(::microstrain::Serializer& serializer, GnssAttAidStatus& self); - ///@} /// @@ -1987,30 +2062,34 @@ struct HeadAidStatus EXTERNAL_MESSAGE = 2, ///< }; + /// Parameters float time_of_week = 0; ///< Last valid aiding measurement time of week [seconds] [processed instead of measured?] HeadingAidType type = static_cast(0); ///< 1 - Dual antenna, 2 - External heading message (user supplied) float reserved[2] = {0}; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_HEAD_AID_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "HeadAidStatus"; static constexpr const char* DOC_NAME = "HeadAidStatus"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_of_week,type,reserved); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_of_week),std::ref(type),std::ref(reserved)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const HeadAidStatus& self); -void extract(::microstrain::Serializer& serializer, HeadAidStatus& self); - ///@} /// @@ -2022,29 +2101,33 @@ void extract(::microstrain::Serializer& serializer, HeadAidStatus& self); struct RelPosNed { + /// Parameters Vector3d relative_position; ///< [meters, NED] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_REL_POS_NED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RelPosNed"; static constexpr const char* DOC_NAME = "NED Relative Position"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(relative_position[0],relative_position[1],relative_position[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(relative_position[0]),std::ref(relative_position[1]),std::ref(relative_position[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const RelPosNed& self); -void extract(::microstrain::Serializer& serializer, RelPosNed& self); - ///@} /// @@ -2056,29 +2139,33 @@ void extract(::microstrain::Serializer& serializer, RelPosNed& self); struct EcefPos { + /// Parameters Vector3d position_ecef; ///< [meters, ECEF] uint16_t valid_flags = 0; ///< 0 - invalid, 1 valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ECEF_POS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EcefPos"; static constexpr const char* DOC_NAME = "ECEF Position"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(position_ecef[0],position_ecef[1],position_ecef[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(position_ecef[0]),std::ref(position_ecef[1]),std::ref(position_ecef[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const EcefPos& self); -void extract(::microstrain::Serializer& serializer, EcefPos& self); - ///@} /// @@ -2090,29 +2177,33 @@ void extract(::microstrain::Serializer& serializer, EcefPos& self); struct EcefVel { + /// Parameters Vector3f velocity_ecef; ///< [meters/second, ECEF] uint16_t valid_flags = 0; ///< 0 - invalid, 1 valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ECEF_VEL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EcefVel"; static constexpr const char* DOC_NAME = "ECEF Velocity"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(velocity_ecef[0],velocity_ecef[1],velocity_ecef[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(velocity_ecef[0]),std::ref(velocity_ecef[1]),std::ref(velocity_ecef[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const EcefVel& self); -void extract(::microstrain::Serializer& serializer, EcefVel& self); - ///@} /// @@ -2124,29 +2215,33 @@ void extract(::microstrain::Serializer& serializer, EcefVel& self); struct EcefPosUncertainty { + /// Parameters Vector3f pos_uncertainty; ///< [meters] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ECEF_POS_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EcefPosUncertainty"; static constexpr const char* DOC_NAME = "ECEF Position Uncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(pos_uncertainty[0],pos_uncertainty[1],pos_uncertainty[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(pos_uncertainty[0]),std::ref(pos_uncertainty[1]),std::ref(pos_uncertainty[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const EcefPosUncertainty& self); -void extract(::microstrain::Serializer& serializer, EcefPosUncertainty& self); - ///@} /// @@ -2158,29 +2253,33 @@ void extract(::microstrain::Serializer& serializer, EcefPosUncertainty& self); struct EcefVelUncertainty { + /// Parameters Vector3f vel_uncertainty; ///< [meters/second] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ECEF_VEL_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EcefVelUncertainty"; static constexpr const char* DOC_NAME = "ECEF Velocity Uncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(vel_uncertainty[0],vel_uncertainty[1],vel_uncertainty[2],valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(vel_uncertainty[0]),std::ref(vel_uncertainty[1]),std::ref(vel_uncertainty[2]),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const EcefVelUncertainty& self); -void extract(::microstrain::Serializer& serializer, EcefVelUncertainty& self); - ///@} /// @@ -2192,31 +2291,35 @@ void extract(::microstrain::Serializer& serializer, EcefVelUncertainty& self); struct AidingMeasurementSummary { + /// Parameters float time_of_week = 0; ///< [seconds] uint8_t source = 0; FilterAidingMeasurementType type = static_cast(0); ///< (see product manual for supported types) Note: values 0x20 and above correspond to commanded aiding measurements in the 0x13 Aiding command set. FilterMeasurementIndicator indicator; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_AID_MEAS_SUMMARY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AidingMeasurementSummary"; static constexpr const char* DOC_NAME = "AidingMeasurementSummary"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_of_week,source,type,indicator); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_of_week),std::ref(source),std::ref(type),std::ref(indicator)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AidingMeasurementSummary& self); -void extract(::microstrain::Serializer& serializer, AidingMeasurementSummary& self); - ///@} /// @@ -2228,29 +2331,33 @@ void extract(::microstrain::Serializer& serializer, AidingMeasurementSummary& se struct OdometerScaleFactorError { + /// Parameters float scale_factor_error = 0; ///< [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ODOMETER_SCALE_FACTOR_ERROR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "OdometerScaleFactorError"; static constexpr const char* DOC_NAME = "Odometer Scale Factor Error"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scale_factor_error,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scale_factor_error),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const OdometerScaleFactorError& self); -void extract(::microstrain::Serializer& serializer, OdometerScaleFactorError& self); - ///@} /// @@ -2262,29 +2369,33 @@ void extract(::microstrain::Serializer& serializer, OdometerScaleFactorError& se struct OdometerScaleFactorErrorUncertainty { + /// Parameters float scale_factor_error_uncertainty = 0; ///< [dimensionless] uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_ODOMETER_SCALE_FACTOR_ERROR_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "OdometerScaleFactorErrorUncertainty"; static constexpr const char* DOC_NAME = "Odometer Scale Factor Error Uncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scale_factor_error_uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scale_factor_error_uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const OdometerScaleFactorErrorUncertainty& self); -void extract(::microstrain::Serializer& serializer, OdometerScaleFactorErrorUncertainty& self); - ///@} /// @@ -2305,6 +2416,7 @@ struct GnssDualAntennaStatus struct DualAntennaStatusFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -2323,17 +2435,10 @@ struct GnssDualAntennaStatus DualAntennaStatusFlags& operator|=(uint16_t val) { return *this = value | val; } DualAntennaStatusFlags& operator&=(uint16_t val) { return *this = value & val; } - bool rcv1DataValid() const { return (value & RCV_1_DATA_VALID) > 0; } - void rcv1DataValid(bool val) { if(val) value |= RCV_1_DATA_VALID; else value &= ~RCV_1_DATA_VALID; } - bool rcv2DataValid() const { return (value & RCV_2_DATA_VALID) > 0; } - void rcv2DataValid(bool val) { if(val) value |= RCV_2_DATA_VALID; else value &= ~RCV_2_DATA_VALID; } - bool antennaOffsetsValid() const { return (value & ANTENNA_OFFSETS_VALID) > 0; } - void antennaOffsetsValid(bool val) { if(val) value |= ANTENNA_OFFSETS_VALID; else value &= ~ANTENNA_OFFSETS_VALID; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters float time_of_week = 0; ///< Last dual-antenna GNSS aiding measurement time of week [seconds] float heading = 0; ///< [radians] float heading_unc = 0; ///< [radians] @@ -2341,26 +2446,29 @@ struct GnssDualAntennaStatus DualAntennaStatusFlags status_flags; uint16_t valid_flags = 0; ///< 0 - invalid, 1 - valid + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_GNSS_DUAL_ANTENNA_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GnssDualAntennaStatus"; static constexpr const char* DOC_NAME = "GNSS Dual Antenna Status"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_of_week,heading,heading_unc,fix_type,status_flags,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_of_week),std::ref(heading),std::ref(heading_unc),std::ref(fix_type),std::ref(status_flags),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GnssDualAntennaStatus& self); -void extract(::microstrain::Serializer& serializer, GnssDualAntennaStatus& self); - ///@} /// @@ -2374,30 +2482,34 @@ void extract(::microstrain::Serializer& serializer, GnssDualAntennaStatus& self) struct AidingFrameConfigError { + /// Parameters uint8_t frame_id = 0; ///< Frame ID for the receiver to which the antenna is attached Vector3f translation; ///< Translation config X, Y, and Z (m). Quatf attitude; ///< Attitude quaternion + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_FRAME_CONFIG_ERROR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AidingFrameConfigError"; static constexpr const char* DOC_NAME = "Aiding Frame Configuration Error"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(frame_id,translation[0],translation[1],translation[2],attitude[0],attitude[1],attitude[2],attitude[3]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(frame_id),std::ref(translation[0]),std::ref(translation[1]),std::ref(translation[2]),std::ref(attitude[0]),std::ref(attitude[1]),std::ref(attitude[2]),std::ref(attitude[3])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AidingFrameConfigError& self); -void extract(::microstrain::Serializer& serializer, AidingFrameConfigError& self); - ///@} /// @@ -2411,30 +2523,34 @@ void extract(::microstrain::Serializer& serializer, AidingFrameConfigError& self struct AidingFrameConfigErrorUncertainty { + /// Parameters uint8_t frame_id = 0; ///< Frame ID for the receiver to which the antenna is attached Vector3f translation_unc; ///< Translation uncertaint X, Y, and Z (m). Vector3f attitude_unc; ///< Attitude uncertainty, X, Y, and Z (radians). + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_filter::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_filter::DATA_FRAME_CONFIG_ERROR_UNCERTAINTY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "AidingFrameConfigErrorUncertainty"; static constexpr const char* DOC_NAME = "Aiding Frame Configuration Error Uncertainty"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(frame_id,translation_unc[0],translation_unc[1],translation_unc[2],attitude_unc[0],attitude_unc[1],attitude_unc[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(frame_id),std::ref(translation_unc[0]),std::ref(translation_unc[1]),std::ref(translation_unc[2]),std::ref(attitude_unc[0]),std::ref(attitude_unc[1]),std::ref(attitude_unc[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const AidingFrameConfigErrorUncertainty& self); -void extract(::microstrain::Serializer& serializer, AidingFrameConfigErrorUncertainty& self); - ///@} /// diff --git a/src/cpp/mip/definitions/data_gnss.cpp b/src/cpp/mip/definitions/data_gnss.cpp index 0d6c21692..707d4180b 100644 --- a/src/cpp/mip/definitions/data_gnss.cpp +++ b/src/cpp/mip/definitions/data_gnss.cpp @@ -1,1228 +1,1203 @@ #include "data_gnss.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace data_gnss { -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const PosLlh& self) +void PosLlh::insert(Serializer& serializer) const { - insert(serializer, self.latitude); + serializer.insert(latitude); - insert(serializer, self.longitude); + serializer.insert(longitude); - insert(serializer, self.ellipsoid_height); + serializer.insert(ellipsoid_height); - insert(serializer, self.msl_height); + serializer.insert(msl_height); - insert(serializer, self.horizontal_accuracy); + serializer.insert(horizontal_accuracy); - insert(serializer, self.vertical_accuracy); + serializer.insert(vertical_accuracy); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, PosLlh& self) +void PosLlh::extract(Serializer& serializer) { - extract(serializer, self.latitude); + serializer.extract(latitude); - extract(serializer, self.longitude); + serializer.extract(longitude); - extract(serializer, self.ellipsoid_height); + serializer.extract(ellipsoid_height); - extract(serializer, self.msl_height); + serializer.extract(msl_height); - extract(serializer, self.horizontal_accuracy); + serializer.extract(horizontal_accuracy); - extract(serializer, self.vertical_accuracy); + serializer.extract(vertical_accuracy); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const PosEcef& self) +void PosEcef::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.x[i]); + serializer.insert(x); - insert(serializer, self.x_accuracy); + serializer.insert(x_accuracy); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, PosEcef& self) +void PosEcef::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.x[i]); + serializer.extract(x); - extract(serializer, self.x_accuracy); + serializer.extract(x_accuracy); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const VelNed& self) +void VelNed::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.v[i]); + serializer.insert(v); - insert(serializer, self.speed); + serializer.insert(speed); - insert(serializer, self.ground_speed); + serializer.insert(ground_speed); - insert(serializer, self.heading); + serializer.insert(heading); - insert(serializer, self.speed_accuracy); + serializer.insert(speed_accuracy); - insert(serializer, self.heading_accuracy); + serializer.insert(heading_accuracy); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, VelNed& self) +void VelNed::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.v[i]); + serializer.extract(v); - extract(serializer, self.speed); + serializer.extract(speed); - extract(serializer, self.ground_speed); + serializer.extract(ground_speed); - extract(serializer, self.heading); + serializer.extract(heading); - extract(serializer, self.speed_accuracy); + serializer.extract(speed_accuracy); - extract(serializer, self.heading_accuracy); + serializer.extract(heading_accuracy); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const VelEcef& self) +void VelEcef::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.v[i]); + serializer.insert(v); - insert(serializer, self.v_accuracy); + serializer.insert(v_accuracy); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, VelEcef& self) +void VelEcef::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.v[i]); + serializer.extract(v); - extract(serializer, self.v_accuracy); + serializer.extract(v_accuracy); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const Dop& self) +void Dop::insert(Serializer& serializer) const { - insert(serializer, self.gdop); + serializer.insert(gdop); - insert(serializer, self.pdop); + serializer.insert(pdop); - insert(serializer, self.hdop); + serializer.insert(hdop); - insert(serializer, self.vdop); + serializer.insert(vdop); - insert(serializer, self.tdop); + serializer.insert(tdop); - insert(serializer, self.ndop); + serializer.insert(ndop); - insert(serializer, self.edop); + serializer.insert(edop); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, Dop& self) +void Dop::extract(Serializer& serializer) { - extract(serializer, self.gdop); + serializer.extract(gdop); - extract(serializer, self.pdop); + serializer.extract(pdop); - extract(serializer, self.hdop); + serializer.extract(hdop); - extract(serializer, self.vdop); + serializer.extract(vdop); - extract(serializer, self.tdop); + serializer.extract(tdop); - extract(serializer, self.ndop); + serializer.extract(ndop); - extract(serializer, self.edop); + serializer.extract(edop); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const UtcTime& self) +void UtcTime::insert(Serializer& serializer) const { - insert(serializer, self.year); + serializer.insert(year); - insert(serializer, self.month); + serializer.insert(month); - insert(serializer, self.day); + serializer.insert(day); - insert(serializer, self.hour); + serializer.insert(hour); - insert(serializer, self.min); + serializer.insert(min); - insert(serializer, self.sec); + serializer.insert(sec); - insert(serializer, self.msec); + serializer.insert(msec); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, UtcTime& self) +void UtcTime::extract(Serializer& serializer) { - extract(serializer, self.year); + serializer.extract(year); - extract(serializer, self.month); + serializer.extract(month); - extract(serializer, self.day); + serializer.extract(day); - extract(serializer, self.hour); + serializer.extract(hour); - extract(serializer, self.min); + serializer.extract(min); - extract(serializer, self.sec); + serializer.extract(sec); - extract(serializer, self.msec); + serializer.extract(msec); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GpsTime& self) +void GpsTime::insert(Serializer& serializer) const { - insert(serializer, self.tow); + serializer.insert(tow); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GpsTime& self) +void GpsTime::extract(Serializer& serializer) { - extract(serializer, self.tow); + serializer.extract(tow); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const ClockInfo& self) +void ClockInfo::insert(Serializer& serializer) const { - insert(serializer, self.bias); + serializer.insert(bias); - insert(serializer, self.drift); + serializer.insert(drift); - insert(serializer, self.accuracy_estimate); + serializer.insert(accuracy_estimate); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, ClockInfo& self) +void ClockInfo::extract(Serializer& serializer) { - extract(serializer, self.bias); + serializer.extract(bias); - extract(serializer, self.drift); + serializer.extract(drift); - extract(serializer, self.accuracy_estimate); + serializer.extract(accuracy_estimate); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const FixInfo& self) +void FixInfo::insert(Serializer& serializer) const { - insert(serializer, self.fix_type); + serializer.insert(fix_type); - insert(serializer, self.num_sv); + serializer.insert(num_sv); - insert(serializer, self.fix_flags); + serializer.insert(fix_flags); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, FixInfo& self) +void FixInfo::extract(Serializer& serializer) { - extract(serializer, self.fix_type); + serializer.extract(fix_type); - extract(serializer, self.num_sv); + serializer.extract(num_sv); - extract(serializer, self.fix_flags); + serializer.extract(fix_flags); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const SvInfo& self) +void SvInfo::insert(Serializer& serializer) const { - insert(serializer, self.channel); + serializer.insert(channel); - insert(serializer, self.sv_id); + serializer.insert(sv_id); - insert(serializer, self.carrier_noise_ratio); + serializer.insert(carrier_noise_ratio); - insert(serializer, self.azimuth); + serializer.insert(azimuth); - insert(serializer, self.elevation); + serializer.insert(elevation); - insert(serializer, self.sv_flags); + serializer.insert(sv_flags); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, SvInfo& self) +void SvInfo::extract(Serializer& serializer) { - extract(serializer, self.channel); + serializer.extract(channel); - extract(serializer, self.sv_id); + serializer.extract(sv_id); - extract(serializer, self.carrier_noise_ratio); + serializer.extract(carrier_noise_ratio); - extract(serializer, self.azimuth); + serializer.extract(azimuth); - extract(serializer, self.elevation); + serializer.extract(elevation); - extract(serializer, self.sv_flags); + serializer.extract(sv_flags); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const HwStatus& self) +void HwStatus::insert(Serializer& serializer) const { - insert(serializer, self.receiver_state); + serializer.insert(receiver_state); - insert(serializer, self.antenna_state); + serializer.insert(antenna_state); - insert(serializer, self.antenna_power); + serializer.insert(antenna_power); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, HwStatus& self) +void HwStatus::extract(Serializer& serializer) { - extract(serializer, self.receiver_state); + serializer.extract(receiver_state); - extract(serializer, self.antenna_state); + serializer.extract(antenna_state); - extract(serializer, self.antenna_power); + serializer.extract(antenna_power); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const DgpsInfo& self) +void DgpsInfo::insert(Serializer& serializer) const { - insert(serializer, self.sv_id); + serializer.insert(sv_id); - insert(serializer, self.age); + serializer.insert(age); - insert(serializer, self.range_correction); + serializer.insert(range_correction); - insert(serializer, self.range_rate_correction); + serializer.insert(range_rate_correction); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, DgpsInfo& self) +void DgpsInfo::extract(Serializer& serializer) { - extract(serializer, self.sv_id); + serializer.extract(sv_id); - extract(serializer, self.age); + serializer.extract(age); - extract(serializer, self.range_correction); + serializer.extract(range_correction); - extract(serializer, self.range_rate_correction); + serializer.extract(range_rate_correction); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const DgpsChannel& self) +void DgpsChannel::insert(Serializer& serializer) const { - insert(serializer, self.sv_id); + serializer.insert(sv_id); - insert(serializer, self.age); + serializer.insert(age); - insert(serializer, self.range_correction); + serializer.insert(range_correction); - insert(serializer, self.range_rate_correction); + serializer.insert(range_rate_correction); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, DgpsChannel& self) +void DgpsChannel::extract(Serializer& serializer) { - extract(serializer, self.sv_id); + serializer.extract(sv_id); - extract(serializer, self.age); + serializer.extract(age); - extract(serializer, self.range_correction); + serializer.extract(range_correction); - extract(serializer, self.range_rate_correction); + serializer.extract(range_rate_correction); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const ClockInfo2& self) +void ClockInfo2::insert(Serializer& serializer) const { - insert(serializer, self.bias); + serializer.insert(bias); - insert(serializer, self.drift); + serializer.insert(drift); - insert(serializer, self.bias_accuracy_estimate); + serializer.insert(bias_accuracy_estimate); - insert(serializer, self.drift_accuracy_estimate); + serializer.insert(drift_accuracy_estimate); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, ClockInfo2& self) +void ClockInfo2::extract(Serializer& serializer) { - extract(serializer, self.bias); + serializer.extract(bias); - extract(serializer, self.drift); + serializer.extract(drift); - extract(serializer, self.bias_accuracy_estimate); + serializer.extract(bias_accuracy_estimate); - extract(serializer, self.drift_accuracy_estimate); + serializer.extract(drift_accuracy_estimate); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GpsLeapSeconds& self) +void GpsLeapSeconds::insert(Serializer& serializer) const { - insert(serializer, self.leap_seconds); + serializer.insert(leap_seconds); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GpsLeapSeconds& self) +void GpsLeapSeconds::extract(Serializer& serializer) { - extract(serializer, self.leap_seconds); + serializer.extract(leap_seconds); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const SbasInfo& self) +void SbasInfo::insert(Serializer& serializer) const { - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.sbas_system); + serializer.insert(sbas_system); - insert(serializer, self.sbas_id); + serializer.insert(sbas_id); - insert(serializer, self.count); + serializer.insert(count); - insert(serializer, self.sbas_status); + serializer.insert(sbas_status); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, SbasInfo& self) +void SbasInfo::extract(Serializer& serializer) { - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.sbas_system); + serializer.extract(sbas_system); - extract(serializer, self.sbas_id); + serializer.extract(sbas_id); - extract(serializer, self.count); + serializer.extract(count); - extract(serializer, self.sbas_status); + serializer.extract(sbas_status); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const SbasCorrection& self) +void SbasCorrection::insert(Serializer& serializer) const { - insert(serializer, self.index); + serializer.insert(index); - insert(serializer, self.count); + serializer.insert(count); - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.gnss_id); + serializer.insert(gnss_id); - insert(serializer, self.sv_id); + serializer.insert(sv_id); - insert(serializer, self.udrei); + serializer.insert(udrei); - insert(serializer, self.pseudorange_correction); + serializer.insert(pseudorange_correction); - insert(serializer, self.iono_correction); + serializer.insert(iono_correction); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, SbasCorrection& self) +void SbasCorrection::extract(Serializer& serializer) { - extract(serializer, self.index); + serializer.extract(index); - extract(serializer, self.count); + serializer.extract(count); - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.gnss_id); + serializer.extract(gnss_id); - extract(serializer, self.sv_id); + serializer.extract(sv_id); - extract(serializer, self.udrei); + serializer.extract(udrei); - extract(serializer, self.pseudorange_correction); + serializer.extract(pseudorange_correction); - extract(serializer, self.iono_correction); + serializer.extract(iono_correction); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const RfErrorDetection& self) +void RfErrorDetection::insert(Serializer& serializer) const { - insert(serializer, self.rf_band); + serializer.insert(rf_band); - insert(serializer, self.jamming_state); + serializer.insert(jamming_state); - insert(serializer, self.spoofing_state); + serializer.insert(spoofing_state); for(unsigned int i=0; i < 4; i++) - insert(serializer, self.reserved[i]); + serializer.insert(reserved[i]); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, RfErrorDetection& self) +void RfErrorDetection::extract(Serializer& serializer) { - extract(serializer, self.rf_band); + serializer.extract(rf_band); - extract(serializer, self.jamming_state); + serializer.extract(jamming_state); - extract(serializer, self.spoofing_state); + serializer.extract(spoofing_state); for(unsigned int i=0; i < 4; i++) - extract(serializer, self.reserved[i]); + serializer.extract(reserved[i]); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const BaseStationInfo& self) +void BaseStationInfo::insert(Serializer& serializer) const { - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.ecef_pos[i]); + serializer.insert(ecef_pos); - insert(serializer, self.height); + serializer.insert(height); - insert(serializer, self.station_id); + serializer.insert(station_id); - insert(serializer, self.indicators); + serializer.insert(indicators); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, BaseStationInfo& self) +void BaseStationInfo::extract(Serializer& serializer) { - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.ecef_pos[i]); + serializer.extract(ecef_pos); - extract(serializer, self.height); + serializer.extract(height); - extract(serializer, self.station_id); + serializer.extract(station_id); - extract(serializer, self.indicators); + serializer.extract(indicators); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const RtkCorrectionsStatus& self) +void RtkCorrectionsStatus::insert(Serializer& serializer) const { - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.epoch_status); + serializer.insert(epoch_status); - insert(serializer, self.dongle_status); + serializer.insert(dongle_status); - insert(serializer, self.gps_correction_latency); + serializer.insert(gps_correction_latency); - insert(serializer, self.glonass_correction_latency); + serializer.insert(glonass_correction_latency); - insert(serializer, self.galileo_correction_latency); + serializer.insert(galileo_correction_latency); - insert(serializer, self.beidou_correction_latency); + serializer.insert(beidou_correction_latency); for(unsigned int i=0; i < 4; i++) - insert(serializer, self.reserved[i]); + serializer.insert(reserved[i]); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, RtkCorrectionsStatus& self) +void RtkCorrectionsStatus::extract(Serializer& serializer) { - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.epoch_status); + serializer.extract(epoch_status); - extract(serializer, self.dongle_status); + serializer.extract(dongle_status); - extract(serializer, self.gps_correction_latency); + serializer.extract(gps_correction_latency); - extract(serializer, self.glonass_correction_latency); + serializer.extract(glonass_correction_latency); - extract(serializer, self.galileo_correction_latency); + serializer.extract(galileo_correction_latency); - extract(serializer, self.beidou_correction_latency); + serializer.extract(beidou_correction_latency); for(unsigned int i=0; i < 4; i++) - extract(serializer, self.reserved[i]); + serializer.extract(reserved[i]); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const SatelliteStatus& self) +void SatelliteStatus::insert(Serializer& serializer) const { - insert(serializer, self.index); + serializer.insert(index); - insert(serializer, self.count); + serializer.insert(count); - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.gnss_id); + serializer.insert(gnss_id); - insert(serializer, self.satellite_id); + serializer.insert(satellite_id); - insert(serializer, self.elevation); + serializer.insert(elevation); - insert(serializer, self.azimuth); + serializer.insert(azimuth); - insert(serializer, self.health); + serializer.insert(health); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, SatelliteStatus& self) +void SatelliteStatus::extract(Serializer& serializer) { - extract(serializer, self.index); + serializer.extract(index); - extract(serializer, self.count); + serializer.extract(count); - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.gnss_id); + serializer.extract(gnss_id); - extract(serializer, self.satellite_id); + serializer.extract(satellite_id); - extract(serializer, self.elevation); + serializer.extract(elevation); - extract(serializer, self.azimuth); + serializer.extract(azimuth); - extract(serializer, self.health); + serializer.extract(health); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const Raw& self) +void Raw::insert(Serializer& serializer) const { - insert(serializer, self.index); + serializer.insert(index); - insert(serializer, self.count); + serializer.insert(count); - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.receiver_id); + serializer.insert(receiver_id); - insert(serializer, self.tracking_channel); + serializer.insert(tracking_channel); - insert(serializer, self.gnss_id); + serializer.insert(gnss_id); - insert(serializer, self.satellite_id); + serializer.insert(satellite_id); - insert(serializer, self.signal_id); + serializer.insert(signal_id); - insert(serializer, self.signal_strength); + serializer.insert(signal_strength); - insert(serializer, self.quality); + serializer.insert(quality); - insert(serializer, self.pseudorange); + serializer.insert(pseudorange); - insert(serializer, self.carrier_phase); + serializer.insert(carrier_phase); - insert(serializer, self.doppler); + serializer.insert(doppler); - insert(serializer, self.range_uncert); + serializer.insert(range_uncert); - insert(serializer, self.phase_uncert); + serializer.insert(phase_uncert); - insert(serializer, self.doppler_uncert); + serializer.insert(doppler_uncert); - insert(serializer, self.lock_time); + serializer.insert(lock_time); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, Raw& self) +void Raw::extract(Serializer& serializer) { - extract(serializer, self.index); + serializer.extract(index); - extract(serializer, self.count); + serializer.extract(count); - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.receiver_id); + serializer.extract(receiver_id); - extract(serializer, self.tracking_channel); + serializer.extract(tracking_channel); - extract(serializer, self.gnss_id); + serializer.extract(gnss_id); - extract(serializer, self.satellite_id); + serializer.extract(satellite_id); - extract(serializer, self.signal_id); + serializer.extract(signal_id); - extract(serializer, self.signal_strength); + serializer.extract(signal_strength); - extract(serializer, self.quality); + serializer.extract(quality); - extract(serializer, self.pseudorange); + serializer.extract(pseudorange); - extract(serializer, self.carrier_phase); + serializer.extract(carrier_phase); - extract(serializer, self.doppler); + serializer.extract(doppler); - extract(serializer, self.range_uncert); + serializer.extract(range_uncert); - extract(serializer, self.phase_uncert); + serializer.extract(phase_uncert); - extract(serializer, self.doppler_uncert); + serializer.extract(doppler_uncert); - extract(serializer, self.lock_time); + serializer.extract(lock_time); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GpsEphemeris& self) +void GpsEphemeris::insert(Serializer& serializer) const { - insert(serializer, self.index); + serializer.insert(index); - insert(serializer, self.count); + serializer.insert(count); - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.satellite_id); + serializer.insert(satellite_id); - insert(serializer, self.health); + serializer.insert(health); - insert(serializer, self.iodc); + serializer.insert(iodc); - insert(serializer, self.iode); + serializer.insert(iode); - insert(serializer, self.t_oc); + serializer.insert(t_oc); - insert(serializer, self.af0); + serializer.insert(af0); - insert(serializer, self.af1); + serializer.insert(af1); - insert(serializer, self.af2); + serializer.insert(af2); - insert(serializer, self.t_gd); + serializer.insert(t_gd); - insert(serializer, self.ISC_L1CA); + serializer.insert(ISC_L1CA); - insert(serializer, self.ISC_L2C); + serializer.insert(ISC_L2C); - insert(serializer, self.t_oe); + serializer.insert(t_oe); - insert(serializer, self.a); + serializer.insert(a); - insert(serializer, self.a_dot); + serializer.insert(a_dot); - insert(serializer, self.mean_anomaly); + serializer.insert(mean_anomaly); - insert(serializer, self.delta_mean_motion); + serializer.insert(delta_mean_motion); - insert(serializer, self.delta_mean_motion_dot); + serializer.insert(delta_mean_motion_dot); - insert(serializer, self.eccentricity); + serializer.insert(eccentricity); - insert(serializer, self.argument_of_perigee); + serializer.insert(argument_of_perigee); - insert(serializer, self.omega); + serializer.insert(omega); - insert(serializer, self.omega_dot); + serializer.insert(omega_dot); - insert(serializer, self.inclination); + serializer.insert(inclination); - insert(serializer, self.inclination_dot); + serializer.insert(inclination_dot); - insert(serializer, self.c_ic); + serializer.insert(c_ic); - insert(serializer, self.c_is); + serializer.insert(c_is); - insert(serializer, self.c_uc); + serializer.insert(c_uc); - insert(serializer, self.c_us); + serializer.insert(c_us); - insert(serializer, self.c_rc); + serializer.insert(c_rc); - insert(serializer, self.c_rs); + serializer.insert(c_rs); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GpsEphemeris& self) +void GpsEphemeris::extract(Serializer& serializer) { - extract(serializer, self.index); + serializer.extract(index); - extract(serializer, self.count); + serializer.extract(count); - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.satellite_id); + serializer.extract(satellite_id); - extract(serializer, self.health); + serializer.extract(health); - extract(serializer, self.iodc); + serializer.extract(iodc); - extract(serializer, self.iode); + serializer.extract(iode); - extract(serializer, self.t_oc); + serializer.extract(t_oc); - extract(serializer, self.af0); + serializer.extract(af0); - extract(serializer, self.af1); + serializer.extract(af1); - extract(serializer, self.af2); + serializer.extract(af2); - extract(serializer, self.t_gd); + serializer.extract(t_gd); - extract(serializer, self.ISC_L1CA); + serializer.extract(ISC_L1CA); - extract(serializer, self.ISC_L2C); + serializer.extract(ISC_L2C); - extract(serializer, self.t_oe); + serializer.extract(t_oe); - extract(serializer, self.a); + serializer.extract(a); - extract(serializer, self.a_dot); + serializer.extract(a_dot); - extract(serializer, self.mean_anomaly); + serializer.extract(mean_anomaly); - extract(serializer, self.delta_mean_motion); + serializer.extract(delta_mean_motion); - extract(serializer, self.delta_mean_motion_dot); + serializer.extract(delta_mean_motion_dot); - extract(serializer, self.eccentricity); + serializer.extract(eccentricity); - extract(serializer, self.argument_of_perigee); + serializer.extract(argument_of_perigee); - extract(serializer, self.omega); + serializer.extract(omega); - extract(serializer, self.omega_dot); + serializer.extract(omega_dot); - extract(serializer, self.inclination); + serializer.extract(inclination); - extract(serializer, self.inclination_dot); + serializer.extract(inclination_dot); - extract(serializer, self.c_ic); + serializer.extract(c_ic); - extract(serializer, self.c_is); + serializer.extract(c_is); - extract(serializer, self.c_uc); + serializer.extract(c_uc); - extract(serializer, self.c_us); + serializer.extract(c_us); - extract(serializer, self.c_rc); + serializer.extract(c_rc); - extract(serializer, self.c_rs); + serializer.extract(c_rs); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GalileoEphemeris& self) +void GalileoEphemeris::insert(Serializer& serializer) const { - insert(serializer, self.index); + serializer.insert(index); - insert(serializer, self.count); + serializer.insert(count); - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.satellite_id); + serializer.insert(satellite_id); - insert(serializer, self.health); + serializer.insert(health); - insert(serializer, self.iodc); + serializer.insert(iodc); - insert(serializer, self.iode); + serializer.insert(iode); - insert(serializer, self.t_oc); + serializer.insert(t_oc); - insert(serializer, self.af0); + serializer.insert(af0); - insert(serializer, self.af1); + serializer.insert(af1); - insert(serializer, self.af2); + serializer.insert(af2); - insert(serializer, self.t_gd); + serializer.insert(t_gd); - insert(serializer, self.ISC_L1CA); + serializer.insert(ISC_L1CA); - insert(serializer, self.ISC_L2C); + serializer.insert(ISC_L2C); - insert(serializer, self.t_oe); + serializer.insert(t_oe); - insert(serializer, self.a); + serializer.insert(a); - insert(serializer, self.a_dot); + serializer.insert(a_dot); - insert(serializer, self.mean_anomaly); + serializer.insert(mean_anomaly); - insert(serializer, self.delta_mean_motion); + serializer.insert(delta_mean_motion); - insert(serializer, self.delta_mean_motion_dot); + serializer.insert(delta_mean_motion_dot); - insert(serializer, self.eccentricity); + serializer.insert(eccentricity); - insert(serializer, self.argument_of_perigee); + serializer.insert(argument_of_perigee); - insert(serializer, self.omega); + serializer.insert(omega); - insert(serializer, self.omega_dot); + serializer.insert(omega_dot); - insert(serializer, self.inclination); + serializer.insert(inclination); - insert(serializer, self.inclination_dot); + serializer.insert(inclination_dot); - insert(serializer, self.c_ic); + serializer.insert(c_ic); - insert(serializer, self.c_is); + serializer.insert(c_is); - insert(serializer, self.c_uc); + serializer.insert(c_uc); - insert(serializer, self.c_us); + serializer.insert(c_us); - insert(serializer, self.c_rc); + serializer.insert(c_rc); - insert(serializer, self.c_rs); + serializer.insert(c_rs); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GalileoEphemeris& self) +void GalileoEphemeris::extract(Serializer& serializer) { - extract(serializer, self.index); + serializer.extract(index); - extract(serializer, self.count); + serializer.extract(count); - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.satellite_id); + serializer.extract(satellite_id); - extract(serializer, self.health); + serializer.extract(health); - extract(serializer, self.iodc); + serializer.extract(iodc); - extract(serializer, self.iode); + serializer.extract(iode); - extract(serializer, self.t_oc); + serializer.extract(t_oc); - extract(serializer, self.af0); + serializer.extract(af0); - extract(serializer, self.af1); + serializer.extract(af1); - extract(serializer, self.af2); + serializer.extract(af2); - extract(serializer, self.t_gd); + serializer.extract(t_gd); - extract(serializer, self.ISC_L1CA); + serializer.extract(ISC_L1CA); - extract(serializer, self.ISC_L2C); + serializer.extract(ISC_L2C); - extract(serializer, self.t_oe); + serializer.extract(t_oe); - extract(serializer, self.a); + serializer.extract(a); - extract(serializer, self.a_dot); + serializer.extract(a_dot); - extract(serializer, self.mean_anomaly); + serializer.extract(mean_anomaly); - extract(serializer, self.delta_mean_motion); + serializer.extract(delta_mean_motion); - extract(serializer, self.delta_mean_motion_dot); + serializer.extract(delta_mean_motion_dot); - extract(serializer, self.eccentricity); + serializer.extract(eccentricity); - extract(serializer, self.argument_of_perigee); + serializer.extract(argument_of_perigee); - extract(serializer, self.omega); + serializer.extract(omega); - extract(serializer, self.omega_dot); + serializer.extract(omega_dot); - extract(serializer, self.inclination); + serializer.extract(inclination); - extract(serializer, self.inclination_dot); + serializer.extract(inclination_dot); - extract(serializer, self.c_ic); + serializer.extract(c_ic); - extract(serializer, self.c_is); + serializer.extract(c_is); - extract(serializer, self.c_uc); + serializer.extract(c_uc); - extract(serializer, self.c_us); + serializer.extract(c_us); - extract(serializer, self.c_rc); + serializer.extract(c_rc); - extract(serializer, self.c_rs); + serializer.extract(c_rs); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GloEphemeris& self) +void GloEphemeris::insert(Serializer& serializer) const { - insert(serializer, self.index); + serializer.insert(index); - insert(serializer, self.count); + serializer.insert(count); - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.satellite_id); + serializer.insert(satellite_id); - insert(serializer, self.freq_number); + serializer.insert(freq_number); - insert(serializer, self.tk); + serializer.insert(tk); - insert(serializer, self.tb); + serializer.insert(tb); - insert(serializer, self.sat_type); + serializer.insert(sat_type); - insert(serializer, self.gamma); + serializer.insert(gamma); - insert(serializer, self.tau_n); + serializer.insert(tau_n); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.x[i]); + serializer.insert(x); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.v[i]); + serializer.insert(v); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.a[i]); + serializer.insert(a); - insert(serializer, self.health); + serializer.insert(health); - insert(serializer, self.P); + serializer.insert(P); - insert(serializer, self.NT); + serializer.insert(NT); - insert(serializer, self.delta_tau_n); + serializer.insert(delta_tau_n); - insert(serializer, self.Ft); + serializer.insert(Ft); - insert(serializer, self.En); + serializer.insert(En); - insert(serializer, self.P1); + serializer.insert(P1); - insert(serializer, self.P2); + serializer.insert(P2); - insert(serializer, self.P3); + serializer.insert(P3); - insert(serializer, self.P4); + serializer.insert(P4); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GloEphemeris& self) +void GloEphemeris::extract(Serializer& serializer) { - extract(serializer, self.index); + serializer.extract(index); - extract(serializer, self.count); + serializer.extract(count); - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.satellite_id); + serializer.extract(satellite_id); - extract(serializer, self.freq_number); + serializer.extract(freq_number); - extract(serializer, self.tk); + serializer.extract(tk); - extract(serializer, self.tb); + serializer.extract(tb); - extract(serializer, self.sat_type); + serializer.extract(sat_type); - extract(serializer, self.gamma); + serializer.extract(gamma); - extract(serializer, self.tau_n); + serializer.extract(tau_n); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.x[i]); + serializer.extract(x); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.v[i]); + serializer.extract(v); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.a[i]); + serializer.extract(a); - extract(serializer, self.health); + serializer.extract(health); - extract(serializer, self.P); + serializer.extract(P); - extract(serializer, self.NT); + serializer.extract(NT); - extract(serializer, self.delta_tau_n); + serializer.extract(delta_tau_n); - extract(serializer, self.Ft); + serializer.extract(Ft); - extract(serializer, self.En); + serializer.extract(En); - extract(serializer, self.P1); + serializer.extract(P1); - extract(serializer, self.P2); + serializer.extract(P2); - extract(serializer, self.P3); + serializer.extract(P3); - extract(serializer, self.P4); + serializer.extract(P4); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GpsIonoCorr& self) +void GpsIonoCorr::insert(Serializer& serializer) const { - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); for(unsigned int i=0; i < 4; i++) - insert(serializer, self.alpha[i]); + serializer.insert(alpha[i]); for(unsigned int i=0; i < 4; i++) - insert(serializer, self.beta[i]); + serializer.insert(beta[i]); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GpsIonoCorr& self) +void GpsIonoCorr::extract(Serializer& serializer) { - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); for(unsigned int i=0; i < 4; i++) - extract(serializer, self.alpha[i]); + serializer.extract(alpha[i]); for(unsigned int i=0; i < 4; i++) - extract(serializer, self.beta[i]); + serializer.extract(beta[i]); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const GalileoIonoCorr& self) +void GalileoIonoCorr::insert(Serializer& serializer) const { - insert(serializer, self.time_of_week); + serializer.insert(time_of_week); - insert(serializer, self.week_number); + serializer.insert(week_number); - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.alpha[i]); + serializer.insert(alpha); - insert(serializer, self.disturbance_flags); + serializer.insert(disturbance_flags); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GalileoIonoCorr& self) +void GalileoIonoCorr::extract(Serializer& serializer) { - extract(serializer, self.time_of_week); + serializer.extract(time_of_week); - extract(serializer, self.week_number); + serializer.extract(week_number); - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.alpha[i]); + serializer.extract(alpha); - extract(serializer, self.disturbance_flags); + serializer.extract(disturbance_flags); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } diff --git a/src/cpp/mip/definitions/data_gnss.hpp b/src/cpp/mip/definitions/data_gnss.hpp index a4aa2b4d2..6a07b7573 100644 --- a/src/cpp/mip/definitions/data_gnss.hpp +++ b/src/cpp/mip/definitions/data_gnss.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -178,6 +176,7 @@ struct PosLlh { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -199,23 +198,10 @@ struct PosLlh ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool latLon() const { return (value & LAT_LON) > 0; } - void latLon(bool val) { if(val) value |= LAT_LON; else value &= ~LAT_LON; } - bool ellipsoidHeight() const { return (value & ELLIPSOID_HEIGHT) > 0; } - void ellipsoidHeight(bool val) { if(val) value |= ELLIPSOID_HEIGHT; else value &= ~ELLIPSOID_HEIGHT; } - bool mslHeight() const { return (value & MSL_HEIGHT) > 0; } - void mslHeight(bool val) { if(val) value |= MSL_HEIGHT; else value &= ~MSL_HEIGHT; } - bool horizontalAccuracy() const { return (value & HORIZONTAL_ACCURACY) > 0; } - void horizontalAccuracy(bool val) { if(val) value |= HORIZONTAL_ACCURACY; else value &= ~HORIZONTAL_ACCURACY; } - bool verticalAccuracy() const { return (value & VERTICAL_ACCURACY) > 0; } - void verticalAccuracy(bool val) { if(val) value |= VERTICAL_ACCURACY; else value &= ~VERTICAL_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double latitude = 0; ///< [degrees] double longitude = 0; ///< [degrees] double ellipsoid_height = 0; ///< [meters] @@ -224,26 +210,29 @@ struct PosLlh float vertical_accuracy = 0; ///< [meters] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_POSITION_LLH; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PosLlh"; static constexpr const char* DOC_NAME = "GNSS LLH Position"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(latitude,longitude,ellipsoid_height,msl_height,horizontal_accuracy,vertical_accuracy,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(latitude),std::ref(longitude),std::ref(ellipsoid_height),std::ref(msl_height),std::ref(horizontal_accuracy),std::ref(vertical_accuracy),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const PosLlh& self); -void extract(::microstrain::Serializer& serializer, PosLlh& self); - ///@} /// @@ -257,6 +246,7 @@ struct PosEcef { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -275,41 +265,37 @@ struct PosEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool position() const { return (value & POSITION) > 0; } - void position(bool val) { if(val) value |= POSITION; else value &= ~POSITION; } - bool positionAccuracy() const { return (value & POSITION_ACCURACY) > 0; } - void positionAccuracy(bool val) { if(val) value |= POSITION_ACCURACY; else value &= ~POSITION_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Vector3d x; ///< [meters] float x_accuracy = 0; ///< [meters] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_POSITION_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PosEcef"; static constexpr const char* DOC_NAME = "GNSS ECEF Position"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(x[0],x[1],x[2],x_accuracy,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(x[0]),std::ref(x[1]),std::ref(x[2]),std::ref(x_accuracy),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const PosEcef& self); -void extract(::microstrain::Serializer& serializer, PosEcef& self); - ///@} /// @@ -323,6 +309,7 @@ struct VelNed { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -345,25 +332,10 @@ struct VelNed ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool velocity() const { return (value & VELOCITY) > 0; } - void velocity(bool val) { if(val) value |= VELOCITY; else value &= ~VELOCITY; } - bool speed3d() const { return (value & SPEED_3D) > 0; } - void speed3d(bool val) { if(val) value |= SPEED_3D; else value &= ~SPEED_3D; } - bool groundSpeed() const { return (value & GROUND_SPEED) > 0; } - void groundSpeed(bool val) { if(val) value |= GROUND_SPEED; else value &= ~GROUND_SPEED; } - bool heading() const { return (value & HEADING) > 0; } - void heading(bool val) { if(val) value |= HEADING; else value &= ~HEADING; } - bool speedAccuracy() const { return (value & SPEED_ACCURACY) > 0; } - void speedAccuracy(bool val) { if(val) value |= SPEED_ACCURACY; else value &= ~SPEED_ACCURACY; } - bool headingAccuracy() const { return (value & HEADING_ACCURACY) > 0; } - void headingAccuracy(bool val) { if(val) value |= HEADING_ACCURACY; else value &= ~HEADING_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Vector3f v; ///< [meters/second] float speed = 0; ///< [meters/second] float ground_speed = 0; ///< [meters/second] @@ -372,26 +344,29 @@ struct VelNed float heading_accuracy = 0; ///< [degrees] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_VELOCITY_NED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "VelNed"; static constexpr const char* DOC_NAME = "NED Velocity"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(v[0],v[1],v[2],speed,ground_speed,heading,speed_accuracy,heading_accuracy,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(v[0]),std::ref(v[1]),std::ref(v[2]),std::ref(speed),std::ref(ground_speed),std::ref(heading),std::ref(speed_accuracy),std::ref(heading_accuracy),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const VelNed& self); -void extract(::microstrain::Serializer& serializer, VelNed& self); - ///@} /// @@ -405,6 +380,7 @@ struct VelEcef { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -423,41 +399,37 @@ struct VelEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool velocity() const { return (value & VELOCITY) > 0; } - void velocity(bool val) { if(val) value |= VELOCITY; else value &= ~VELOCITY; } - bool velocityAccuracy() const { return (value & VELOCITY_ACCURACY) > 0; } - void velocityAccuracy(bool val) { if(val) value |= VELOCITY_ACCURACY; else value &= ~VELOCITY_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Vector3f v; ///< [meters/second] float v_accuracy = 0; ///< [meters/second] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_VELOCITY_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "VelEcef"; static constexpr const char* DOC_NAME = "GNSS ECEF Velocity"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(v[0],v[1],v[2],v_accuracy,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(v[0]),std::ref(v[1]),std::ref(v[2]),std::ref(v_accuracy),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const VelEcef& self); -void extract(::microstrain::Serializer& serializer, VelEcef& self); - ///@} /// @@ -471,6 +443,7 @@ struct Dop { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -494,27 +467,10 @@ struct Dop ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gdop() const { return (value & GDOP) > 0; } - void gdop(bool val) { if(val) value |= GDOP; else value &= ~GDOP; } - bool pdop() const { return (value & PDOP) > 0; } - void pdop(bool val) { if(val) value |= PDOP; else value &= ~PDOP; } - bool hdop() const { return (value & HDOP) > 0; } - void hdop(bool val) { if(val) value |= HDOP; else value &= ~HDOP; } - bool vdop() const { return (value & VDOP) > 0; } - void vdop(bool val) { if(val) value |= VDOP; else value &= ~VDOP; } - bool tdop() const { return (value & TDOP) > 0; } - void tdop(bool val) { if(val) value |= TDOP; else value &= ~TDOP; } - bool ndop() const { return (value & NDOP) > 0; } - void ndop(bool val) { if(val) value |= NDOP; else value &= ~NDOP; } - bool edop() const { return (value & EDOP) > 0; } - void edop(bool val) { if(val) value |= EDOP; else value &= ~EDOP; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters float gdop = 0; ///< Geometric DOP float pdop = 0; ///< Position DOP float hdop = 0; ///< Horizontal DOP @@ -524,26 +480,29 @@ struct Dop float edop = 0; ///< Easting DOP ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_DOP; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Dop"; static constexpr const char* DOC_NAME = "Dop"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(gdop,pdop,hdop,vdop,tdop,ndop,edop,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(gdop),std::ref(pdop),std::ref(hdop),std::ref(vdop),std::ref(tdop),std::ref(ndop),std::ref(edop),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const Dop& self); -void extract(::microstrain::Serializer& serializer, Dop& self); - ///@} /// @@ -557,6 +516,7 @@ struct UtcTime { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -575,17 +535,10 @@ struct UtcTime ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gnssDateTime() const { return (value & GNSS_DATE_TIME) > 0; } - void gnssDateTime(bool val) { if(val) value |= GNSS_DATE_TIME; else value &= ~GNSS_DATE_TIME; } - bool leapSecondsKnown() const { return (value & LEAP_SECONDS_KNOWN) > 0; } - void leapSecondsKnown(bool val) { if(val) value |= LEAP_SECONDS_KNOWN; else value &= ~LEAP_SECONDS_KNOWN; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint16_t year = 0; uint8_t month = 0; ///< Month (1-12) uint8_t day = 0; ///< Day (1-31) @@ -595,26 +548,29 @@ struct UtcTime uint32_t msec = 0; ///< Millisecond(0-999) ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_UTC_TIME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "UtcTime"; static constexpr const char* DOC_NAME = "UtcTime"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(year,month,day,hour,min,sec,msec,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(year),std::ref(month),std::ref(day),std::ref(hour),std::ref(min),std::ref(sec),std::ref(msec),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const UtcTime& self); -void extract(::microstrain::Serializer& serializer, UtcTime& self); - ///@} /// @@ -628,6 +584,7 @@ struct GpsTime { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -646,41 +603,37 @@ struct GpsTime ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double tow = 0; ///< GPS Time of week [seconds] uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GPS_TIME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsTime"; static constexpr const char* DOC_NAME = "GpsTime"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(tow,week_number,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GpsTime& self); -void extract(::microstrain::Serializer& serializer, GpsTime& self); - ///@} /// @@ -694,6 +647,7 @@ struct ClockInfo { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -713,44 +667,38 @@ struct ClockInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool bias() const { return (value & BIAS) > 0; } - void bias(bool val) { if(val) value |= BIAS; else value &= ~BIAS; } - bool drift() const { return (value & DRIFT) > 0; } - void drift(bool val) { if(val) value |= DRIFT; else value &= ~DRIFT; } - bool accuracyEstimate() const { return (value & ACCURACY_ESTIMATE) > 0; } - void accuracyEstimate(bool val) { if(val) value |= ACCURACY_ESTIMATE; else value &= ~ACCURACY_ESTIMATE; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double bias = 0; ///< [seconds] double drift = 0; ///< [seconds/second] double accuracy_estimate = 0; ///< [seconds] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_CLOCK_INFO; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ClockInfo"; static constexpr const char* DOC_NAME = "ClockInfo"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias,drift,accuracy_estimate,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias),std::ref(drift),std::ref(accuracy_estimate),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ClockInfo& self); -void extract(::microstrain::Serializer& serializer, ClockInfo& self); - ///@} /// @@ -776,6 +724,7 @@ struct FixInfo struct FixFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -793,17 +742,12 @@ struct FixInfo FixFlags& operator|=(uint16_t val) { return *this = value | val; } FixFlags& operator&=(uint16_t val) { return *this = value & val; } - bool sbasUsed() const { return (value & SBAS_USED) > 0; } - void sbasUsed(bool val) { if(val) value |= SBAS_USED; else value &= ~SBAS_USED; } - bool dgnssUsed() const { return (value & DGNSS_USED) > 0; } - void dgnssUsed(bool val) { if(val) value |= DGNSS_USED; else value &= ~DGNSS_USED; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -823,44 +767,38 @@ struct FixInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool fixType() const { return (value & FIX_TYPE) > 0; } - void fixType(bool val) { if(val) value |= FIX_TYPE; else value &= ~FIX_TYPE; } - bool numSv() const { return (value & NUM_SV) > 0; } - void numSv(bool val) { if(val) value |= NUM_SV; else value &= ~NUM_SV; } - bool fixFlags() const { return (value & FIX_FLAGS) > 0; } - void fixFlags(bool val) { if(val) value |= FIX_FLAGS; else value &= ~FIX_FLAGS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters FixType fix_type = static_cast(0); uint8_t num_sv = 0; FixFlags fix_flags; ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_FIX_INFO; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "FixInfo"; static constexpr const char* DOC_NAME = "FixInfo"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(fix_type,num_sv,fix_flags,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(fix_type),std::ref(num_sv),std::ref(fix_flags),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const FixInfo& self); -void extract(::microstrain::Serializer& serializer, FixInfo& self); - ///@} /// @@ -876,6 +814,7 @@ struct SvInfo { struct SVFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -893,17 +832,12 @@ struct SvInfo SVFlags& operator|=(uint16_t val) { return *this = value | val; } SVFlags& operator&=(uint16_t val) { return *this = value & val; } - bool usedForNavigation() const { return (value & USED_FOR_NAVIGATION) > 0; } - void usedForNavigation(bool val) { if(val) value |= USED_FOR_NAVIGATION; else value &= ~USED_FOR_NAVIGATION; } - bool healthy() const { return (value & HEALTHY) > 0; } - void healthy(bool val) { if(val) value |= HEALTHY; else value &= ~HEALTHY; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -926,25 +860,10 @@ struct SvInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool channel() const { return (value & CHANNEL) > 0; } - void channel(bool val) { if(val) value |= CHANNEL; else value &= ~CHANNEL; } - bool svId() const { return (value & SV_ID) > 0; } - void svId(bool val) { if(val) value |= SV_ID; else value &= ~SV_ID; } - bool carrierNoiseRatio() const { return (value & CARRIER_NOISE_RATIO) > 0; } - void carrierNoiseRatio(bool val) { if(val) value |= CARRIER_NOISE_RATIO; else value &= ~CARRIER_NOISE_RATIO; } - bool azimuth() const { return (value & AZIMUTH) > 0; } - void azimuth(bool val) { if(val) value |= AZIMUTH; else value &= ~AZIMUTH; } - bool elevation() const { return (value & ELEVATION) > 0; } - void elevation(bool val) { if(val) value |= ELEVATION; else value &= ~ELEVATION; } - bool svFlags() const { return (value & SV_FLAGS) > 0; } - void svFlags(bool val) { if(val) value |= SV_FLAGS; else value &= ~SV_FLAGS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t channel = 0; ///< Receiver channel number uint8_t sv_id = 0; ///< GNSS Satellite ID uint16_t carrier_noise_ratio = 0; ///< [dBHz] @@ -953,26 +872,29 @@ struct SvInfo SVFlags sv_flags; ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_SV_INFO; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SvInfo"; static constexpr const char* DOC_NAME = "SvInfo"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(channel,sv_id,carrier_noise_ratio,azimuth,elevation,sv_flags,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(channel),std::ref(sv_id),std::ref(carrier_noise_ratio),std::ref(azimuth),std::ref(elevation),std::ref(sv_flags),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const SvInfo& self); -void extract(::microstrain::Serializer& serializer, SvInfo& self); - ///@} /// @@ -1009,6 +931,7 @@ struct HwStatus struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1028,44 +951,38 @@ struct HwStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool sensorState() const { return (value & SENSOR_STATE) > 0; } - void sensorState(bool val) { if(val) value |= SENSOR_STATE; else value &= ~SENSOR_STATE; } - bool antennaState() const { return (value & ANTENNA_STATE) > 0; } - void antennaState(bool val) { if(val) value |= ANTENNA_STATE; else value &= ~ANTENNA_STATE; } - bool antennaPower() const { return (value & ANTENNA_POWER) > 0; } - void antennaPower(bool val) { if(val) value |= ANTENNA_POWER; else value &= ~ANTENNA_POWER; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters ReceiverState receiver_state = static_cast(0); AntennaState antenna_state = static_cast(0); AntennaPower antenna_power = static_cast(0); ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_HW_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "HwStatus"; static constexpr const char* DOC_NAME = "GNSS Hardware Status"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(receiver_state,antenna_state,antenna_power,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(receiver_state),std::ref(antenna_state),std::ref(antenna_power),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const HwStatus& self); -void extract(::microstrain::Serializer& serializer, HwStatus& self); - ///@} /// @@ -1091,6 +1008,7 @@ struct DgpsInfo { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1111,47 +1029,39 @@ struct DgpsInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool age() const { return (value & AGE) > 0; } - void age(bool val) { if(val) value |= AGE; else value &= ~AGE; } - bool baseStationId() const { return (value & BASE_STATION_ID) > 0; } - void baseStationId(bool val) { if(val) value |= BASE_STATION_ID; else value &= ~BASE_STATION_ID; } - bool baseStationStatus() const { return (value & BASE_STATION_STATUS) > 0; } - void baseStationStatus(bool val) { if(val) value |= BASE_STATION_STATUS; else value &= ~BASE_STATION_STATUS; } - bool numChannels() const { return (value & NUM_CHANNELS) > 0; } - void numChannels(bool val) { if(val) value |= NUM_CHANNELS; else value &= ~NUM_CHANNELS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t sv_id = 0; float age = 0; float range_correction = 0; float range_rate_correction = 0; ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_DGPS_INFO; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DgpsInfo"; static constexpr const char* DOC_NAME = "DgpsInfo"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(sv_id,age,range_correction,range_rate_correction,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(sv_id),std::ref(age),std::ref(range_correction),std::ref(range_rate_correction),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const DgpsInfo& self); -void extract(::microstrain::Serializer& serializer, DgpsInfo& self); - ///@} /// @@ -1167,6 +1077,7 @@ struct DgpsChannel { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1187,47 +1098,39 @@ struct DgpsChannel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool id() const { return (value & ID) > 0; } - void id(bool val) { if(val) value |= ID; else value &= ~ID; } - bool age() const { return (value & AGE) > 0; } - void age(bool val) { if(val) value |= AGE; else value &= ~AGE; } - bool rangeCorrection() const { return (value & RANGE_CORRECTION) > 0; } - void rangeCorrection(bool val) { if(val) value |= RANGE_CORRECTION; else value &= ~RANGE_CORRECTION; } - bool rangeRateCorrection() const { return (value & RANGE_RATE_CORRECTION) > 0; } - void rangeRateCorrection(bool val) { if(val) value |= RANGE_RATE_CORRECTION; else value &= ~RANGE_RATE_CORRECTION; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t sv_id = 0; float age = 0; ///< [s] float range_correction = 0; ///< [m] float range_rate_correction = 0; ///< [m/s] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_DGPS_CHANNEL_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DgpsChannel"; static constexpr const char* DOC_NAME = "DgpsChannel"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(sv_id,age,range_correction,range_rate_correction,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(sv_id),std::ref(age),std::ref(range_correction),std::ref(range_rate_correction),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const DgpsChannel& self); -void extract(::microstrain::Serializer& serializer, DgpsChannel& self); - ///@} /// @@ -1243,6 +1146,7 @@ struct ClockInfo2 { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1263,47 +1167,39 @@ struct ClockInfo2 ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool bias() const { return (value & BIAS) > 0; } - void bias(bool val) { if(val) value |= BIAS; else value &= ~BIAS; } - bool drift() const { return (value & DRIFT) > 0; } - void drift(bool val) { if(val) value |= DRIFT; else value &= ~DRIFT; } - bool biasAccuracy() const { return (value & BIAS_ACCURACY) > 0; } - void biasAccuracy(bool val) { if(val) value |= BIAS_ACCURACY; else value &= ~BIAS_ACCURACY; } - bool driftAccuracy() const { return (value & DRIFT_ACCURACY) > 0; } - void driftAccuracy(bool val) { if(val) value |= DRIFT_ACCURACY; else value &= ~DRIFT_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double bias = 0; double drift = 0; double bias_accuracy_estimate = 0; double drift_accuracy_estimate = 0; ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_CLOCK_INFO_2; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ClockInfo2"; static constexpr const char* DOC_NAME = "ClockInfo2"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(bias,drift,bias_accuracy_estimate,drift_accuracy_estimate,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(bias),std::ref(drift),std::ref(bias_accuracy_estimate),std::ref(drift_accuracy_estimate),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ClockInfo2& self); -void extract(::microstrain::Serializer& serializer, ClockInfo2& self); - ///@} /// @@ -1317,6 +1213,7 @@ struct GpsLeapSeconds { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1333,36 +1230,36 @@ struct GpsLeapSeconds ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool leapSeconds() const { return (value & LEAP_SECONDS) > 0; } - void leapSeconds(bool val) { if(val) value |= LEAP_SECONDS; else value &= ~LEAP_SECONDS; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t leap_seconds = 0; ///< [s] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GPS_LEAP_SECONDS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsLeapSeconds"; static constexpr const char* DOC_NAME = "GpsLeapSeconds"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(leap_seconds,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(leap_seconds),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GpsLeapSeconds& self); -void extract(::microstrain::Serializer& serializer, GpsLeapSeconds& self); - ///@} /// @@ -1376,6 +1273,7 @@ struct SbasInfo { struct SbasStatus : Bitfield { + typedef uint8_t Type; enum _enumType : uint8_t { NONE = 0x00, @@ -1395,21 +1293,12 @@ struct SbasInfo SbasStatus& operator|=(uint8_t val) { return *this = value | val; } SbasStatus& operator&=(uint8_t val) { return *this = value & val; } - bool rangeAvailable() const { return (value & RANGE_AVAILABLE) > 0; } - void rangeAvailable(bool val) { if(val) value |= RANGE_AVAILABLE; else value &= ~RANGE_AVAILABLE; } - bool correctionsAvailable() const { return (value & CORRECTIONS_AVAILABLE) > 0; } - void correctionsAvailable(bool val) { if(val) value |= CORRECTIONS_AVAILABLE; else value &= ~CORRECTIONS_AVAILABLE; } - bool integrityAvailable() const { return (value & INTEGRITY_AVAILABLE) > 0; } - void integrityAvailable(bool val) { if(val) value |= INTEGRITY_AVAILABLE; else value &= ~INTEGRITY_AVAILABLE; } - bool testMode() const { return (value & TEST_MODE) > 0; } - void testMode(bool val) { if(val) value |= TEST_MODE; else value &= ~TEST_MODE; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1432,25 +1321,10 @@ struct SbasInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool sbasSystem() const { return (value & SBAS_SYSTEM) > 0; } - void sbasSystem(bool val) { if(val) value |= SBAS_SYSTEM; else value &= ~SBAS_SYSTEM; } - bool sbasId() const { return (value & SBAS_ID) > 0; } - void sbasId(bool val) { if(val) value |= SBAS_ID; else value &= ~SBAS_ID; } - bool count() const { return (value & COUNT) > 0; } - void count(bool val) { if(val) value |= COUNT; else value &= ~COUNT; } - bool sbasStatus() const { return (value & SBAS_STATUS) > 0; } - void sbasStatus(bool val) { if(val) value |= SBAS_STATUS; else value &= ~SBAS_STATUS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double time_of_week = 0; ///< GPS Time of week [seconds] uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] SbasSystem sbas_system = static_cast(0); ///< SBAS system id @@ -1459,26 +1333,29 @@ struct SbasInfo SbasStatus sbas_status; ///< Status of the SBAS service ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_SBAS_INFO; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SbasInfo"; static constexpr const char* DOC_NAME = "SbasInfo"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_of_week,week_number,sbas_system,sbas_id,count,sbas_status,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(sbas_system),std::ref(sbas_id),std::ref(count),std::ref(sbas_status),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const SbasInfo& self); -void extract(::microstrain::Serializer& serializer, SbasInfo& self); - ///@} /// @@ -1514,6 +1391,7 @@ struct SbasCorrection { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1533,19 +1411,10 @@ struct SbasCorrection ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool udrei() const { return (value & UDREI) > 0; } - void udrei(bool val) { if(val) value |= UDREI; else value &= ~UDREI; } - bool pseudorangeCorrection() const { return (value & PSEUDORANGE_CORRECTION) > 0; } - void pseudorangeCorrection(bool val) { if(val) value |= PSEUDORANGE_CORRECTION; else value &= ~PSEUDORANGE_CORRECTION; } - bool ionoCorrection() const { return (value & IONO_CORRECTION) > 0; } - void ionoCorrection(bool val) { if(val) value |= IONO_CORRECTION; else value &= ~IONO_CORRECTION; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t index = 0; ///< Index of this field in this epoch. uint8_t count = 0; ///< Total number of fields in this epoch. double time_of_week = 0; ///< GPS Time of week the message was received [seconds] @@ -1557,26 +1426,29 @@ struct SbasCorrection float iono_correction = 0; ///< Ionospheric correction [meters]. ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_SBAS_CORRECTION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SbasCorrection"; static constexpr const char* DOC_NAME = "SbasCorrection"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(index,count,time_of_week,week_number,gnss_id,sv_id,udrei,pseudorange_correction,iono_correction,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(gnss_id),std::ref(sv_id),std::ref(udrei),std::ref(pseudorange_correction),std::ref(iono_correction),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const SbasCorrection& self); -void extract(::microstrain::Serializer& serializer, SbasCorrection& self); - ///@} /// @@ -1614,6 +1486,7 @@ struct RfErrorDetection struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1633,45 +1506,39 @@ struct RfErrorDetection ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool rfBand() const { return (value & RF_BAND) > 0; } - void rfBand(bool val) { if(val) value |= RF_BAND; else value &= ~RF_BAND; } - bool jammingState() const { return (value & JAMMING_STATE) > 0; } - void jammingState(bool val) { if(val) value |= JAMMING_STATE; else value &= ~JAMMING_STATE; } - bool spoofingState() const { return (value & SPOOFING_STATE) > 0; } - void spoofingState(bool val) { if(val) value |= SPOOFING_STATE; else value &= ~SPOOFING_STATE; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters RFBand rf_band = static_cast(0); ///< RF Band of the reported information JammingState jamming_state = static_cast(0); ///< GNSS Jamming State (as reported by the GNSS module) SpoofingState spoofing_state = static_cast(0); ///< GNSS Spoofing State (as reported by the GNSS module) uint8_t reserved[4] = {0}; ///< Reserved for future use ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_RF_ERROR_DETECTION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RfErrorDetection"; static constexpr const char* DOC_NAME = "RfErrorDetection"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(rf_band,jamming_state,spoofing_state,reserved,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(rf_band),std::ref(jamming_state),std::ref(spoofing_state),std::ref(reserved),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const RfErrorDetection& self); -void extract(::microstrain::Serializer& serializer, RfErrorDetection& self); - ///@} /// @@ -1687,6 +1554,7 @@ struct BaseStationInfo { struct IndicatorFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1711,31 +1579,12 @@ struct BaseStationInfo IndicatorFlags& operator|=(uint16_t val) { return *this = value | val; } IndicatorFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gps() const { return (value & GPS) > 0; } - void gps(bool val) { if(val) value |= GPS; else value &= ~GPS; } - bool glonass() const { return (value & GLONASS) > 0; } - void glonass(bool val) { if(val) value |= GLONASS; else value &= ~GLONASS; } - bool galileo() const { return (value & GALILEO) > 0; } - void galileo(bool val) { if(val) value |= GALILEO; else value &= ~GALILEO; } - bool beidou() const { return (value & BEIDOU) > 0; } - void beidou(bool val) { if(val) value |= BEIDOU; else value &= ~BEIDOU; } - bool refStation() const { return (value & REF_STATION) > 0; } - void refStation(bool val) { if(val) value |= REF_STATION; else value &= ~REF_STATION; } - bool singleReceiver() const { return (value & SINGLE_RECEIVER) > 0; } - void singleReceiver(bool val) { if(val) value |= SINGLE_RECEIVER; else value &= ~SINGLE_RECEIVER; } - bool quarterCycleBit1() const { return (value & QUARTER_CYCLE_BIT1) > 0; } - void quarterCycleBit1(bool val) { if(val) value |= QUARTER_CYCLE_BIT1; else value &= ~QUARTER_CYCLE_BIT1; } - bool quarterCycleBit2() const { return (value & QUARTER_CYCLE_BIT2) > 0; } - void quarterCycleBit2(bool val) { if(val) value |= QUARTER_CYCLE_BIT2; else value &= ~QUARTER_CYCLE_BIT2; } - uint16_t quarterCycleBits() const { return (value & QUARTER_CYCLE_BITS) >> 6; } - void quarterCycleBits(uint16_t val) { value = (value & ~QUARTER_CYCLE_BITS) | (val << 6); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1758,25 +1607,10 @@ struct BaseStationInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool ecefPosition() const { return (value & ECEF_POSITION) > 0; } - void ecefPosition(bool val) { if(val) value |= ECEF_POSITION; else value &= ~ECEF_POSITION; } - bool height() const { return (value & HEIGHT) > 0; } - void height(bool val) { if(val) value |= HEIGHT; else value &= ~HEIGHT; } - bool stationId() const { return (value & STATION_ID) > 0; } - void stationId(bool val) { if(val) value |= STATION_ID; else value &= ~STATION_ID; } - bool indicators() const { return (value & INDICATORS) > 0; } - void indicators(bool val) { if(val) value |= INDICATORS; else value &= ~INDICATORS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double time_of_week = 0; ///< GPS Time of week the message was received [seconds] uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] Vector3d ecef_pos; ///< Earth-centered, Earth-fixed [m] @@ -1785,26 +1619,29 @@ struct BaseStationInfo IndicatorFlags indicators; ///< Bitfield ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_BASE_STATION_INFO; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "BaseStationInfo"; static constexpr const char* DOC_NAME = "BaseStationInfo"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_of_week,week_number,ecef_pos[0],ecef_pos[1],ecef_pos[2],height,station_id,indicators,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(ecef_pos[0]),std::ref(ecef_pos[1]),std::ref(ecef_pos[2]),std::ref(height),std::ref(station_id),std::ref(indicators),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const BaseStationInfo& self); -void extract(::microstrain::Serializer& serializer, BaseStationInfo& self); - ///@} /// @@ -1817,6 +1654,7 @@ struct RtkCorrectionsStatus { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1841,31 +1679,12 @@ struct RtkCorrectionsStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool epochStatus() const { return (value & EPOCH_STATUS) > 0; } - void epochStatus(bool val) { if(val) value |= EPOCH_STATUS; else value &= ~EPOCH_STATUS; } - bool dongleStatus() const { return (value & DONGLE_STATUS) > 0; } - void dongleStatus(bool val) { if(val) value |= DONGLE_STATUS; else value &= ~DONGLE_STATUS; } - bool gpsLatency() const { return (value & GPS_LATENCY) > 0; } - void gpsLatency(bool val) { if(val) value |= GPS_LATENCY; else value &= ~GPS_LATENCY; } - bool glonassLatency() const { return (value & GLONASS_LATENCY) > 0; } - void glonassLatency(bool val) { if(val) value |= GLONASS_LATENCY; else value &= ~GLONASS_LATENCY; } - bool galileoLatency() const { return (value & GALILEO_LATENCY) > 0; } - void galileoLatency(bool val) { if(val) value |= GALILEO_LATENCY; else value &= ~GALILEO_LATENCY; } - bool beidouLatency() const { return (value & BEIDOU_LATENCY) > 0; } - void beidouLatency(bool val) { if(val) value |= BEIDOU_LATENCY; else value &= ~BEIDOU_LATENCY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - struct EpochStatus : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1890,29 +1709,10 @@ struct RtkCorrectionsStatus EpochStatus& operator|=(uint16_t val) { return *this = value | val; } EpochStatus& operator&=(uint16_t val) { return *this = value & val; } - bool antennaLocationReceived() const { return (value & ANTENNA_LOCATION_RECEIVED) > 0; } - void antennaLocationReceived(bool val) { if(val) value |= ANTENNA_LOCATION_RECEIVED; else value &= ~ANTENNA_LOCATION_RECEIVED; } - bool antennaDescriptionReceived() const { return (value & ANTENNA_DESCRIPTION_RECEIVED) > 0; } - void antennaDescriptionReceived(bool val) { if(val) value |= ANTENNA_DESCRIPTION_RECEIVED; else value &= ~ANTENNA_DESCRIPTION_RECEIVED; } - bool gpsReceived() const { return (value & GPS_RECEIVED) > 0; } - void gpsReceived(bool val) { if(val) value |= GPS_RECEIVED; else value &= ~GPS_RECEIVED; } - bool glonassReceived() const { return (value & GLONASS_RECEIVED) > 0; } - void glonassReceived(bool val) { if(val) value |= GLONASS_RECEIVED; else value &= ~GLONASS_RECEIVED; } - bool galileoReceived() const { return (value & GALILEO_RECEIVED) > 0; } - void galileoReceived(bool val) { if(val) value |= GALILEO_RECEIVED; else value &= ~GALILEO_RECEIVED; } - bool beidouReceived() const { return (value & BEIDOU_RECEIVED) > 0; } - void beidouReceived(bool val) { if(val) value |= BEIDOU_RECEIVED; else value &= ~BEIDOU_RECEIVED; } - bool usingGpsMsmMessages() const { return (value & USING_GPS_MSM_MESSAGES) > 0; } - void usingGpsMsmMessages(bool val) { if(val) value |= USING_GPS_MSM_MESSAGES; else value &= ~USING_GPS_MSM_MESSAGES; } - bool usingGlonassMsmMessages() const { return (value & USING_GLONASS_MSM_MESSAGES) > 0; } - void usingGlonassMsmMessages(bool val) { if(val) value |= USING_GLONASS_MSM_MESSAGES; else value &= ~USING_GLONASS_MSM_MESSAGES; } - bool dongleStatusReadFailed() const { return (value & DONGLE_STATUS_READ_FAILED) > 0; } - void dongleStatusReadFailed(bool val) { if(val) value |= DONGLE_STATUS_READ_FAILED; else value &= ~DONGLE_STATUS_READ_FAILED; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double time_of_week = 0; ///< GPS Time of week [seconds] uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] EpochStatus epoch_status; ///< Status of the corrections received during this epoch @@ -1924,26 +1724,29 @@ struct RtkCorrectionsStatus uint32_t reserved[4] = {0}; ///< Reserved for future use ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_RTK_CORRECTIONS_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RtkCorrectionsStatus"; static constexpr const char* DOC_NAME = "RtkCorrectionsStatus"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_of_week,week_number,epoch_status,dongle_status,gps_correction_latency,glonass_correction_latency,galileo_correction_latency,beidou_correction_latency,reserved,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(epoch_status),std::ref(dongle_status),std::ref(gps_correction_latency),std::ref(glonass_correction_latency),std::ref(galileo_correction_latency),std::ref(beidou_correction_latency),std::ref(reserved),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const RtkCorrectionsStatus& self); -void extract(::microstrain::Serializer& serializer, RtkCorrectionsStatus& self); - ///@} /// @@ -1957,6 +1760,7 @@ struct SatelliteStatus { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -1980,27 +1784,10 @@ struct SatelliteStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool gnssId() const { return (value & GNSS_ID) > 0; } - void gnssId(bool val) { if(val) value |= GNSS_ID; else value &= ~GNSS_ID; } - bool satelliteId() const { return (value & SATELLITE_ID) > 0; } - void satelliteId(bool val) { if(val) value |= SATELLITE_ID; else value &= ~SATELLITE_ID; } - bool elevation() const { return (value & ELEVATION) > 0; } - void elevation(bool val) { if(val) value |= ELEVATION; else value &= ~ELEVATION; } - bool azimuth() const { return (value & AZIMUTH) > 0; } - void azimuth(bool val) { if(val) value |= AZIMUTH; else value &= ~AZIMUTH; } - bool health() const { return (value & HEALTH) > 0; } - void health(bool val) { if(val) value |= HEALTH; else value &= ~HEALTH; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t index = 0; ///< Index of this field in this epoch. uint8_t count = 0; ///< Total number of fields in this epoch. double time_of_week = 0; ///< GPS Time of week [seconds] @@ -2012,26 +1799,29 @@ struct SatelliteStatus bool health = 0; ///< True if the satellite is healthy. ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_SATELLITE_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "SatelliteStatus"; static constexpr const char* DOC_NAME = "SatelliteStatus"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(index,count,time_of_week,week_number,gnss_id,satellite_id,elevation,azimuth,health,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(gnss_id),std::ref(satellite_id),std::ref(elevation),std::ref(azimuth),std::ref(health),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const SatelliteStatus& self); -void extract(::microstrain::Serializer& serializer, SatelliteStatus& self); - ///@} /// @@ -2055,6 +1845,7 @@ struct Raw struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -2087,45 +1878,10 @@ struct Raw ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool receiverId() const { return (value & RECEIVER_ID) > 0; } - void receiverId(bool val) { if(val) value |= RECEIVER_ID; else value &= ~RECEIVER_ID; } - bool trackingChannel() const { return (value & TRACKING_CHANNEL) > 0; } - void trackingChannel(bool val) { if(val) value |= TRACKING_CHANNEL; else value &= ~TRACKING_CHANNEL; } - bool gnssId() const { return (value & GNSS_ID) > 0; } - void gnssId(bool val) { if(val) value |= GNSS_ID; else value &= ~GNSS_ID; } - bool satelliteId() const { return (value & SATELLITE_ID) > 0; } - void satelliteId(bool val) { if(val) value |= SATELLITE_ID; else value &= ~SATELLITE_ID; } - bool signalId() const { return (value & SIGNAL_ID) > 0; } - void signalId(bool val) { if(val) value |= SIGNAL_ID; else value &= ~SIGNAL_ID; } - bool signalStrength() const { return (value & SIGNAL_STRENGTH) > 0; } - void signalStrength(bool val) { if(val) value |= SIGNAL_STRENGTH; else value &= ~SIGNAL_STRENGTH; } - bool quality() const { return (value & QUALITY) > 0; } - void quality(bool val) { if(val) value |= QUALITY; else value &= ~QUALITY; } - bool pseudorange() const { return (value & PSEUDORANGE) > 0; } - void pseudorange(bool val) { if(val) value |= PSEUDORANGE; else value &= ~PSEUDORANGE; } - bool carrierPhase() const { return (value & CARRIER_PHASE) > 0; } - void carrierPhase(bool val) { if(val) value |= CARRIER_PHASE; else value &= ~CARRIER_PHASE; } - bool doppler() const { return (value & DOPPLER) > 0; } - void doppler(bool val) { if(val) value |= DOPPLER; else value &= ~DOPPLER; } - bool rangeUncertainty() const { return (value & RANGE_UNCERTAINTY) > 0; } - void rangeUncertainty(bool val) { if(val) value |= RANGE_UNCERTAINTY; else value &= ~RANGE_UNCERTAINTY; } - bool carrierPhaseUncertainty() const { return (value & CARRIER_PHASE_UNCERTAINTY) > 0; } - void carrierPhaseUncertainty(bool val) { if(val) value |= CARRIER_PHASE_UNCERTAINTY; else value &= ~CARRIER_PHASE_UNCERTAINTY; } - bool dopplerUncertainty() const { return (value & DOPPLER_UNCERTAINTY) > 0; } - void dopplerUncertainty(bool val) { if(val) value |= DOPPLER_UNCERTAINTY; else value &= ~DOPPLER_UNCERTAINTY; } - bool lockTime() const { return (value & LOCK_TIME) > 0; } - void lockTime(bool val) { if(val) value |= LOCK_TIME; else value &= ~LOCK_TIME; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t index = 0; ///< Index of this field in this epoch. uint8_t count = 0; ///< Total number of fields in this epoch. double time_of_week = 0; ///< GPS Time of week [seconds] @@ -2146,26 +1902,29 @@ struct Raw float lock_time = 0; ///< DOC Minimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver. ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_RAW; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Raw"; static constexpr const char* DOC_NAME = "Raw"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(index,count,time_of_week,week_number,receiver_id,tracking_channel,gnss_id,satellite_id,signal_id,signal_strength,quality,pseudorange,carrier_phase,doppler,range_uncert,phase_uncert,doppler_uncert,lock_time,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(receiver_id),std::ref(tracking_channel),std::ref(gnss_id),std::ref(satellite_id),std::ref(signal_id),std::ref(signal_strength),std::ref(quality),std::ref(pseudorange),std::ref(carrier_phase),std::ref(doppler),std::ref(range_uncert),std::ref(phase_uncert),std::ref(doppler_uncert),std::ref(lock_time),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const Raw& self); -void extract(::microstrain::Serializer& serializer, Raw& self); - ///@} /// @@ -2179,6 +1938,7 @@ struct GpsEphemeris { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -2197,17 +1957,10 @@ struct GpsEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool ephemeris() const { return (value & EPHEMERIS) > 0; } - void ephemeris(bool val) { if(val) value |= EPHEMERIS; else value &= ~EPHEMERIS; } - bool modernData() const { return (value & MODERN_DATA) > 0; } - void modernData(bool val) { if(val) value |= MODERN_DATA; else value &= ~MODERN_DATA; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t index = 0; ///< Index of this field in this epoch. uint8_t count = 0; ///< Total number of fields in this epoch. double time_of_week = 0; ///< GPS Time of week [seconds] @@ -2243,26 +1996,29 @@ struct GpsEphemeris double c_rs = 0; ///< Harmonic Correction Term. ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GPS_EPHEMERIS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsEphemeris"; static constexpr const char* DOC_NAME = "GpsEphemeris"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(index,count,time_of_week,week_number,satellite_id,health,iodc,iode,t_oc,af0,af1,af2,t_gd,ISC_L1CA,ISC_L2C,t_oe,a,a_dot,mean_anomaly,delta_mean_motion,delta_mean_motion_dot,eccentricity,argument_of_perigee,omega,omega_dot,inclination,inclination_dot,c_ic,c_is,c_uc,c_us,c_rc,c_rs,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(satellite_id),std::ref(health),std::ref(iodc),std::ref(iode),std::ref(t_oc),std::ref(af0),std::ref(af1),std::ref(af2),std::ref(t_gd),std::ref(ISC_L1CA),std::ref(ISC_L2C),std::ref(t_oe),std::ref(a),std::ref(a_dot),std::ref(mean_anomaly),std::ref(delta_mean_motion),std::ref(delta_mean_motion_dot),std::ref(eccentricity),std::ref(argument_of_perigee),std::ref(omega),std::ref(omega_dot),std::ref(inclination),std::ref(inclination_dot),std::ref(c_ic),std::ref(c_is),std::ref(c_uc),std::ref(c_us),std::ref(c_rc),std::ref(c_rs),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GpsEphemeris& self); -void extract(::microstrain::Serializer& serializer, GpsEphemeris& self); - ///@} /// @@ -2276,6 +2032,7 @@ struct GalileoEphemeris { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -2294,17 +2051,10 @@ struct GalileoEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool ephemeris() const { return (value & EPHEMERIS) > 0; } - void ephemeris(bool val) { if(val) value |= EPHEMERIS; else value &= ~EPHEMERIS; } - bool modernData() const { return (value & MODERN_DATA) > 0; } - void modernData(bool val) { if(val) value |= MODERN_DATA; else value &= ~MODERN_DATA; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t index = 0; ///< Index of this field in this epoch. uint8_t count = 0; ///< Total number of fields in this epoch. double time_of_week = 0; ///< GPS Time of week [seconds] @@ -2340,26 +2090,29 @@ struct GalileoEphemeris double c_rs = 0; ///< Harmonic Correction Term. ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GALILEO_EPHEMERIS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GalileoEphemeris"; static constexpr const char* DOC_NAME = "GalileoEphemeris"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(index,count,time_of_week,week_number,satellite_id,health,iodc,iode,t_oc,af0,af1,af2,t_gd,ISC_L1CA,ISC_L2C,t_oe,a,a_dot,mean_anomaly,delta_mean_motion,delta_mean_motion_dot,eccentricity,argument_of_perigee,omega,omega_dot,inclination,inclination_dot,c_ic,c_is,c_uc,c_us,c_rc,c_rs,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(satellite_id),std::ref(health),std::ref(iodc),std::ref(iode),std::ref(t_oc),std::ref(af0),std::ref(af1),std::ref(af2),std::ref(t_gd),std::ref(ISC_L1CA),std::ref(ISC_L2C),std::ref(t_oe),std::ref(a),std::ref(a_dot),std::ref(mean_anomaly),std::ref(delta_mean_motion),std::ref(delta_mean_motion_dot),std::ref(eccentricity),std::ref(argument_of_perigee),std::ref(omega),std::ref(omega_dot),std::ref(inclination),std::ref(inclination_dot),std::ref(c_ic),std::ref(c_is),std::ref(c_uc),std::ref(c_us),std::ref(c_rc),std::ref(c_rs),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GalileoEphemeris& self); -void extract(::microstrain::Serializer& serializer, GalileoEphemeris& self); - ///@} /// @@ -2373,6 +2126,7 @@ struct GloEphemeris { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -2390,15 +2144,10 @@ struct GloEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool ephemeris() const { return (value & EPHEMERIS) > 0; } - void ephemeris(bool val) { if(val) value |= EPHEMERIS; else value &= ~EPHEMERIS; } - bool flags() const { return (value & FLAGS) > 0; } - void flags(bool val) { if(val) value |= FLAGS; else value &= ~FLAGS; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint8_t index = 0; ///< Index of this field in this epoch. uint8_t count = 0; ///< Total number of fields in this epoch. double time_of_week = 0; ///< GPS Time of week [seconds] @@ -2425,26 +2174,29 @@ struct GloEphemeris uint8_t P4 = 0; ///< Flag indicating ephemeris parameters are present ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GLONASS_EPHEMERIS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GloEphemeris"; static constexpr const char* DOC_NAME = "Glonass Ephemeris"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(index,count,time_of_week,week_number,satellite_id,freq_number,tk,tb,sat_type,gamma,tau_n,x[0],x[1],x[2],v[0],v[1],v[2],a[0],a[1],a[2],health,P,NT,delta_tau_n,Ft,En,P1,P2,P3,P4,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(index),std::ref(count),std::ref(time_of_week),std::ref(week_number),std::ref(satellite_id),std::ref(freq_number),std::ref(tk),std::ref(tb),std::ref(sat_type),std::ref(gamma),std::ref(tau_n),std::ref(x[0]),std::ref(x[1]),std::ref(x[2]),std::ref(v[0]),std::ref(v[1]),std::ref(v[2]),std::ref(a[0]),std::ref(a[1]),std::ref(a[2]),std::ref(health),std::ref(P),std::ref(NT),std::ref(delta_tau_n),std::ref(Ft),std::ref(En),std::ref(P1),std::ref(P2),std::ref(P3),std::ref(P4),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GloEphemeris& self); -void extract(::microstrain::Serializer& serializer, GloEphemeris& self); - ///@} /// @@ -2458,6 +2210,7 @@ struct GpsIonoCorr { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -2478,47 +2231,39 @@ struct GpsIonoCorr ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool alpha() const { return (value & ALPHA) > 0; } - void alpha(bool val) { if(val) value |= ALPHA; else value &= ~ALPHA; } - bool beta() const { return (value & BETA) > 0; } - void beta(bool val) { if(val) value |= BETA; else value &= ~BETA; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double time_of_week = 0; ///< GPS Time of week [seconds] uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] double alpha[4] = {0}; ///< Ionospheric Correction Terms. double beta[4] = {0}; ///< Ionospheric Correction Terms. ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GPS_IONO_CORR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsIonoCorr"; static constexpr const char* DOC_NAME = "GPS Ionospheric Correction"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_of_week,week_number,alpha,beta,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(alpha),std::ref(beta),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GpsIonoCorr& self); -void extract(::microstrain::Serializer& serializer, GpsIonoCorr& self); - ///@} /// @@ -2532,6 +2277,7 @@ struct GalileoIonoCorr { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -2552,47 +2298,39 @@ struct GalileoIonoCorr ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool alpha() const { return (value & ALPHA) > 0; } - void alpha(bool val) { if(val) value |= ALPHA; else value &= ~ALPHA; } - bool disturbanceFlags() const { return (value & DISTURBANCE_FLAGS) > 0; } - void disturbanceFlags(bool val) { if(val) value |= DISTURBANCE_FLAGS; else value &= ~DISTURBANCE_FLAGS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double time_of_week = 0; ///< GPS Time of week [seconds] uint16_t week_number = 0; ///< GPS Week since 1980 [weeks] Vector3d alpha; ///< Coefficients for the model. uint8_t disturbance_flags = 0; ///< Region disturbance flags (bits 1-5). ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_gnss::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GALILEO_IONO_CORR; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GalileoIonoCorr"; static constexpr const char* DOC_NAME = "Galileo Ionospheric Correction"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_of_week,week_number,alpha[0],alpha[1],alpha[2],disturbance_flags,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_of_week),std::ref(week_number),std::ref(alpha[0]),std::ref(alpha[1]),std::ref(alpha[2]),std::ref(disturbance_flags),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GalileoIonoCorr& self); -void extract(::microstrain::Serializer& serializer, GalileoIonoCorr& self); - ///@} /// diff --git a/src/cpp/mip/definitions/data_sensor.cpp b/src/cpp/mip/definitions/data_sensor.cpp index 883c7629d..0ebb058b1 100644 --- a/src/cpp/mip/definitions/data_sensor.cpp +++ b/src/cpp/mip/definitions/data_sensor.cpp @@ -1,348 +1,313 @@ #include "data_sensor.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace data_sensor { -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const RawAccel& self) +void RawAccel::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.raw_accel[i]); + serializer.insert(raw_accel); } -void extract(::microstrain::Serializer& serializer, RawAccel& self) +void RawAccel::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.raw_accel[i]); + serializer.extract(raw_accel); } -void insert(::microstrain::Serializer& serializer, const RawGyro& self) +void RawGyro::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.raw_gyro[i]); + serializer.insert(raw_gyro); } -void extract(::microstrain::Serializer& serializer, RawGyro& self) +void RawGyro::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.raw_gyro[i]); + serializer.extract(raw_gyro); } -void insert(::microstrain::Serializer& serializer, const RawMag& self) +void RawMag::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.raw_mag[i]); + serializer.insert(raw_mag); } -void extract(::microstrain::Serializer& serializer, RawMag& self) +void RawMag::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.raw_mag[i]); + serializer.extract(raw_mag); } -void insert(::microstrain::Serializer& serializer, const RawPressure& self) +void RawPressure::insert(Serializer& serializer) const { - insert(serializer, self.raw_pressure); + serializer.insert(raw_pressure); } -void extract(::microstrain::Serializer& serializer, RawPressure& self) +void RawPressure::extract(Serializer& serializer) { - extract(serializer, self.raw_pressure); + serializer.extract(raw_pressure); } -void insert(::microstrain::Serializer& serializer, const ScaledAccel& self) +void ScaledAccel::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.scaled_accel[i]); + serializer.insert(scaled_accel); } -void extract(::microstrain::Serializer& serializer, ScaledAccel& self) +void ScaledAccel::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.scaled_accel[i]); + serializer.extract(scaled_accel); } -void insert(::microstrain::Serializer& serializer, const ScaledGyro& self) +void ScaledGyro::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.scaled_gyro[i]); + serializer.insert(scaled_gyro); } -void extract(::microstrain::Serializer& serializer, ScaledGyro& self) +void ScaledGyro::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.scaled_gyro[i]); + serializer.extract(scaled_gyro); } -void insert(::microstrain::Serializer& serializer, const ScaledMag& self) +void ScaledMag::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.scaled_mag[i]); + serializer.insert(scaled_mag); } -void extract(::microstrain::Serializer& serializer, ScaledMag& self) +void ScaledMag::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.scaled_mag[i]); + serializer.extract(scaled_mag); } -void insert(::microstrain::Serializer& serializer, const ScaledPressure& self) +void ScaledPressure::insert(Serializer& serializer) const { - insert(serializer, self.scaled_pressure); + serializer.insert(scaled_pressure); } -void extract(::microstrain::Serializer& serializer, ScaledPressure& self) +void ScaledPressure::extract(Serializer& serializer) { - extract(serializer, self.scaled_pressure); + serializer.extract(scaled_pressure); } -void insert(::microstrain::Serializer& serializer, const DeltaTheta& self) +void DeltaTheta::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.delta_theta[i]); + serializer.insert(delta_theta); } -void extract(::microstrain::Serializer& serializer, DeltaTheta& self) +void DeltaTheta::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.delta_theta[i]); + serializer.extract(delta_theta); } -void insert(::microstrain::Serializer& serializer, const DeltaVelocity& self) +void DeltaVelocity::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.delta_velocity[i]); + serializer.insert(delta_velocity); } -void extract(::microstrain::Serializer& serializer, DeltaVelocity& self) +void DeltaVelocity::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.delta_velocity[i]); + serializer.extract(delta_velocity); } -void insert(::microstrain::Serializer& serializer, const CompOrientationMatrix& self) +void CompOrientationMatrix::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.m[i]); + serializer.insert(m); } -void extract(::microstrain::Serializer& serializer, CompOrientationMatrix& self) +void CompOrientationMatrix::extract(Serializer& serializer) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.m[i]); + serializer.extract(m); } -void insert(::microstrain::Serializer& serializer, const CompQuaternion& self) +void CompQuaternion::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 4; i++) - insert(serializer, self.q[i]); + serializer.insert(q); } -void extract(::microstrain::Serializer& serializer, CompQuaternion& self) +void CompQuaternion::extract(Serializer& serializer) { - for(unsigned int i=0; i < 4; i++) - extract(serializer, self.q[i]); + serializer.extract(q); } -void insert(::microstrain::Serializer& serializer, const CompEulerAngles& self) +void CompEulerAngles::insert(Serializer& serializer) const { - insert(serializer, self.roll); + serializer.insert(roll); - insert(serializer, self.pitch); + serializer.insert(pitch); - insert(serializer, self.yaw); + serializer.insert(yaw); } -void extract(::microstrain::Serializer& serializer, CompEulerAngles& self) +void CompEulerAngles::extract(Serializer& serializer) { - extract(serializer, self.roll); + serializer.extract(roll); - extract(serializer, self.pitch); + serializer.extract(pitch); - extract(serializer, self.yaw); + serializer.extract(yaw); } -void insert(::microstrain::Serializer& serializer, const CompOrientationUpdateMatrix& self) +void CompOrientationUpdateMatrix::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 9; i++) - insert(serializer, self.m[i]); + serializer.insert(m); } -void extract(::microstrain::Serializer& serializer, CompOrientationUpdateMatrix& self) +void CompOrientationUpdateMatrix::extract(Serializer& serializer) { - for(unsigned int i=0; i < 9; i++) - extract(serializer, self.m[i]); + serializer.extract(m); } -void insert(::microstrain::Serializer& serializer, const OrientationRawTemp& self) +void OrientationRawTemp::insert(Serializer& serializer) const { for(unsigned int i=0; i < 4; i++) - insert(serializer, self.raw_temp[i]); + serializer.insert(raw_temp[i]); } -void extract(::microstrain::Serializer& serializer, OrientationRawTemp& self) +void OrientationRawTemp::extract(Serializer& serializer) { for(unsigned int i=0; i < 4; i++) - extract(serializer, self.raw_temp[i]); + serializer.extract(raw_temp[i]); } -void insert(::microstrain::Serializer& serializer, const InternalTimestamp& self) +void InternalTimestamp::insert(Serializer& serializer) const { - insert(serializer, self.counts); + serializer.insert(counts); } -void extract(::microstrain::Serializer& serializer, InternalTimestamp& self) +void InternalTimestamp::extract(Serializer& serializer) { - extract(serializer, self.counts); + serializer.extract(counts); } -void insert(::microstrain::Serializer& serializer, const PpsTimestamp& self) +void PpsTimestamp::insert(Serializer& serializer) const { - insert(serializer, self.seconds); + serializer.insert(seconds); - insert(serializer, self.useconds); + serializer.insert(useconds); } -void extract(::microstrain::Serializer& serializer, PpsTimestamp& self) +void PpsTimestamp::extract(Serializer& serializer) { - extract(serializer, self.seconds); + serializer.extract(seconds); - extract(serializer, self.useconds); + serializer.extract(useconds); } -void insert(::microstrain::Serializer& serializer, const GpsTimestamp& self) +void GpsTimestamp::insert(Serializer& serializer) const { - insert(serializer, self.tow); + serializer.insert(tow); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GpsTimestamp& self) +void GpsTimestamp::extract(Serializer& serializer) { - extract(serializer, self.tow); + serializer.extract(tow); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const TemperatureAbs& self) +void TemperatureAbs::insert(Serializer& serializer) const { - insert(serializer, self.min_temp); + serializer.insert(min_temp); - insert(serializer, self.max_temp); + serializer.insert(max_temp); - insert(serializer, self.mean_temp); + serializer.insert(mean_temp); } -void extract(::microstrain::Serializer& serializer, TemperatureAbs& self) +void TemperatureAbs::extract(Serializer& serializer) { - extract(serializer, self.min_temp); + serializer.extract(min_temp); - extract(serializer, self.max_temp); + serializer.extract(max_temp); - extract(serializer, self.mean_temp); + serializer.extract(mean_temp); } -void insert(::microstrain::Serializer& serializer, const UpVector& self) +void UpVector::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.up[i]); + serializer.insert(up); } -void extract(::microstrain::Serializer& serializer, UpVector& self) +void UpVector::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.up[i]); + serializer.extract(up); } -void insert(::microstrain::Serializer& serializer, const NorthVector& self) +void NorthVector::insert(Serializer& serializer) const { - for(unsigned int i=0; i < 3; i++) - insert(serializer, self.north[i]); + serializer.insert(north); } -void extract(::microstrain::Serializer& serializer, NorthVector& self) +void NorthVector::extract(Serializer& serializer) { - for(unsigned int i=0; i < 3; i++) - extract(serializer, self.north[i]); + serializer.extract(north); } -void insert(::microstrain::Serializer& serializer, const OverrangeStatus& self) +void OverrangeStatus::insert(Serializer& serializer) const { - insert(serializer, self.status); + serializer.insert(status); } -void extract(::microstrain::Serializer& serializer, OverrangeStatus& self) +void OverrangeStatus::extract(Serializer& serializer) { - extract(serializer, self.status); + serializer.extract(status); } -void insert(::microstrain::Serializer& serializer, const OdometerData& self) +void OdometerData::insert(Serializer& serializer) const { - insert(serializer, self.speed); + serializer.insert(speed); - insert(serializer, self.uncertainty); + serializer.insert(uncertainty); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, OdometerData& self) +void OdometerData::extract(Serializer& serializer) { - extract(serializer, self.speed); + serializer.extract(speed); - extract(serializer, self.uncertainty); + serializer.extract(uncertainty); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } diff --git a/src/cpp/mip/definitions/data_sensor.hpp b/src/cpp/mip/definitions/data_sensor.hpp index 443b6fdff..be7f62301 100644 --- a/src/cpp/mip/definitions/data_sensor.hpp +++ b/src/cpp/mip/definitions/data_sensor.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -79,28 +77,32 @@ enum struct RawAccel { + /// Parameters Vector3f raw_accel; ///< Native sensor counts + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_ACCEL_RAW; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RawAccel"; static constexpr const char* DOC_NAME = "RawAccel"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(raw_accel[0],raw_accel[1],raw_accel[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(raw_accel[0]),std::ref(raw_accel[1]),std::ref(raw_accel[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const RawAccel& self); -void extract(::microstrain::Serializer& serializer, RawAccel& self); - ///@} /// @@ -113,28 +115,32 @@ void extract(::microstrain::Serializer& serializer, RawAccel& self); struct RawGyro { + /// Parameters Vector3f raw_gyro; ///< Native sensor counts + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_GYRO_RAW; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RawGyro"; static constexpr const char* DOC_NAME = "RawGyro"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(raw_gyro[0],raw_gyro[1],raw_gyro[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(raw_gyro[0]),std::ref(raw_gyro[1]),std::ref(raw_gyro[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const RawGyro& self); -void extract(::microstrain::Serializer& serializer, RawGyro& self); - ///@} /// @@ -147,28 +153,32 @@ void extract(::microstrain::Serializer& serializer, RawGyro& self); struct RawMag { + /// Parameters Vector3f raw_mag; ///< Native sensor counts + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_MAG_RAW; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RawMag"; static constexpr const char* DOC_NAME = "RawMag"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(raw_mag[0],raw_mag[1],raw_mag[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(raw_mag[0]),std::ref(raw_mag[1]),std::ref(raw_mag[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const RawMag& self); -void extract(::microstrain::Serializer& serializer, RawMag& self); - ///@} /// @@ -181,28 +191,32 @@ void extract(::microstrain::Serializer& serializer, RawMag& self); struct RawPressure { + /// Parameters float raw_pressure = 0; ///< Native sensor counts + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_PRESSURE_RAW; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "RawPressure"; static constexpr const char* DOC_NAME = "RawPressure"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(raw_pressure); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(raw_pressure)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const RawPressure& self); -void extract(::microstrain::Serializer& serializer, RawPressure& self); - ///@} /// @@ -215,28 +229,32 @@ void extract(::microstrain::Serializer& serializer, RawPressure& self); struct ScaledAccel { + /// Parameters Vector3f scaled_accel; ///< (x, y, z)[g] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_ACCEL_SCALED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ScaledAccel"; static constexpr const char* DOC_NAME = "ScaledAccel"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scaled_accel[0],scaled_accel[1],scaled_accel[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scaled_accel[0]),std::ref(scaled_accel[1]),std::ref(scaled_accel[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ScaledAccel& self); -void extract(::microstrain::Serializer& serializer, ScaledAccel& self); - ///@} /// @@ -249,28 +267,32 @@ void extract(::microstrain::Serializer& serializer, ScaledAccel& self); struct ScaledGyro { + /// Parameters Vector3f scaled_gyro; ///< (x, y, z) [radians/second] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_GYRO_SCALED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ScaledGyro"; static constexpr const char* DOC_NAME = "ScaledGyro"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scaled_gyro[0],scaled_gyro[1],scaled_gyro[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scaled_gyro[0]),std::ref(scaled_gyro[1]),std::ref(scaled_gyro[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ScaledGyro& self); -void extract(::microstrain::Serializer& serializer, ScaledGyro& self); - ///@} /// @@ -283,28 +305,32 @@ void extract(::microstrain::Serializer& serializer, ScaledGyro& self); struct ScaledMag { + /// Parameters Vector3f scaled_mag; ///< (x, y, z) [Gauss] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_MAG_SCALED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ScaledMag"; static constexpr const char* DOC_NAME = "ScaledMag"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scaled_mag[0],scaled_mag[1],scaled_mag[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scaled_mag[0]),std::ref(scaled_mag[1]),std::ref(scaled_mag[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ScaledMag& self); -void extract(::microstrain::Serializer& serializer, ScaledMag& self); - ///@} /// @@ -316,28 +342,32 @@ void extract(::microstrain::Serializer& serializer, ScaledMag& self); struct ScaledPressure { + /// Parameters float scaled_pressure = 0; ///< [mBar] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_PRESSURE_SCALED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ScaledPressure"; static constexpr const char* DOC_NAME = "ScaledPressure"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(scaled_pressure); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(scaled_pressure)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ScaledPressure& self); -void extract(::microstrain::Serializer& serializer, ScaledPressure& self); - ///@} /// @@ -350,28 +380,32 @@ void extract(::microstrain::Serializer& serializer, ScaledPressure& self); struct DeltaTheta { + /// Parameters Vector3f delta_theta; ///< (x, y, z) [radians] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_DELTA_THETA; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DeltaTheta"; static constexpr const char* DOC_NAME = "DeltaTheta"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(delta_theta[0],delta_theta[1],delta_theta[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(delta_theta[0]),std::ref(delta_theta[1]),std::ref(delta_theta[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const DeltaTheta& self); -void extract(::microstrain::Serializer& serializer, DeltaTheta& self); - ///@} /// @@ -384,28 +418,32 @@ void extract(::microstrain::Serializer& serializer, DeltaTheta& self); struct DeltaVelocity { + /// Parameters Vector3f delta_velocity; ///< (x, y, z) [g*sec] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_DELTA_VELOCITY; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DeltaVelocity"; static constexpr const char* DOC_NAME = "DeltaVelocity"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(delta_velocity[0],delta_velocity[1],delta_velocity[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(delta_velocity[0]),std::ref(delta_velocity[1]),std::ref(delta_velocity[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const DeltaVelocity& self); -void extract(::microstrain::Serializer& serializer, DeltaVelocity& self); - ///@} /// @@ -427,28 +465,32 @@ void extract(::microstrain::Serializer& serializer, DeltaVelocity& self); struct CompOrientationMatrix { + /// Parameters Matrix3f m; ///< Matrix elements in row-major order. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_COMP_ORIENTATION_MATRIX; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CompOrientationMatrix"; static constexpr const char* DOC_NAME = "Complementary Filter Orientation Matrix"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(m[0],m[1],m[2],m[3],m[4],m[5],m[6],m[7],m[8]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(m[0]),std::ref(m[1]),std::ref(m[2]),std::ref(m[3]),std::ref(m[4]),std::ref(m[5]),std::ref(m[6]),std::ref(m[7]),std::ref(m[8])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const CompOrientationMatrix& self); -void extract(::microstrain::Serializer& serializer, CompOrientationMatrix& self); - ///@} /// @@ -468,28 +510,32 @@ void extract(::microstrain::Serializer& serializer, CompOrientationMatrix& self) struct CompQuaternion { + /// Parameters Quatf q; ///< Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_COMP_QUATERNION; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CompQuaternion"; static constexpr const char* DOC_NAME = "Complementary Filter Quaternion"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(q[0],q[1],q[2],q[3]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(q[0]),std::ref(q[1]),std::ref(q[2]),std::ref(q[3])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const CompQuaternion& self); -void extract(::microstrain::Serializer& serializer, CompQuaternion& self); - ///@} /// @@ -502,30 +548,34 @@ void extract(::microstrain::Serializer& serializer, CompQuaternion& self); struct CompEulerAngles { + /// Parameters float roll = 0; ///< [radians] float pitch = 0; ///< [radians] float yaw = 0; ///< [radians] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_COMP_EULER_ANGLES; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CompEulerAngles"; static constexpr const char* DOC_NAME = "Complementary Filter Euler Angles"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(roll,pitch,yaw); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(roll),std::ref(pitch),std::ref(yaw)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const CompEulerAngles& self); -void extract(::microstrain::Serializer& serializer, CompEulerAngles& self); - ///@} /// @@ -537,28 +587,32 @@ void extract(::microstrain::Serializer& serializer, CompEulerAngles& self); struct CompOrientationUpdateMatrix { + /// Parameters Matrix3f m; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_COMP_ORIENTATION_UPDATE_MATRIX; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "CompOrientationUpdateMatrix"; static constexpr const char* DOC_NAME = "Complementary Filter Orientation Update Matrix"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(m[0],m[1],m[2],m[3],m[4],m[5],m[6],m[7],m[8]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(m[0]),std::ref(m[1]),std::ref(m[2]),std::ref(m[3]),std::ref(m[4]),std::ref(m[5]),std::ref(m[6]),std::ref(m[7]),std::ref(m[8])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const CompOrientationUpdateMatrix& self); -void extract(::microstrain::Serializer& serializer, CompOrientationUpdateMatrix& self); - ///@} /// @@ -570,28 +624,32 @@ void extract(::microstrain::Serializer& serializer, CompOrientationUpdateMatrix& struct OrientationRawTemp { + /// Parameters uint16_t raw_temp[4] = {0}; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TEMPERATURE_RAW; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "OrientationRawTemp"; static constexpr const char* DOC_NAME = "OrientationRawTemp"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(raw_temp); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(raw_temp)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const OrientationRawTemp& self); -void extract(::microstrain::Serializer& serializer, OrientationRawTemp& self); - ///@} /// @@ -603,28 +661,32 @@ void extract(::microstrain::Serializer& serializer, OrientationRawTemp& self); struct InternalTimestamp { + /// Parameters uint32_t counts = 0; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TIME_STAMP_INTERNAL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "InternalTimestamp"; static constexpr const char* DOC_NAME = "InternalTimestamp"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(counts); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(counts)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const InternalTimestamp& self); -void extract(::microstrain::Serializer& serializer, InternalTimestamp& self); - ///@} /// @@ -636,29 +698,33 @@ void extract(::microstrain::Serializer& serializer, InternalTimestamp& self); struct PpsTimestamp { + /// Parameters uint32_t seconds = 0; uint32_t useconds = 0; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TIME_STAMP_PPS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "PpsTimestamp"; static constexpr const char* DOC_NAME = "PPS Timestamp"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(seconds,useconds); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(seconds),std::ref(useconds)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const PpsTimestamp& self); -void extract(::microstrain::Serializer& serializer, PpsTimestamp& self); - ///@} /// @@ -678,6 +744,7 @@ struct GpsTimestamp { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -698,45 +765,37 @@ struct GpsTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool ppsValid() const { return (value & PPS_VALID) > 0; } - void ppsValid(bool val) { if(val) value |= PPS_VALID; else value &= ~PPS_VALID; } - bool timeRefresh() const { return (value & TIME_REFRESH) > 0; } - void timeRefresh(bool val) { if(val) value |= TIME_REFRESH; else value &= ~TIME_REFRESH; } - bool timeInitialized() const { return (value & TIME_INITIALIZED) > 0; } - void timeInitialized(bool val) { if(val) value |= TIME_INITIALIZED; else value &= ~TIME_INITIALIZED; } - bool towValid() const { return (value & TOW_VALID) > 0; } - void towValid(bool val) { if(val) value |= TOW_VALID; else value &= ~TOW_VALID; } - bool weekNumberValid() const { return (value & WEEK_NUMBER_VALID) > 0; } - void weekNumberValid(bool val) { if(val) value |= WEEK_NUMBER_VALID; else value &= ~WEEK_NUMBER_VALID; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double tow = 0; ///< GPS Time of Week [seconds] uint16_t week_number = 0; ///< GPS Week Number since 1980 [weeks] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TIME_STAMP_GPS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsTimestamp"; static constexpr const char* DOC_NAME = "GpsTimestamp"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(tow,week_number,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GpsTimestamp& self); -void extract(::microstrain::Serializer& serializer, GpsTimestamp& self); - ///@} /// @@ -752,30 +811,34 @@ void extract(::microstrain::Serializer& serializer, GpsTimestamp& self); struct TemperatureAbs { + /// Parameters float min_temp = 0; ///< [degC] float max_temp = 0; ///< [degC] float mean_temp = 0; ///< [degC] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_TEMPERATURE_ABS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "TemperatureAbs"; static constexpr const char* DOC_NAME = "Temperature Statistics"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(min_temp,max_temp,mean_temp); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(min_temp),std::ref(max_temp),std::ref(mean_temp)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const TemperatureAbs& self); -void extract(::microstrain::Serializer& serializer, TemperatureAbs& self); - ///@} /// @@ -793,28 +856,32 @@ void extract(::microstrain::Serializer& serializer, TemperatureAbs& self); struct UpVector { + /// Parameters Vector3f up; ///< [Gs] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_STAB_ACCEL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "UpVector"; static constexpr const char* DOC_NAME = "UpVector"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(up[0],up[1],up[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(up[0]),std::ref(up[1]),std::ref(up[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const UpVector& self); -void extract(::microstrain::Serializer& serializer, UpVector& self); - ///@} /// @@ -829,28 +896,32 @@ void extract(::microstrain::Serializer& serializer, UpVector& self); struct NorthVector { + /// Parameters Vector3f north; ///< [Gauss] + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_STAB_MAG; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "NorthVector"; static constexpr const char* DOC_NAME = "NorthVector"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(north[0],north[1],north[2]); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(north[0]),std::ref(north[1]),std::ref(north[2])); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const NorthVector& self); -void extract(::microstrain::Serializer& serializer, NorthVector& self); - ///@} /// @@ -863,6 +934,7 @@ struct OverrangeStatus { struct Status : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -888,53 +960,35 @@ struct OverrangeStatus Status& operator|=(uint16_t val) { return *this = value | val; } Status& operator&=(uint16_t val) { return *this = value & val; } - bool accelX() const { return (value & ACCEL_X) > 0; } - void accelX(bool val) { if(val) value |= ACCEL_X; else value &= ~ACCEL_X; } - bool accelY() const { return (value & ACCEL_Y) > 0; } - void accelY(bool val) { if(val) value |= ACCEL_Y; else value &= ~ACCEL_Y; } - bool accelZ() const { return (value & ACCEL_Z) > 0; } - void accelZ(bool val) { if(val) value |= ACCEL_Z; else value &= ~ACCEL_Z; } - bool gyroX() const { return (value & GYRO_X) > 0; } - void gyroX(bool val) { if(val) value |= GYRO_X; else value &= ~GYRO_X; } - bool gyroY() const { return (value & GYRO_Y) > 0; } - void gyroY(bool val) { if(val) value |= GYRO_Y; else value &= ~GYRO_Y; } - bool gyroZ() const { return (value & GYRO_Z) > 0; } - void gyroZ(bool val) { if(val) value |= GYRO_Z; else value &= ~GYRO_Z; } - bool magX() const { return (value & MAG_X) > 0; } - void magX(bool val) { if(val) value |= MAG_X; else value &= ~MAG_X; } - bool magY() const { return (value & MAG_Y) > 0; } - void magY(bool val) { if(val) value |= MAG_Y; else value &= ~MAG_Y; } - bool magZ() const { return (value & MAG_Z) > 0; } - void magZ(bool val) { if(val) value |= MAG_Z; else value &= ~MAG_Z; } - bool press() const { return (value & PRESS) > 0; } - void press(bool val) { if(val) value |= PRESS; else value &= ~PRESS; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters Status status; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_OVERRANGE_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "OverrangeStatus"; static constexpr const char* DOC_NAME = "OverrangeStatus"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(status); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(status)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const OverrangeStatus& self); -void extract(::microstrain::Serializer& serializer, OverrangeStatus& self); - ///@} /// @@ -945,30 +999,34 @@ void extract(::microstrain::Serializer& serializer, OverrangeStatus& self); struct OdometerData { + /// Parameters float speed = 0; ///< Average speed over the time interval [m/s]. Can be negative for quadrature encoders. float uncertainty = 0; ///< Uncertainty of velocity [m/s]. uint16_t valid_flags = 0; ///< If odometer is configured, bit 0 will be set to 1. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_sensor::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_sensor::DATA_ODOMETER; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "OdometerData"; static constexpr const char* DOC_NAME = "OdometerData"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(speed,uncertainty,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(speed),std::ref(uncertainty),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const OdometerData& self); -void extract(::microstrain::Serializer& serializer, OdometerData& self); - ///@} /// diff --git a/src/cpp/mip/definitions/data_shared.cpp b/src/cpp/mip/definitions/data_shared.cpp index 7872b60ab..f1661e76e 100644 --- a/src/cpp/mip/definitions/data_shared.cpp +++ b/src/cpp/mip/definitions/data_shared.cpp @@ -1,146 +1,137 @@ #include "data_shared.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace data_shared { -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const EventSource& self) +void EventSource::insert(Serializer& serializer) const { - insert(serializer, self.trigger_id); + serializer.insert(trigger_id); } -void extract(::microstrain::Serializer& serializer, EventSource& self) +void EventSource::extract(Serializer& serializer) { - extract(serializer, self.trigger_id); + serializer.extract(trigger_id); } -void insert(::microstrain::Serializer& serializer, const Ticks& self) +void Ticks::insert(Serializer& serializer) const { - insert(serializer, self.ticks); + serializer.insert(ticks); } -void extract(::microstrain::Serializer& serializer, Ticks& self) +void Ticks::extract(Serializer& serializer) { - extract(serializer, self.ticks); + serializer.extract(ticks); } -void insert(::microstrain::Serializer& serializer, const DeltaTicks& self) +void DeltaTicks::insert(Serializer& serializer) const { - insert(serializer, self.ticks); + serializer.insert(ticks); } -void extract(::microstrain::Serializer& serializer, DeltaTicks& self) +void DeltaTicks::extract(Serializer& serializer) { - extract(serializer, self.ticks); + serializer.extract(ticks); } -void insert(::microstrain::Serializer& serializer, const GpsTimestamp& self) +void GpsTimestamp::insert(Serializer& serializer) const { - insert(serializer, self.tow); + serializer.insert(tow); - insert(serializer, self.week_number); + serializer.insert(week_number); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, GpsTimestamp& self) +void GpsTimestamp::extract(Serializer& serializer) { - extract(serializer, self.tow); + serializer.extract(tow); - extract(serializer, self.week_number); + serializer.extract(week_number); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const DeltaTime& self) +void DeltaTime::insert(Serializer& serializer) const { - insert(serializer, self.seconds); + serializer.insert(seconds); } -void extract(::microstrain::Serializer& serializer, DeltaTime& self) +void DeltaTime::extract(Serializer& serializer) { - extract(serializer, self.seconds); + serializer.extract(seconds); } -void insert(::microstrain::Serializer& serializer, const ReferenceTimestamp& self) +void ReferenceTimestamp::insert(Serializer& serializer) const { - insert(serializer, self.nanoseconds); + serializer.insert(nanoseconds); } -void extract(::microstrain::Serializer& serializer, ReferenceTimestamp& self) +void ReferenceTimestamp::extract(Serializer& serializer) { - extract(serializer, self.nanoseconds); + serializer.extract(nanoseconds); } -void insert(::microstrain::Serializer& serializer, const ReferenceTimeDelta& self) +void ReferenceTimeDelta::insert(Serializer& serializer) const { - insert(serializer, self.dt_nanos); + serializer.insert(dt_nanos); } -void extract(::microstrain::Serializer& serializer, ReferenceTimeDelta& self) +void ReferenceTimeDelta::extract(Serializer& serializer) { - extract(serializer, self.dt_nanos); + serializer.extract(dt_nanos); } -void insert(::microstrain::Serializer& serializer, const ExternalTimestamp& self) +void ExternalTimestamp::insert(Serializer& serializer) const { - insert(serializer, self.nanoseconds); + serializer.insert(nanoseconds); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, ExternalTimestamp& self) +void ExternalTimestamp::extract(Serializer& serializer) { - extract(serializer, self.nanoseconds); + serializer.extract(nanoseconds); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } -void insert(::microstrain::Serializer& serializer, const ExternalTimeDelta& self) +void ExternalTimeDelta::insert(Serializer& serializer) const { - insert(serializer, self.dt_nanos); + serializer.insert(dt_nanos); - insert(serializer, self.valid_flags); + serializer.insert(valid_flags); } -void extract(::microstrain::Serializer& serializer, ExternalTimeDelta& self) +void ExternalTimeDelta::extract(Serializer& serializer) { - extract(serializer, self.dt_nanos); + serializer.extract(dt_nanos); - extract(serializer, self.valid_flags); + serializer.extract(valid_flags); } diff --git a/src/cpp/mip/definitions/data_shared.hpp b/src/cpp/mip/definitions/data_shared.hpp index 42193fd55..c7cc64d22 100644 --- a/src/cpp/mip/definitions/data_shared.hpp +++ b/src/cpp/mip/definitions/data_shared.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -66,28 +64,32 @@ static constexpr const uint8_t MIP_DATA_DESC_SHARED_START = 0xD0; struct EventSource { + /// Parameters uint8_t trigger_id = 0; ///< Trigger ID number. If 0, this message was emitted due to being scheduled in the 3DM Message Format Command (0x0C,0x0F). + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_EVENT_SOURCE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "EventSource"; static constexpr const char* DOC_NAME = "EventSource"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(trigger_id); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(trigger_id)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const EventSource& self); -void extract(::microstrain::Serializer& serializer, EventSource& self); - ///@} /// @@ -102,28 +104,32 @@ void extract(::microstrain::Serializer& serializer, EventSource& self); struct Ticks { + /// Parameters uint32_t ticks = 0; ///< Ticks since powerup. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_TICKS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "Ticks"; static constexpr const char* DOC_NAME = "Ticks"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(ticks); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(ticks)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const Ticks& self); -void extract(::microstrain::Serializer& serializer, Ticks& self); - ///@} /// @@ -139,28 +145,32 @@ void extract(::microstrain::Serializer& serializer, Ticks& self); struct DeltaTicks { + /// Parameters uint32_t ticks = 0; ///< Ticks since last output. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_DELTA_TICKS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DeltaTicks"; static constexpr const char* DOC_NAME = "DeltaTicks"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(ticks); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(ticks)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const DeltaTicks& self); -void extract(::microstrain::Serializer& serializer, DeltaTicks& self); - ///@} /// @@ -177,6 +187,7 @@ struct GpsTimestamp { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -195,41 +206,37 @@ struct GpsTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - uint16_t timeValid() const { return (value & TIME_VALID) >> 0; } - void timeValid(uint16_t val) { value = (value & ~TIME_VALID) | (val << 0); } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters double tow = 0; ///< GPS Time of Week [seconds] uint16_t week_number = 0; ///< GPS Week Number since 1980 [weeks] ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_GPS_TIME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsTimestamp"; static constexpr const char* DOC_NAME = "GpsTimestamp"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(tow,week_number,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(tow),std::ref(week_number),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GpsTimestamp& self); -void extract(::microstrain::Serializer& serializer, GpsTimestamp& self); - ///@} /// @@ -250,28 +257,32 @@ void extract(::microstrain::Serializer& serializer, GpsTimestamp& self); struct DeltaTime { + /// Parameters double seconds = 0; ///< Seconds since last output. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_DELTA_TIME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "DeltaTime"; static constexpr const char* DOC_NAME = "DeltaTime"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(seconds); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(seconds)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const DeltaTime& self); -void extract(::microstrain::Serializer& serializer, DeltaTime& self); - ///@} /// @@ -290,28 +301,32 @@ void extract(::microstrain::Serializer& serializer, DeltaTime& self); struct ReferenceTimestamp { + /// Parameters uint64_t nanoseconds = 0; ///< Nanoseconds since initialization. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_REFERENCE_TIME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ReferenceTimestamp"; static constexpr const char* DOC_NAME = "ReferenceTimestamp"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(nanoseconds); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(nanoseconds)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ReferenceTimestamp& self); -void extract(::microstrain::Serializer& serializer, ReferenceTimestamp& self); - ///@} /// @@ -332,28 +347,32 @@ void extract(::microstrain::Serializer& serializer, ReferenceTimestamp& self); struct ReferenceTimeDelta { + /// Parameters uint64_t dt_nanos = 0; ///< Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_REF_TIME_DELTA; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ReferenceTimeDelta"; static constexpr const char* DOC_NAME = "ReferenceTimeDelta"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(dt_nanos); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(dt_nanos)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ReferenceTimeDelta& self); -void extract(::microstrain::Serializer& serializer, ReferenceTimeDelta& self); - ///@} /// @@ -375,6 +394,7 @@ struct ExternalTimestamp { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -391,36 +411,36 @@ struct ExternalTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool nanoseconds() const { return (value & NANOSECONDS) > 0; } - void nanoseconds(bool val) { if(val) value |= NANOSECONDS; else value &= ~NANOSECONDS; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint64_t nanoseconds = 0; ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_EXTERNAL_TIME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ExternalTimestamp"; static constexpr const char* DOC_NAME = "ExternalTimestamp"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(nanoseconds,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(nanoseconds),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ExternalTimestamp& self); -void extract(::microstrain::Serializer& serializer, ExternalTimestamp& self); - ///@} /// @@ -446,6 +466,7 @@ struct ExternalTimeDelta { struct ValidFlags : Bitfield { + typedef uint16_t Type; enum _enumType : uint16_t { NONE = 0x0000, @@ -462,36 +483,36 @@ struct ExternalTimeDelta ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool dtNanos() const { return (value & DT_NANOS) > 0; } - void dtNanos(bool val) { if(val) value |= DT_NANOS; else value &= ~DT_NANOS; } - bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; - + /// Parameters uint64_t dt_nanos = 0; ///< Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source. ValidFlags valid_flags; + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_shared::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_shared::DATA_SYS_TIME_DELTA; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "ExternalTimeDelta"; static constexpr const char* DOC_NAME = "ExternalTimeDelta"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(dt_nanos,valid_flags); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(dt_nanos),std::ref(valid_flags)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const ExternalTimeDelta& self); -void extract(::microstrain::Serializer& serializer, ExternalTimeDelta& self); - ///@} /// diff --git a/src/cpp/mip/definitions/data_system.cpp b/src/cpp/mip/definitions/data_system.cpp index a6c339eba..c11c1f4b3 100644 --- a/src/cpp/mip/definitions/data_system.cpp +++ b/src/cpp/mip/definitions/data_system.cpp @@ -1,85 +1,76 @@ #include "data_system.hpp" -#include "microstrain/common/serialization.hpp" -#include "../mip_interface.hpp" +#include +#include #include namespace mip { -; - namespace C { struct mip_interface; } // namespace C namespace data_system { -using ::mip::insert; -using ::mip::extract; using namespace ::mip::C; -//////////////////////////////////////////////////////////////////////////////// -// Shared Type Definitions -//////////////////////////////////////////////////////////////////////////////// - - //////////////////////////////////////////////////////////////////////////////// // Mip Fields //////////////////////////////////////////////////////////////////////////////// -void insert(::microstrain::Serializer& serializer, const BuiltInTest& self) +void BuiltInTest::insert(Serializer& serializer) const { for(unsigned int i=0; i < 16; i++) - insert(serializer, self.result[i]); + serializer.insert(result[i]); } -void extract(::microstrain::Serializer& serializer, BuiltInTest& self) +void BuiltInTest::extract(Serializer& serializer) { for(unsigned int i=0; i < 16; i++) - extract(serializer, self.result[i]); + serializer.extract(result[i]); } -void insert(::microstrain::Serializer& serializer, const TimeSyncStatus& self) +void TimeSyncStatus::insert(Serializer& serializer) const { - insert(serializer, self.time_sync); + serializer.insert(time_sync); - insert(serializer, self.last_pps_rcvd); + serializer.insert(last_pps_rcvd); } -void extract(::microstrain::Serializer& serializer, TimeSyncStatus& self) +void TimeSyncStatus::extract(Serializer& serializer) { - extract(serializer, self.time_sync); + serializer.extract(time_sync); - extract(serializer, self.last_pps_rcvd); + serializer.extract(last_pps_rcvd); } -void insert(::microstrain::Serializer& serializer, const GpioState& self) +void GpioState::insert(Serializer& serializer) const { - insert(serializer, self.states); + serializer.insert(states); } -void extract(::microstrain::Serializer& serializer, GpioState& self) +void GpioState::extract(Serializer& serializer) { - extract(serializer, self.states); + serializer.extract(states); } -void insert(::microstrain::Serializer& serializer, const GpioAnalogValue& self) +void GpioAnalogValue::insert(Serializer& serializer) const { - insert(serializer, self.gpio_id); + serializer.insert(gpio_id); - insert(serializer, self.value); + serializer.insert(value); } -void extract(::microstrain::Serializer& serializer, GpioAnalogValue& self) +void GpioAnalogValue::extract(Serializer& serializer) { - extract(serializer, self.gpio_id); + serializer.extract(gpio_id); - extract(serializer, self.value); + serializer.extract(value); } diff --git a/src/cpp/mip/definitions/data_system.hpp b/src/cpp/mip/definitions/data_system.hpp index b2c1db326..fe009316a 100644 --- a/src/cpp/mip/definitions/data_system.hpp +++ b/src/cpp/mip/definitions/data_system.hpp @@ -1,16 +1,14 @@ #pragma once #include "common.hpp" -#include "mip/mip_descriptors.hpp" -#include "../mip_result.hpp" +#include +#include +#include #include #include -#include namespace mip { -; - namespace C { struct mip_interface; } // namespace C @@ -74,28 +72,32 @@ enum struct BuiltInTest { + /// Parameters uint8_t result[16] = {0}; ///< Device-specific bitfield (128 bits). See device user manual. Bits are least-significant-byte first. For example, bit 0 is located at bit 0 of result[0], bit 1 is located at bit 1 of result[0], bit 8 is located at bit 0 of result[1], and bit 127 is located at bit 7 of result[15]. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_system::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_system::DATA_BUILT_IN_TEST; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "BuiltInTest"; static constexpr const char* DOC_NAME = "BuiltInTest"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(result); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(result)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const BuiltInTest& self); -void extract(::microstrain::Serializer& serializer, BuiltInTest& self); - ///@} /// @@ -107,29 +109,33 @@ void extract(::microstrain::Serializer& serializer, BuiltInTest& self); struct TimeSyncStatus { + /// Parameters bool time_sync = 0; ///< True if sync with the PPS signal is currently valid. False if PPS feature is disabled or a PPS signal is not detected. uint8_t last_pps_rcvd = 0; ///< Elapsed time in seconds since last PPS was received, with a maximum value of 255. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_system::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_system::DATA_TIME_SYNC_STATUS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "TimeSyncStatus"; static constexpr const char* DOC_NAME = "TimeSyncStatus"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(time_sync,last_pps_rcvd); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(time_sync),std::ref(last_pps_rcvd)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const TimeSyncStatus& self); -void extract(::microstrain::Serializer& serializer, TimeSyncStatus& self); - ///@} /// @@ -159,28 +165,32 @@ void extract(::microstrain::Serializer& serializer, TimeSyncStatus& self); struct GpioState { + /// Parameters uint8_t states = 0; ///< Bitfield containing the states for each GPIO pin.
Bit 0 (0x01): pin 1
Bit 1 (0x02): pin 2
Bit 2 (0x04): pin 3
Bit 3 (0x08): pin 4
Bits for pins that don't exist will read as 0. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_system::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_system::DATA_GPIO_STATE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpioState"; static constexpr const char* DOC_NAME = "GpioState"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(states); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(states)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GpioState& self); -void extract(::microstrain::Serializer& serializer, GpioState& self); - ///@} /// @@ -193,29 +203,33 @@ void extract(::microstrain::Serializer& serializer, GpioState& self); struct GpioAnalogValue { + /// Parameters uint8_t gpio_id = 0; ///< GPIO pin number starting with 1. float value = 0; ///< Value of the GPIO line in scaled volts. + /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::data_system::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_system::DATA_GPIO_ANALOG_VALUE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpioAnalogValue"; static constexpr const char* DOC_NAME = "GpioAnalogValue"; + static constexpr const bool HAS_FUNCTION_SELECTOR = false; - - auto as_tuple() const + auto asTuple() const { return std::make_tuple(gpio_id,value); } - auto as_tuple() + auto asTuple() { return std::make_tuple(std::ref(gpio_id),std::ref(value)); } + + /// Serialization + void insert(Serializer& serializer) const; + void extract(Serializer& serializer); + }; -void insert(::microstrain::Serializer& serializer, const GpioAnalogValue& self); -void extract(::microstrain::Serializer& serializer, GpioAnalogValue& self); - ///@} /// diff --git a/src/cpp/mip/mip_descriptors.hpp b/src/cpp/mip/mip_descriptors.hpp index c568c521f..65d007591 100644 --- a/src/cpp/mip/mip_descriptors.hpp +++ b/src/cpp/mip/mip_descriptors.hpp @@ -1,8 +1,7 @@ #pragma once #include "mip_result.hpp" - -#include "microstrain/common/serialization.hpp" +#include "mip_serialization.hpp" #include @@ -62,8 +61,8 @@ using EnableForFieldTypes = std::enable_if::value, T>; /// template struct Bitfield {}; -template void insert (::microstrain::Serializer& serializer, const Bitfield& bitfield) { insert(serializer, static_cast(bitfield).value); } -template void extract(::microstrain::Serializer& serializer, Bitfield& bitfield) { extract(serializer, static_cast(bitfield).value); } +template void insert (Serializer& serializer, const Bitfield& bitfield) { insert(serializer, static_cast(bitfield).value); } +template void extract(Serializer& serializer, Bitfield& bitfield) { extract(serializer, static_cast(bitfield).value); } enum class FunctionSelector : uint8_t diff --git a/src/cpp/mip/mip_packet.hpp b/src/cpp/mip/mip_packet.hpp index deca65839..62972fec8 100644 --- a/src/cpp/mip/mip_packet.hpp +++ b/src/cpp/mip/mip_packet.hpp @@ -76,12 +76,12 @@ class PacketView : public C::mip_packet_view int remainingSpace() const { return C::mip_packet_remaining_space(this); } ///<@copydoc mip::C::mip_packet_remaining_space bool addField(uint8_t fieldDescriptor, const uint8_t* payload, uint8_t payloadLength) { return C::mip_packet_add_field(this, fieldDescriptor, payload, payloadLength); } ///<@copydoc mip::C::mip_packet_add_field - microstrain::Serializer createField(uint8_t fieldDescriptor, uint8_t length) { uint8_t * ptr; if(C::mip_packet_alloc_field(this, fieldDescriptor, length, &ptr) < 0) length =0; return microstrain::Serializer{ptr, length}; } + Serializer createField(uint8_t fieldDescriptor, uint8_t length) { uint8_t * ptr; if(C::mip_packet_alloc_field(this, fieldDescriptor, length, &ptr) < 0) length =0; return Serializer{ptr, length}; } //std::tuple createField(uint8_t fieldDescriptor) { uint8_t* ptr; int max_size = C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr); return max_size >= 0 ? std::make_tuple(ptr, max_size) : std::make_tuple(nullptr, 0); } ///<@copydoc mip::C::mip_packet_alloc_field //int finishLastField(uint8_t* payloadPtr, uint8_t newPayloadLength) { return C::mip_packet_realloc_last_field(this, payloadPtr, newPayloadLength); } ///<@copydoc mip::C::mip_packet_realloc_last_field //int cancelLastField(uint8_t* payloadPtr) { return C::mip_packet_cancel_last_field(this, payloadPtr); } ///<@copydoc mip::C::mip_packet_cancel_last_field - class AllocatedField : public microstrain::Serializer + class AllocatedField : public Serializer { public: AllocatedField(mip::PacketView& packet, uint8_t* buffer, size_t space) : Serializer(buffer, space), m_packet(packet) {} @@ -254,7 +254,7 @@ class SizedPacketBuf : public PacketView ///@brief Copy constructor SizedPacketBuf(const SizedPacketBuf& other) : PacketView(mData, sizeof(mData)) { copyFrom(other); } - ///@brief Copy constructor (required to put packets into std::vector in some cases). + ///@brief Copy constructor (required to insert packets into std::vector in some cases). template explicit SizedPacketBuf(const SizedPacketBuf& other) : PacketView(mData, sizeof(mData)) { copyFrom(other); }; diff --git a/src/cpp/mip/mip_serialization.hpp b/src/cpp/mip/mip_serialization.hpp index 6ef2370dd..fa07650e9 100644 --- a/src/cpp/mip/mip_serialization.hpp +++ b/src/cpp/mip/mip_serialization.hpp @@ -8,51 +8,44 @@ namespace mip { -} // namespace mip +using Serializer = microstrain::BigEndianSerializer; -// These functions must be in the microstrain namespace in order to be seen as overloads. -namespace microstrain +namespace serialization { -// -// Mip field types (commands and data) -// - -template -typename std::enable_if::value, size_t>::type -/*size_t*/ insert(microstrain::Serializer& serializer, const T& field) -{ - //static_assert(std::is_base_of, T>::value, "T doesn't derive from FieldStruct"); - - return insert(serializer, field.asTuple()); -} - -template -typename std::enable_if::value, size_t>::type -/*size_t*/ extract(microstrain::Serializer& serializer, T& field) -{ - //static_assert(std::is_base_of, T>::value, "T doesn't derive from FieldStruct"); - - return extract(serializer, field.asTuple()); + using namespace microstrain::serialization; + using namespace microstrain::serialization::big_endian; } // -// Bitfields +//template +//size_t insert(Serializer& serializer, const Ts&... values) +//{ +// return serializer.insert(std::forward(values)...); +//} +// +//template +//size_t extract(Serializer& serializer, Ts&... values) +//{ +// return microstrain::extract(serializer, std::forward(values)...); +//} // +//template +//size_t extract_count(Serializer& buffer, T* count, size_t max_count) +//{ +// return microstrain::extract_count(buffer, count, max_count); +//} +//template +//size_t extract_count(Serializer& buffer, T& count, size_t max_count) +//{ +// return microstrain::extract_count(buffer, count, max_count); +//} -template -typename std::enable_if, T>::value, size_t>::type -/*size_t*/ insert(Serializer& serializer, T bits) -{ - return insert(serializer, bits.value); -} -template -typename std::enable_if, T>::value, size_t>::type -/*size_t*/ extract(Serializer& serializer, T& bits) -{ - return extract(serializer, bits.value); -} +} // namespace mip +// These functions must be in the microstrain namespace in order to be seen as overloads. +namespace microstrain +{ } // namespace microstrain From 90c7443905abc622c6a710d528c3537d45cde9a4 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 16 Jul 2024 17:26:43 -0400 Subject: [PATCH 049/147] Serialization code update complete. Add ReplyField metadata. Stringification example is working. --- examples/CSV/stringify.cpp | 16 +- src/c/mip/definitions/commands_3dm.c | 224 ++++++++++++++++++ src/c/mip/definitions/commands_3dm.h | 90 +++---- src/c/mip/definitions/commands_aiding.h | 36 +-- src/c/mip/definitions/commands_base.h | 30 ++- src/c/mip/definitions/commands_filter.h | 64 ++--- src/c/mip/definitions/commands_gnss.c | 21 ++ src/c/mip/definitions/commands_gnss.h | 2 + src/c/mip/definitions/commands_rtk.h | 40 +++- src/c/mip/definitions/data_filter.h | 40 ++-- src/c/mip/definitions/data_gnss.h | 172 +++++++------- src/c/mip/definitions/data_sensor.h | 8 +- src/c/mip/definitions/data_shared.h | 12 +- .../common/serialization/serializer.hpp | 141 ++++++----- src/cpp/mip/definitions/commands_3dm.cpp | 221 +++++++++++++++++ src/cpp/mip/definitions/commands_gnss.cpp | 21 ++ src/cpp/mip/definitions/common.hpp | 16 +- src/cpp/mip/metadata/definitions/common.hpp | 153 +++++++++--- src/cpp/mip/metadata/mip_definitions.cpp | 5 +- src/cpp/mip/mip_descriptors.hpp | 4 +- src/cpp/mip/mip_serialization.hpp | 8 + 21 files changed, 996 insertions(+), 328 deletions(-) diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp index cc46a008f..707cd1f94 100644 --- a/examples/CSV/stringify.cpp +++ b/examples/CSV/stringify.cpp @@ -81,14 +81,14 @@ static std::optional readIntegralValue(Type type, mip::Serializer& ser { switch(type) { - case Type::U8: return microstrain::extract(serializer); - case Type::S8: return microstrain::extract(serializer); - case Type::U16: return microstrain::extract(serializer); - case Type::S16: return microstrain::extract(serializer); - case Type::U32: return microstrain::extract(serializer); - case Type::S32: return microstrain::extract(serializer); - case Type::U64: return microstrain::extract(serializer); - case Type::S64: return microstrain::extract(serializer); + case Type::U8: return microstrain::extract< uint8_t>(serializer); + case Type::S8: return microstrain::extract< int8_t>(serializer); + case Type::U16: return microstrain::extract(serializer); + case Type::S16: return microstrain::extract< int32_t>(serializer); + case Type::U32: return microstrain::extract(serializer); + case Type::S32: return microstrain::extract< int64_t>(serializer); + case Type::U64: return microstrain::extract(serializer); + case Type::S64: return microstrain::extract< int64_t>(serializer); default: return std::nullopt; } } diff --git a/src/c/mip/definitions/commands_3dm.c b/src/c/mip/definitions/commands_3dm.c index 8704e3243..cf7b15ce1 100644 --- a/src/c/mip/definitions/commands_3dm.c +++ b/src/c/mip/definitions/commands_3dm.c @@ -1219,6 +1219,33 @@ mip_cmd_result mip_3dm_default_datastream_control(mip_interface* device, uint8_t return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_CONTROL_DATA_STREAM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } +void insert_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_settings* self) +{ + insert_mip_3dm_constellation_settings_command_constellation_id(serializer, self->constellation_id); + + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_u8(serializer, self->reserved_channels); + + microstrain_insert_u8(serializer, self->max_channels); + + insert_mip_3dm_constellation_settings_command_option_flags(serializer, self->option_flags); + +} +void extract_mip_3dm_constellation_settings_command_settings(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_settings* self) +{ + extract_mip_3dm_constellation_settings_command_constellation_id(serializer, &self->constellation_id); + + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_u8(serializer, &self->reserved_channels); + + microstrain_extract_u8(serializer, &self->max_channels); + + extract_mip_3dm_constellation_settings_command_option_flags(serializer, &self->option_flags); + +} + void insert_mip_3dm_constellation_settings_command(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2220,6 +2247,21 @@ mip_cmd_result mip_3dm_default_odometer(mip_interface* device) return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_ODOMETER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } +void insert_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_info* self) +{ + microstrain_insert_u8(serializer, self->type); + + microstrain_insert_u8(serializer, self->count); + +} +void extract_mip_3dm_get_event_support_command_info(microstrain_serializer* serializer, mip_3dm_get_event_support_command_info* self) +{ + microstrain_extract_u8(serializer, &self->type); + + microstrain_extract_u8(serializer, &self->count); + +} + void insert_mip_3dm_get_event_support_command(microstrain_serializer* serializer, const mip_3dm_get_event_support_command* self) { insert_mip_3dm_get_event_support_command_query(serializer, self->query); @@ -2379,6 +2421,21 @@ mip_cmd_result mip_3dm_default_event_control(mip_interface* device, uint8_t inst return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } +void insert_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_entry* self) +{ + microstrain_insert_u8(serializer, self->type); + + insert_mip_3dm_get_event_trigger_status_command_status(serializer, self->status); + +} +void extract_mip_3dm_get_event_trigger_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_entry* self) +{ + microstrain_extract_u8(serializer, &self->type); + + extract_mip_3dm_get_event_trigger_status_command_status(serializer, &self->status); + +} + void insert_mip_3dm_get_event_trigger_status_command(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command* self) { microstrain_insert_u8(serializer, self->requested_count); @@ -2432,6 +2489,21 @@ mip_cmd_result mip_3dm_get_event_trigger_status(mip_interface* device, uint8_t r } return result; } +void insert_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command_entry* self) +{ + microstrain_insert_u8(serializer, self->action_type); + + microstrain_insert_u8(serializer, self->trigger_id); + +} +void extract_mip_3dm_get_event_action_status_command_entry(microstrain_serializer* serializer, mip_3dm_get_event_action_status_command_entry* self) +{ + microstrain_extract_u8(serializer, &self->action_type); + + microstrain_extract_u8(serializer, &self->trigger_id); + +} + void insert_mip_3dm_get_event_action_status_command(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_command* self) { microstrain_insert_u8(serializer, self->requested_count); @@ -2485,6 +2557,101 @@ mip_cmd_result mip_3dm_get_event_action_status(mip_interface* device, uint8_t re } return result; } +void insert_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params* self) +{ + microstrain_insert_u8(serializer, self->pin); + + insert_mip_3dm_event_trigger_command_gpio_params_mode(serializer, self->mode); + +} +void extract_mip_3dm_event_trigger_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params* self) +{ + microstrain_extract_u8(serializer, &self->pin); + + extract_mip_3dm_event_trigger_command_gpio_params_mode(serializer, &self->mode); + +} + +void insert_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params* self) +{ + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u8(serializer, self->field_desc); + + microstrain_insert_u8(serializer, self->param_id); + + insert_mip_3dm_event_trigger_command_threshold_params_type(serializer, self->type); + + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) + { + microstrain_insert_double(serializer, self->low_thres); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) + { + microstrain_insert_double(serializer, self->int_thres); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) + { + microstrain_insert_double(serializer, self->high_thres); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) + { + microstrain_insert_double(serializer, self->interval); + + } +} +void extract_mip_3dm_event_trigger_command_threshold_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params* self) +{ + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_u8(serializer, &self->field_desc); + + microstrain_extract_u8(serializer, &self->param_id); + + extract_mip_3dm_event_trigger_command_threshold_params_type(serializer, &self->type); + + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) + { + microstrain_extract_double(serializer, &self->low_thres); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) + { + microstrain_extract_double(serializer, &self->int_thres); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_WINDOW ) + { + microstrain_extract_double(serializer, &self->high_thres); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_THRESHOLD_PARAMS_TYPE_INTERVAL ) + { + microstrain_extract_double(serializer, &self->interval); + + } +} + +void insert_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_combination_params* self) +{ + microstrain_insert_u16(serializer, self->logic_table); + + for(unsigned int i=0; i < 4; i++) + microstrain_insert_u8(serializer, self->input_triggers[i]); + +} +void extract_mip_3dm_event_trigger_command_combination_params(microstrain_serializer* serializer, mip_3dm_event_trigger_command_combination_params* self) +{ + microstrain_extract_u16(serializer, &self->logic_table); + + for(unsigned int i=0; i < 4; i++) + microstrain_extract_u8(serializer, &self->input_triggers[i]); + +} + void insert_mip_3dm_event_trigger_command(microstrain_serializer* serializer, const mip_3dm_event_trigger_command* self) { insert_mip_function_selector(serializer, self->function); @@ -2658,6 +2825,48 @@ mip_cmd_result mip_3dm_default_event_trigger(mip_interface* device, uint8_t inst return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } +void insert_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params* self) +{ + microstrain_insert_u8(serializer, self->pin); + + insert_mip_3dm_event_action_command_gpio_params_mode(serializer, self->mode); + +} +void extract_mip_3dm_event_action_command_gpio_params(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params* self) +{ + microstrain_extract_u8(serializer, &self->pin); + + extract_mip_3dm_event_action_command_gpio_params_mode(serializer, &self->mode); + +} + +void insert_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, const mip_3dm_event_action_command_message_params* self) +{ + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u16(serializer, self->decimation); + + microstrain_insert_u8(serializer, self->num_fields); + + + for(unsigned int i=0; i < self->num_fields; i++) + microstrain_insert_u8(serializer, self->descriptors[i]); + +} +void extract_mip_3dm_event_action_command_message_params(microstrain_serializer* serializer, mip_3dm_event_action_command_message_params* self) +{ + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_u16(serializer, &self->decimation); + + assert(self->num_fields); + microstrain_extract_count(serializer, &self->num_fields, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + + for(unsigned int i=0; i < self->num_fields; i++) + microstrain_extract_u8(serializer, &self->descriptors[i]); + +} + void insert_mip_3dm_event_action_command(microstrain_serializer* serializer, const mip_3dm_event_action_command* self) { insert_mip_function_selector(serializer, self->function); @@ -3907,6 +4116,21 @@ mip_cmd_result mip_3dm_default_sensor_range(mip_interface* device, mip_sensor_ra return mip_interface_run_command(device, MIP_3DM_CMD_DESC_SET, MIP_CMD_DESC_3DM_SENSOR_RANGE, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } +void insert_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command_entry* self) +{ + microstrain_insert_u8(serializer, self->setting); + + microstrain_insert_float(serializer, self->range); + +} +void extract_mip_3dm_calibrated_sensor_ranges_command_entry(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_command_entry* self) +{ + microstrain_extract_u8(serializer, &self->setting); + + microstrain_extract_float(serializer, &self->range); + +} + void insert_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_command* self) { insert_mip_sensor_range_type(serializer, self->sensor); diff --git a/src/c/mip/definitions/commands_3dm.h b/src/c/mip/definitions/commands_3dm.h index d004ba10a..480cbf5a3 100644 --- a/src/c/mip/definitions/commands_3dm.h +++ b/src/c/mip/definitions/commands_3dm.h @@ -157,11 +157,11 @@ enum mip_nmea_message_message_id }; typedef enum mip_nmea_message_message_id mip_nmea_message_message_id; -inline void insert_mip_nmea_message_message_id(microstrain_serializer* serializer, const mip_nmea_message_message_id self) +static inline void insert_mip_nmea_message_message_id(microstrain_serializer* serializer, const mip_nmea_message_message_id self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_nmea_message_message_id(microstrain_serializer* serializer, mip_nmea_message_message_id* self) +static inline void extract_mip_nmea_message_message_id(microstrain_serializer* serializer, mip_nmea_message_message_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -178,11 +178,11 @@ enum mip_nmea_message_talker_id }; typedef enum mip_nmea_message_talker_id mip_nmea_message_talker_id; -inline void insert_mip_nmea_message_talker_id(microstrain_serializer* serializer, const mip_nmea_message_talker_id self) +static inline void insert_mip_nmea_message_talker_id(microstrain_serializer* serializer, const mip_nmea_message_talker_id self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_nmea_message_talker_id(microstrain_serializer* serializer, mip_nmea_message_talker_id* self) +static inline void extract_mip_nmea_message_talker_id(microstrain_serializer* serializer, mip_nmea_message_talker_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -212,11 +212,11 @@ enum mip_sensor_range_type }; typedef enum mip_sensor_range_type mip_sensor_range_type; -inline void insert_mip_sensor_range_type(microstrain_serializer* serializer, const mip_sensor_range_type self) +static inline void insert_mip_sensor_range_type(microstrain_serializer* serializer, const mip_sensor_range_type self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_sensor_range_type(microstrain_serializer* serializer, mip_sensor_range_type* self) +static inline void extract_mip_sensor_range_type(microstrain_serializer* serializer, mip_sensor_range_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -432,6 +432,8 @@ mip_cmd_result mip_3dm_default_filter_message_format(mip_interface* device); /// ///@{ +typedef struct mip_3dm_imu_get_base_rate_command mip_3dm_imu_get_base_rate_command; ///< No parameters (empty struct not allowed in C) + struct mip_3dm_imu_get_base_rate_response { uint16_t rate; ///< [hz] @@ -454,6 +456,8 @@ mip_cmd_result mip_3dm_imu_get_base_rate(mip_interface* device, uint16_t* rate_o /// ///@{ +typedef struct mip_3dm_gps_get_base_rate_command mip_3dm_gps_get_base_rate_command; ///< No parameters (empty struct not allowed in C) + struct mip_3dm_gps_get_base_rate_response { uint16_t rate; ///< [hz] @@ -476,6 +480,8 @@ mip_cmd_result mip_3dm_gps_get_base_rate(mip_interface* device, uint16_t* rate_o /// ///@{ +typedef struct mip_3dm_filter_get_base_rate_command mip_3dm_filter_get_base_rate_command; ///< No parameters (empty struct not allowed in C) + struct mip_3dm_filter_get_base_rate_response { uint16_t rate; ///< [hz] @@ -737,11 +743,11 @@ enum mip_3dm_factory_streaming_command_action }; typedef enum mip_3dm_factory_streaming_command_action mip_3dm_factory_streaming_command_action; -inline void insert_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command_action self) +static inline void insert_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, const mip_3dm_factory_streaming_command_action self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, mip_3dm_factory_streaming_command_action* self) +static inline void extract_mip_3dm_factory_streaming_command_action(microstrain_serializer* serializer, mip_3dm_factory_streaming_command_action* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -842,11 +848,11 @@ enum mip_3dm_constellation_settings_command_constellation_id }; typedef enum mip_3dm_constellation_settings_command_constellation_id mip_3dm_constellation_settings_command_constellation_id; -inline void insert_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self) +static inline void insert_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_constellation_id self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self) +static inline void extract_mip_3dm_constellation_settings_command_constellation_id(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_constellation_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -857,11 +863,11 @@ typedef uint16_t mip_3dm_constellation_settings_command_option_flags; static const mip_3dm_constellation_settings_command_option_flags MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_OPTION_FLAGS_NONE = 0x0000; static const mip_3dm_constellation_settings_command_option_flags MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_OPTION_FLAGS_L1SAIF = 0x0001; ///< Available only for QZSS static const mip_3dm_constellation_settings_command_option_flags MIP_3DM_CONSTELLATION_SETTINGS_COMMAND_OPTION_FLAGS_ALL = 0x0001; -inline void insert_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self) +static inline void insert_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, const mip_3dm_constellation_settings_command_option_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self) +static inline void extract_mip_3dm_constellation_settings_command_option_flags(microstrain_serializer* serializer, mip_3dm_constellation_settings_command_option_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -929,11 +935,11 @@ static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SE static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SETTINGS_COMMAND_SBASOPTIONS_ENABLE_CORRECTIONS = 0x0002; ///< Use SBAS differential corrections static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SETTINGS_COMMAND_SBASOPTIONS_APPLY_INTEGRITY = 0x0004; ///< Use SBAS integrity information. If enabled, only GPS satellites for which integrity information is available will be used. static const mip_3dm_gnss_sbas_settings_command_sbasoptions MIP_3DM_GNSS_SBAS_SETTINGS_COMMAND_SBASOPTIONS_ALL = 0x0007; -inline void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self) +static inline void insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_command_sbasoptions self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self) +static inline void extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_command_sbasoptions* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -997,11 +1003,11 @@ enum mip_3dm_gnss_assisted_fix_command_assisted_fix_option }; typedef enum mip_3dm_gnss_assisted_fix_command_assisted_fix_option mip_3dm_gnss_assisted_fix_command_assisted_fix_option; -inline void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self) +static inline void insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_command_assisted_fix_option self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self) +static inline void extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_command_assisted_fix_option* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1147,11 +1153,11 @@ enum mip_3dm_pps_source_command_source }; typedef enum mip_3dm_pps_source_command_source mip_3dm_pps_source_command_source; -inline void insert_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, const mip_3dm_pps_source_command_source self) +static inline void insert_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, const mip_3dm_pps_source_command_source self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, mip_3dm_pps_source_command_source* self) +static inline void extract_mip_3dm_pps_source_command_source(microstrain_serializer* serializer, mip_3dm_pps_source_command_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1219,11 +1225,11 @@ enum mip_3dm_gpio_config_command_feature }; typedef enum mip_3dm_gpio_config_command_feature mip_3dm_gpio_config_command_feature; -inline void insert_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_feature self) +static inline void insert_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_feature self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, mip_3dm_gpio_config_command_feature* self) +static inline void extract_mip_3dm_gpio_config_command_feature(microstrain_serializer* serializer, mip_3dm_gpio_config_command_feature* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1250,11 +1256,11 @@ enum mip_3dm_gpio_config_command_behavior }; typedef enum mip_3dm_gpio_config_command_behavior mip_3dm_gpio_config_command_behavior; -inline void insert_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_behavior self) +static inline void insert_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_behavior self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, mip_3dm_gpio_config_command_behavior* self) +static inline void extract_mip_3dm_gpio_config_command_behavior(microstrain_serializer* serializer, mip_3dm_gpio_config_command_behavior* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1267,11 +1273,11 @@ static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PI static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PIN_MODE_PULLDOWN = 0x02; ///< The pin will have an internal pull-down resistor enabled. This is useful for connecting inputs to signals which can only be pulled high such as mechanical switches. Cannot be used in combination with pull-up. See the device specifications for the resistance value. static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PIN_MODE_PULLUP = 0x04; ///< The pin will have an internal pull-up resistor enabled. Useful for connecting inputs to signals which can only be pulled low such as mechanical switches, or in combination with an open drain output. Cannot be used in combination with pull-down. See the device specifications for the resistance value. Use of this mode may restrict the maximum allowed input voltage. See the device datasheet for details. static const mip_3dm_gpio_config_command_pin_mode MIP_3DM_GPIO_CONFIG_COMMAND_PIN_MODE_ALL = 0x07; -inline void insert_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self) +static inline void insert_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, const mip_3dm_gpio_config_command_pin_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self) +static inline void extract_mip_3dm_gpio_config_command_pin_mode(microstrain_serializer* serializer, mip_3dm_gpio_config_command_pin_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1373,11 +1379,11 @@ enum mip_3dm_odometer_command_mode }; typedef enum mip_3dm_odometer_command_mode mip_3dm_odometer_command_mode; -inline void insert_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, const mip_3dm_odometer_command_mode self) +static inline void insert_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, const mip_3dm_odometer_command_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, mip_3dm_odometer_command_mode* self) +static inline void extract_mip_3dm_odometer_command_mode(microstrain_serializer* serializer, mip_3dm_odometer_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1445,11 +1451,11 @@ enum mip_3dm_get_event_support_command_query }; typedef enum mip_3dm_get_event_support_command_query mip_3dm_get_event_support_command_query; -inline void insert_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_query self) +static inline void insert_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, const mip_3dm_get_event_support_command_query self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, mip_3dm_get_event_support_command_query* self) +static inline void extract_mip_3dm_get_event_support_command_query(microstrain_serializer* serializer, mip_3dm_get_event_support_command_query* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1516,11 +1522,11 @@ enum mip_3dm_event_control_command_mode }; typedef enum mip_3dm_event_control_command_mode mip_3dm_event_control_command_mode; -inline void insert_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, const mip_3dm_event_control_command_mode self) +static inline void insert_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, const mip_3dm_event_control_command_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, mip_3dm_event_control_command_mode* self) +static inline void extract_mip_3dm_event_control_command_mode(microstrain_serializer* serializer, mip_3dm_event_control_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1568,11 +1574,11 @@ static const mip_3dm_get_event_trigger_status_command_status MIP_3DM_GET_EVENT_T static const mip_3dm_get_event_trigger_status_command_status MIP_3DM_GET_EVENT_TRIGGER_STATUS_COMMAND_STATUS_ENABLED = 0x02; ///< True if the trigger is enabled. static const mip_3dm_get_event_trigger_status_command_status MIP_3DM_GET_EVENT_TRIGGER_STATUS_COMMAND_STATUS_TEST = 0x04; ///< True if the trigger is in test mode. static const mip_3dm_get_event_trigger_status_command_status MIP_3DM_GET_EVENT_TRIGGER_STATUS_COMMAND_STATUS_ALL = 0x07; -inline void insert_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self) +static inline void insert_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_command_status self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self) +static inline void extract_mip_3dm_get_event_trigger_status_command_status(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_command_status* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1669,11 +1675,11 @@ enum mip_3dm_event_trigger_command_gpio_params_mode }; typedef enum mip_3dm_event_trigger_command_gpio_params_mode mip_3dm_event_trigger_command_gpio_params_mode; -inline void insert_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self) +static inline void insert_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_gpio_params_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self) +static inline void extract_mip_3dm_event_trigger_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_trigger_command_gpio_params_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1698,11 +1704,11 @@ enum mip_3dm_event_trigger_command_threshold_params_type }; typedef enum mip_3dm_event_trigger_command_threshold_params_type mip_3dm_event_trigger_command_threshold_params_type; -inline void insert_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self) +static inline void insert_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_threshold_params_type self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self) +static inline void extract_mip_3dm_event_trigger_command_threshold_params_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_threshold_params_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1765,11 +1771,11 @@ enum mip_3dm_event_trigger_command_type }; typedef enum mip_3dm_event_trigger_command_type mip_3dm_event_trigger_command_type; -inline void insert_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_type self) +static inline void insert_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, const mip_3dm_event_trigger_command_type self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_type* self) +static inline void extract_mip_3dm_event_trigger_command_type(microstrain_serializer* serializer, mip_3dm_event_trigger_command_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1832,11 +1838,11 @@ enum mip_3dm_event_action_command_gpio_params_mode }; typedef enum mip_3dm_event_action_command_gpio_params_mode mip_3dm_event_action_command_gpio_params_mode; -inline void insert_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self) +static inline void insert_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, const mip_3dm_event_action_command_gpio_params_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self) +static inline void extract_mip_3dm_event_action_command_gpio_params_mode(microstrain_serializer* serializer, mip_3dm_event_action_command_gpio_params_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1874,11 +1880,11 @@ enum mip_3dm_event_action_command_type }; typedef enum mip_3dm_event_action_command_type mip_3dm_event_action_command_type; -inline void insert_mip_3dm_event_action_command_type(microstrain_serializer* serializer, const mip_3dm_event_action_command_type self) +static inline void insert_mip_3dm_event_action_command_type(microstrain_serializer* serializer, const mip_3dm_event_action_command_type self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_3dm_event_action_command_type(microstrain_serializer* serializer, mip_3dm_event_action_command_type* self) +static inline void extract_mip_3dm_event_action_command_type(microstrain_serializer* serializer, mip_3dm_event_action_command_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); diff --git a/src/c/mip/definitions/commands_aiding.h b/src/c/mip/definitions/commands_aiding.h index bfa412195..81425e141 100644 --- a/src/c/mip/definitions/commands_aiding.h +++ b/src/c/mip/definitions/commands_aiding.h @@ -66,11 +66,11 @@ enum mip_time_timebase }; typedef enum mip_time_timebase mip_time_timebase; -inline void insert_mip_time_timebase(microstrain_serializer* serializer, const mip_time_timebase self) +static inline void insert_mip_time_timebase(microstrain_serializer* serializer, const mip_time_timebase self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_time_timebase(microstrain_serializer* serializer, mip_time_timebase* self) +static inline void extract_mip_time_timebase(microstrain_serializer* serializer, mip_time_timebase* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -130,11 +130,11 @@ enum mip_aiding_frame_config_command_format }; typedef enum mip_aiding_frame_config_command_format mip_aiding_frame_config_command_format; -inline void insert_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self) +static inline void insert_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, const mip_aiding_frame_config_command_format self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self) +static inline void extract_mip_aiding_frame_config_command_format(microstrain_serializer* serializer, mip_aiding_frame_config_command_format* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -197,11 +197,11 @@ enum mip_aiding_aiding_echo_control_command_mode }; typedef enum mip_aiding_aiding_echo_control_command_mode mip_aiding_aiding_echo_control_command_mode; -inline void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) +static inline void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) +static inline void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -248,11 +248,11 @@ static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) +static inline void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) +static inline void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -290,11 +290,11 @@ static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_V static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_LONGITUDE = 0x0002; ///< static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_HEIGHT = 0x0004; ///< static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) +static inline void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) +static inline void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -356,11 +356,11 @@ static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) +static inline void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) +static inline void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -397,11 +397,11 @@ static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_V static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) +static inline void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) +static inline void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -439,11 +439,11 @@ static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AID static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) +static inline void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) +static inline void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -502,11 +502,11 @@ static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_F static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_FIELD_COMMAND_VALID_FLAGS_Y = 0x0002; ///< static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_FIELD_COMMAND_VALID_FLAGS_Z = 0x0004; ///< static const mip_aiding_magnetic_field_command_valid_flags MIP_AIDING_MAGNETIC_FIELD_COMMAND_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self) +static inline void insert_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_magnetic_field_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self) +static inline void extract_mip_aiding_magnetic_field_command_valid_flags(microstrain_serializer* serializer, mip_aiding_magnetic_field_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/c/mip/definitions/commands_base.h b/src/c/mip/definitions/commands_base.h index ab837b526..c36ce3c8c 100644 --- a/src/c/mip/definitions/commands_base.h +++ b/src/c/mip/definitions/commands_base.h @@ -77,11 +77,11 @@ enum mip_time_format }; typedef enum mip_time_format mip_time_format; -inline void insert_mip_time_format(microstrain_serializer* serializer, const mip_time_format self) +static inline void insert_mip_time_format(microstrain_serializer* serializer, const mip_time_format self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_time_format(microstrain_serializer* serializer, mip_time_format* self) +static inline void extract_mip_time_format(microstrain_serializer* serializer, mip_time_format* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -118,11 +118,11 @@ static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_RTK_FA static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_SOLUTION_FAULT = 0x40000000; ///< static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_GNSS_GENERAL_FAULT = 0x80000000; ///< static const mip_commanded_test_bits_gq7 MIP_COMMANDED_TEST_BITS_GQ7_ALL = 0xFFFFFFFF; -inline void insert_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self) +static inline void insert_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, const mip_commanded_test_bits_gq7 self) { microstrain_insert_u32(serializer, (uint32_t)(self)); } -inline void extract_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self) +static inline void extract_mip_commanded_test_bits_gq7(microstrain_serializer* serializer, mip_commanded_test_bits_gq7* self) { uint32_t tmp = 0; microstrain_extract_u32(serializer, &tmp); @@ -144,6 +144,8 @@ inline void extract_mip_commanded_test_bits_gq7(microstrain_serializer* serializ /// ///@{ +typedef struct mip_base_ping_command mip_base_ping_command; ///< No parameters (empty struct not allowed in C) + mip_cmd_result mip_base_ping(mip_interface* device); ///@} @@ -158,6 +160,8 @@ mip_cmd_result mip_base_ping(mip_interface* device); /// ///@{ +typedef struct mip_base_set_idle_command mip_base_set_idle_command; ///< No parameters (empty struct not allowed in C) + mip_cmd_result mip_base_set_idle(mip_interface* device); ///@} @@ -168,6 +172,8 @@ mip_cmd_result mip_base_set_idle(mip_interface* device); /// ///@{ +typedef struct mip_base_get_device_info_command mip_base_get_device_info_command; ///< No parameters (empty struct not allowed in C) + struct mip_base_get_device_info_response { mip_base_device_info device_info; @@ -190,6 +196,8 @@ mip_cmd_result mip_base_get_device_info(mip_interface* device, mip_base_device_i /// ///@{ +typedef struct mip_base_get_device_descriptors_command mip_base_get_device_descriptors_command; ///< No parameters (empty struct not allowed in C) + struct mip_base_get_device_descriptors_response { uint16_t descriptors[253]; @@ -215,6 +223,8 @@ mip_cmd_result mip_base_get_device_descriptors(mip_interface* device, uint16_t* /// ///@{ +typedef struct mip_base_built_in_test_command mip_base_built_in_test_command; ///< No parameters (empty struct not allowed in C) + struct mip_base_built_in_test_response { uint32_t result; @@ -236,6 +246,8 @@ mip_cmd_result mip_base_built_in_test(mip_interface* device, uint32_t* result_ou /// ///@{ +typedef struct mip_base_resume_command mip_base_resume_command; ///< No parameters (empty struct not allowed in C) + mip_cmd_result mip_base_resume(mip_interface* device); ///@} @@ -249,6 +261,8 @@ mip_cmd_result mip_base_resume(mip_interface* device); /// ///@{ +typedef struct mip_base_get_extended_descriptors_command mip_base_get_extended_descriptors_command; ///< No parameters (empty struct not allowed in C) + struct mip_base_get_extended_descriptors_response { uint16_t descriptors[253]; @@ -271,6 +285,8 @@ mip_cmd_result mip_base_get_extended_descriptors(mip_interface* device, uint16_t /// ///@{ +typedef struct mip_base_continuous_bit_command mip_base_continuous_bit_command; ///< No parameters (empty struct not allowed in C) + struct mip_base_continuous_bit_response { uint8_t result[16]; ///< Device-specific bitfield (128 bits). See device user manual. Bits are least-significant-byte first. For example, bit 0 is located at bit 0 of result[0], bit 1 is located at bit 1 of result[0], bit 8 is located at bit 0 of result[1], and bit 127 is located at bit 7 of result[15]. @@ -350,11 +366,11 @@ enum mip_base_gps_time_update_command_field_id }; typedef enum mip_base_gps_time_update_command_field_id mip_base_gps_time_update_command_field_id; -inline void insert_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self) +static inline void insert_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, const mip_base_gps_time_update_command_field_id self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self) +static inline void extract_mip_base_gps_time_update_command_field_id(microstrain_serializer* serializer, mip_base_gps_time_update_command_field_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -385,6 +401,8 @@ mip_cmd_result mip_base_write_gps_time_update(mip_interface* device, mip_base_gp /// ///@{ +typedef struct mip_base_soft_reset_command mip_base_soft_reset_command; ///< No parameters (empty struct not allowed in C) + mip_cmd_result mip_base_soft_reset(mip_interface* device); ///@} diff --git a/src/c/mip/definitions/commands_filter.h b/src/c/mip/definitions/commands_filter.h index 9718f4329..ac33425dc 100644 --- a/src/c/mip/definitions/commands_filter.h +++ b/src/c/mip/definitions/commands_filter.h @@ -161,11 +161,11 @@ enum mip_filter_reference_frame }; typedef enum mip_filter_reference_frame mip_filter_reference_frame; -inline void insert_mip_filter_reference_frame(microstrain_serializer* serializer, const mip_filter_reference_frame self) +static inline void insert_mip_filter_reference_frame(microstrain_serializer* serializer, const mip_filter_reference_frame self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_reference_frame(microstrain_serializer* serializer, mip_filter_reference_frame* self) +static inline void extract_mip_filter_reference_frame(microstrain_serializer* serializer, mip_filter_reference_frame* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -180,11 +180,11 @@ enum mip_filter_mag_param_source }; typedef enum mip_filter_mag_param_source mip_filter_mag_param_source; -inline void insert_mip_filter_mag_param_source(microstrain_serializer* serializer, const mip_filter_mag_param_source self) +static inline void insert_mip_filter_mag_param_source(microstrain_serializer* serializer, const mip_filter_mag_param_source self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_mag_param_source(microstrain_serializer* serializer, mip_filter_mag_param_source* self) +static inline void extract_mip_filter_mag_param_source(microstrain_serializer* serializer, mip_filter_mag_param_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -199,11 +199,11 @@ enum mip_filter_adaptive_measurement }; typedef enum mip_filter_adaptive_measurement mip_filter_adaptive_measurement; -inline void insert_mip_filter_adaptive_measurement(microstrain_serializer* serializer, const mip_filter_adaptive_measurement self) +static inline void insert_mip_filter_adaptive_measurement(microstrain_serializer* serializer, const mip_filter_adaptive_measurement self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_adaptive_measurement(microstrain_serializer* serializer, mip_filter_adaptive_measurement* self) +static inline void extract_mip_filter_adaptive_measurement(microstrain_serializer* serializer, mip_filter_adaptive_measurement* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -224,6 +224,8 @@ inline void extract_mip_filter_adaptive_measurement(microstrain_serializer* seri /// ///@{ +typedef struct mip_filter_reset_command mip_filter_reset_command; ///< No parameters (empty struct not allowed in C) + mip_cmd_result mip_filter_reset(mip_interface* device); ///@} @@ -286,11 +288,11 @@ static const mip_filter_estimation_control_command_enable_flags MIP_FILTER_ESTIM static const mip_filter_estimation_control_command_enable_flags MIP_FILTER_ESTIMATION_CONTROL_COMMAND_ENABLE_FLAGS_AUTO_MAG_HARD_IRON = 0x0020; ///< static const mip_filter_estimation_control_command_enable_flags MIP_FILTER_ESTIMATION_CONTROL_COMMAND_ENABLE_FLAGS_AUTO_MAG_SOFT_IRON = 0x0040; ///< static const mip_filter_estimation_control_command_enable_flags MIP_FILTER_ESTIMATION_CONTROL_COMMAND_ENABLE_FLAGS_ALL = 0x007F; -inline void insert_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self) +static inline void insert_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, const mip_filter_estimation_control_command_enable_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self) +static inline void extract_mip_filter_estimation_control_command_enable_flags(microstrain_serializer* serializer, mip_filter_estimation_control_command_enable_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -443,11 +445,11 @@ static const mip_filter_tare_orientation_command_mip_tare_axes MIP_FILTER_TARE_O static const mip_filter_tare_orientation_command_mip_tare_axes MIP_FILTER_TARE_ORIENTATION_COMMAND_MIP_TARE_AXES_PITCH = 0x2; ///< static const mip_filter_tare_orientation_command_mip_tare_axes MIP_FILTER_TARE_ORIENTATION_COMMAND_MIP_TARE_AXES_YAW = 0x4; ///< static const mip_filter_tare_orientation_command_mip_tare_axes MIP_FILTER_TARE_ORIENTATION_COMMAND_MIP_TARE_AXES_ALL = 0x7; -inline void insert_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self) +static inline void insert_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, const mip_filter_tare_orientation_command_mip_tare_axes self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self) +static inline void extract_mip_filter_tare_orientation_command_mip_tare_axes(microstrain_serializer* serializer, mip_filter_tare_orientation_command_mip_tare_axes* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -497,11 +499,11 @@ enum mip_filter_vehicle_dynamics_mode_command_dynamics_mode }; typedef enum mip_filter_vehicle_dynamics_mode_command_dynamics_mode mip_filter_vehicle_dynamics_mode_command_dynamics_mode; -inline void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self) +static inline void insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_command_dynamics_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self) +static inline void extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_command_dynamics_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -814,11 +816,11 @@ enum mip_filter_gnss_source_command_source }; typedef enum mip_filter_gnss_source_command_source mip_filter_gnss_source_command_source; -inline void insert_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self) +static inline void insert_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, const mip_filter_gnss_source_command_source self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self) +static inline void extract_mip_filter_gnss_source_command_source(microstrain_serializer* serializer, mip_filter_gnss_source_command_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -883,11 +885,11 @@ enum mip_filter_heading_source_command_source }; typedef enum mip_filter_heading_source_command_source mip_filter_heading_source_command_source; -inline void insert_mip_filter_heading_source_command_source(microstrain_serializer* serializer, const mip_filter_heading_source_command_source self) +static inline void insert_mip_filter_heading_source_command_source(microstrain_serializer* serializer, const mip_filter_heading_source_command_source self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_heading_source_command_source(microstrain_serializer* serializer, mip_filter_heading_source_command_source* self) +static inline void extract_mip_filter_heading_source_command_source(microstrain_serializer* serializer, mip_filter_heading_source_command_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1134,11 +1136,11 @@ enum mip_filter_altitude_aiding_command_aiding_selector }; typedef enum mip_filter_altitude_aiding_command_aiding_selector mip_filter_altitude_aiding_command_aiding_selector; -inline void insert_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self) +static inline void insert_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, const mip_filter_altitude_aiding_command_aiding_selector self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self) +static inline void extract_mip_filter_altitude_aiding_command_aiding_selector(microstrain_serializer* serializer, mip_filter_altitude_aiding_command_aiding_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1187,11 +1189,11 @@ enum mip_filter_pitch_roll_aiding_command_aiding_source }; typedef enum mip_filter_pitch_roll_aiding_command_aiding_source mip_filter_pitch_roll_aiding_command_aiding_source; -inline void insert_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self) +static inline void insert_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_command_aiding_source self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self) +static inline void extract_mip_filter_pitch_roll_aiding_command_aiding_source(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_command_aiding_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1305,6 +1307,8 @@ mip_cmd_result mip_filter_default_auto_angular_zupt(mip_interface* device); /// ///@{ +typedef struct mip_filter_commanded_zupt_command mip_filter_commanded_zupt_command; ///< No parameters (empty struct not allowed in C) + mip_cmd_result mip_filter_commanded_zupt(mip_interface* device); ///@} @@ -1315,6 +1319,8 @@ mip_cmd_result mip_filter_commanded_zupt(mip_interface* device); /// ///@{ +typedef struct mip_filter_commanded_angular_zupt_command mip_filter_commanded_angular_zupt_command; ///< No parameters (empty struct not allowed in C) + mip_cmd_result mip_filter_commanded_angular_zupt(mip_interface* device); ///@} @@ -1878,11 +1884,11 @@ enum mip_filter_aiding_measurement_enable_command_aiding_source }; typedef enum mip_filter_aiding_measurement_enable_command_aiding_source mip_filter_aiding_measurement_enable_command_aiding_source; -inline void insert_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self) +static inline void insert_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_command_aiding_source self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self) +static inline void extract_mip_filter_aiding_measurement_enable_command_aiding_source(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_command_aiding_source* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1927,6 +1933,8 @@ mip_cmd_result mip_filter_default_aiding_measurement_enable(mip_interface* devic /// ///@{ +typedef struct mip_filter_run_command mip_filter_run_command; ///< No parameters (empty struct not allowed in C) + mip_cmd_result mip_filter_run(mip_interface* device); ///@} @@ -1987,11 +1995,11 @@ static const mip_filter_initialization_configuration_command_alignment_selector static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_MAGNETOMETER = 0x04; ///< Magnetometer heading alignment (Internal magnetometer determines initial heading) static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_EXTERNAL = 0x08; ///< External heading alignment (External heading input determines heading) static const mip_filter_initialization_configuration_command_alignment_selector MIP_FILTER_INITIALIZATION_CONFIGURATION_COMMAND_ALIGNMENT_SELECTOR_ALL = 0x0F; -inline void insert_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self) +static inline void insert_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_alignment_selector self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self) +static inline void extract_mip_filter_initialization_configuration_command_alignment_selector(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_alignment_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2007,11 +2015,11 @@ enum mip_filter_initialization_configuration_command_initial_condition_source }; typedef enum mip_filter_initialization_configuration_command_initial_condition_source mip_filter_initialization_configuration_command_initial_condition_source; -inline void insert_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self) +static inline void insert_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, const mip_filter_initialization_configuration_command_initial_condition_source self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self) +static inline void extract_mip_filter_initialization_configuration_command_initial_condition_source(microstrain_serializer* serializer, mip_filter_initialization_configuration_command_initial_condition_source* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -2191,11 +2199,11 @@ enum mip_filter_ref_point_lever_arm_command_reference_point_selector }; typedef enum mip_filter_ref_point_lever_arm_command_reference_point_selector mip_filter_ref_point_lever_arm_command_reference_point_selector; -inline void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self) +static inline void insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_command_reference_point_selector self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self) +static inline void extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_command_reference_point_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); diff --git a/src/c/mip/definitions/commands_gnss.c b/src/c/mip/definitions/commands_gnss.c index 34d3e0933..b45abcfbf 100644 --- a/src/c/mip/definitions/commands_gnss.c +++ b/src/c/mip/definitions/commands_gnss.c @@ -19,6 +19,27 @@ extern "C" { // Mip Fields //////////////////////////////////////////////////////////////////////////////// +void insert_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, const mip_gnss_receiver_info_command_info* self) +{ + microstrain_insert_u8(serializer, self->receiver_id); + + microstrain_insert_u8(serializer, self->mip_data_descriptor_set); + + for(unsigned int i=0; i < 32; i++) + microstrain_insert_char(serializer, self->description[i]); + +} +void extract_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, mip_gnss_receiver_info_command_info* self) +{ + microstrain_extract_u8(serializer, &self->receiver_id); + + microstrain_extract_u8(serializer, &self->mip_data_descriptor_set); + + for(unsigned int i=0; i < 32; i++) + microstrain_extract_char(serializer, &self->description[i]); + +} + mip_cmd_result mip_gnss_receiver_info(mip_interface* device, uint8_t* num_receivers_out, uint8_t num_receivers_out_max, mip_gnss_receiver_info_command_info* receiver_info_out) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/c/mip/definitions/commands_gnss.h b/src/c/mip/definitions/commands_gnss.h index 09669c6ad..5957ceedb 100644 --- a/src/c/mip/definitions/commands_gnss.h +++ b/src/c/mip/definitions/commands_gnss.h @@ -76,6 +76,8 @@ void insert_mip_gnss_receiver_info_command_info(microstrain_serializer* serializ void extract_mip_gnss_receiver_info_command_info(microstrain_serializer* serializer, mip_gnss_receiver_info_command_info* self); +typedef struct mip_gnss_receiver_info_command mip_gnss_receiver_info_command; ///< No parameters (empty struct not allowed in C) + struct mip_gnss_receiver_info_response { uint8_t num_receivers; ///< Number of physical receivers in the device diff --git a/src/c/mip/definitions/commands_rtk.h b/src/c/mip/definitions/commands_rtk.h index e59309208..40b5d76f2 100644 --- a/src/c/mip/definitions/commands_rtk.h +++ b/src/c/mip/definitions/commands_rtk.h @@ -66,11 +66,11 @@ enum mip_media_selector }; typedef enum mip_media_selector mip_media_selector; -inline void insert_mip_media_selector(microstrain_serializer* serializer, const mip_media_selector self) +static inline void insert_mip_media_selector(microstrain_serializer* serializer, const mip_media_selector self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_media_selector(microstrain_serializer* serializer, mip_media_selector* self) +static inline void extract_mip_media_selector(microstrain_serializer* serializer, mip_media_selector* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -85,11 +85,11 @@ enum mip_led_action }; typedef enum mip_led_action mip_led_action; -inline void insert_mip_led_action(microstrain_serializer* serializer, const mip_led_action self) +static inline void insert_mip_led_action(microstrain_serializer* serializer, const mip_led_action self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_led_action(microstrain_serializer* serializer, mip_led_action* self) +static inline void extract_mip_led_action(microstrain_serializer* serializer, mip_led_action* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -120,11 +120,11 @@ static const mip_rtk_get_status_flags_command_status_flags_legacy MIP_RTK_GET_ST static const mip_rtk_get_status_flags_command_status_flags_legacy MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_LEGACY_RSRQ = 0x30000000; ///< static const mip_rtk_get_status_flags_command_status_flags_legacy MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_LEGACY_SINR = 0xC0000000; ///< static const mip_rtk_get_status_flags_command_status_flags_legacy MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_LEGACY_ALL = 0xFFFFFFFF; -inline void insert_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self) +static inline void insert_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags_legacy self) { microstrain_insert_u32(serializer, (uint32_t)(self)); } -inline void extract_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self) +static inline void extract_mip_rtk_get_status_flags_command_status_flags_legacy(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags_legacy* self) { uint32_t tmp = 0; microstrain_extract_u32(serializer, &tmp); @@ -146,11 +146,11 @@ static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FL static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_RESERVED = 0x20000000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_VERSION = 0xC0000000; ///< static const mip_rtk_get_status_flags_command_status_flags MIP_RTK_GET_STATUS_FLAGS_COMMAND_STATUS_FLAGS_ALL = 0xFFFFFFFF; -inline void insert_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self) +static inline void insert_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, const mip_rtk_get_status_flags_command_status_flags self) { microstrain_insert_u32(serializer, (uint32_t)(self)); } -inline void extract_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self) +static inline void extract_mip_rtk_get_status_flags_command_status_flags(microstrain_serializer* serializer, mip_rtk_get_status_flags_command_status_flags* self) { uint32_t tmp = 0; microstrain_extract_u32(serializer, &tmp); @@ -158,6 +158,8 @@ inline void extract_mip_rtk_get_status_flags_command_status_flags(microstrain_se } +typedef struct mip_rtk_get_status_flags_command mip_rtk_get_status_flags_command; ///< No parameters (empty struct not allowed in C) + struct mip_rtk_get_status_flags_response { mip_rtk_get_status_flags_command_status_flags flags; ///< Model number dependent. See above structures. @@ -176,6 +178,8 @@ mip_cmd_result mip_rtk_get_status_flags(mip_interface* device, mip_rtk_get_statu /// ///@{ +typedef struct mip_rtk_get_imei_command mip_rtk_get_imei_command; ///< No parameters (empty struct not allowed in C) + struct mip_rtk_get_imei_response { char IMEI[32]; @@ -194,6 +198,8 @@ mip_cmd_result mip_rtk_get_imei(mip_interface* device, char* imei_out); /// ///@{ +typedef struct mip_rtk_get_imsi_command mip_rtk_get_imsi_command; ///< No parameters (empty struct not allowed in C) + struct mip_rtk_get_imsi_response { char IMSI[32]; @@ -212,6 +218,8 @@ mip_cmd_result mip_rtk_get_imsi(mip_interface* device, char* imsi_out); /// ///@{ +typedef struct mip_rtk_get_iccid_command mip_rtk_get_iccid_command; ///< No parameters (empty struct not allowed in C) + struct mip_rtk_get_iccid_response { char ICCID[32]; @@ -237,11 +245,11 @@ enum mip_rtk_connected_device_type_command_type }; typedef enum mip_rtk_connected_device_type_command_type mip_rtk_connected_device_type_command_type; -inline void insert_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self) +static inline void insert_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, const mip_rtk_connected_device_type_command_type self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self) +static inline void extract_mip_rtk_connected_device_type_command_type(microstrain_serializer* serializer, mip_rtk_connected_device_type_command_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -281,6 +289,8 @@ mip_cmd_result mip_rtk_default_connected_device_type(mip_interface* device); /// ///@{ +typedef struct mip_rtk_get_act_code_command mip_rtk_get_act_code_command; ///< No parameters (empty struct not allowed in C) + struct mip_rtk_get_act_code_response { char ActivationCode[32]; @@ -299,6 +309,8 @@ mip_cmd_result mip_rtk_get_act_code(mip_interface* device, char* activation_code /// ///@{ +typedef struct mip_rtk_get_modem_firmware_version_command mip_rtk_get_modem_firmware_version_command; ///< No parameters (empty struct not allowed in C) + struct mip_rtk_get_modem_firmware_version_response { char ModemFirmwareVersion[32]; @@ -318,6 +330,8 @@ mip_cmd_result mip_rtk_get_modem_firmware_version(mip_interface* device, char* m /// ///@{ +typedef struct mip_rtk_get_rssi_command mip_rtk_get_rssi_command; ///< No parameters (empty struct not allowed in C) + struct mip_rtk_get_rssi_response { bool valid; @@ -345,11 +359,11 @@ static const mip_rtk_service_status_command_service_flags MIP_RTK_SERVICE_STATUS static const mip_rtk_service_status_command_service_flags MIP_RTK_SERVICE_STATUS_COMMAND_SERVICE_FLAGS_CORRECTIONS_UNAVAILABLE = 0x02; ///< static const mip_rtk_service_status_command_service_flags MIP_RTK_SERVICE_STATUS_COMMAND_SERVICE_FLAGS_RESERVED = 0xFC; ///< static const mip_rtk_service_status_command_service_flags MIP_RTK_SERVICE_STATUS_COMMAND_SERVICE_FLAGS_ALL = 0xFF; -inline void insert_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self) +static inline void insert_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, const mip_rtk_service_status_command_service_flags self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self) +static inline void extract_mip_rtk_service_status_command_service_flags(microstrain_serializer* serializer, mip_rtk_service_status_command_service_flags* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -432,6 +446,8 @@ mip_cmd_result mip_rtk_led_control(mip_interface* device, const uint8_t* primary /// ///@{ +typedef struct mip_rtk_modem_hard_reset_command mip_rtk_modem_hard_reset_command; ///< No parameters (empty struct not allowed in C) + mip_cmd_result mip_rtk_modem_hard_reset(mip_interface* device); ///@} diff --git a/src/c/mip/definitions/data_filter.h b/src/c/mip/definitions/data_filter.h index b1e0bd50d..591778eb9 100644 --- a/src/c/mip/definitions/data_filter.h +++ b/src/c/mip/definitions/data_filter.h @@ -113,11 +113,11 @@ enum mip_filter_mode }; typedef enum mip_filter_mode mip_filter_mode; -inline void insert_mip_filter_mode(microstrain_serializer* serializer, const mip_filter_mode self) +static inline void insert_mip_filter_mode(microstrain_serializer* serializer, const mip_filter_mode self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_filter_mode(microstrain_serializer* serializer, mip_filter_mode* self) +static inline void extract_mip_filter_mode(microstrain_serializer* serializer, mip_filter_mode* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -133,11 +133,11 @@ enum mip_filter_dynamics_mode }; typedef enum mip_filter_dynamics_mode mip_filter_dynamics_mode; -inline void insert_mip_filter_dynamics_mode(microstrain_serializer* serializer, const mip_filter_dynamics_mode self) +static inline void insert_mip_filter_dynamics_mode(microstrain_serializer* serializer, const mip_filter_dynamics_mode self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_filter_dynamics_mode(microstrain_serializer* serializer, mip_filter_dynamics_mode* self) +static inline void extract_mip_filter_dynamics_mode(microstrain_serializer* serializer, mip_filter_dynamics_mode* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -175,11 +175,11 @@ static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_MOUNTING_TRANSF static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_TIME_SYNC_WARNING = 0x0400; ///< No time synchronization pulse detected static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_GQ7_SOLUTION_ERROR = 0xF000; ///< Filter computation warning flags. If any bits 12-15 are set, and all filter outputs will be invalid. static const mip_filter_status_flags MIP_FILTER_STATUS_FLAGS_ALL = 0xFFFF; -inline void insert_mip_filter_status_flags(microstrain_serializer* serializer, const mip_filter_status_flags self) +static inline void insert_mip_filter_status_flags(microstrain_serializer* serializer, const mip_filter_status_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_filter_status_flags(microstrain_serializer* serializer, mip_filter_status_flags* self) +static inline void extract_mip_filter_status_flags(microstrain_serializer* serializer, mip_filter_status_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -203,11 +203,11 @@ enum mip_filter_aiding_measurement_type }; typedef enum mip_filter_aiding_measurement_type mip_filter_aiding_measurement_type; -inline void insert_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self) +static inline void insert_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, const mip_filter_aiding_measurement_type self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self) +static inline void extract_mip_filter_aiding_measurement_type(microstrain_serializer* serializer, mip_filter_aiding_measurement_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -223,11 +223,11 @@ static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_S static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_CONFIGURATION_ERROR = 0x10; ///< static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_MAX_NUM_MEAS_EXCEEDED = 0x20; ///< static const mip_filter_measurement_indicator MIP_FILTER_MEASUREMENT_INDICATOR_ALL = 0x3F; -inline void insert_mip_filter_measurement_indicator(microstrain_serializer* serializer, const mip_filter_measurement_indicator self) +static inline void insert_mip_filter_measurement_indicator(microstrain_serializer* serializer, const mip_filter_measurement_indicator self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_measurement_indicator(microstrain_serializer* serializer, mip_filter_measurement_indicator* self) +static inline void extract_mip_filter_measurement_indicator(microstrain_serializer* serializer, mip_filter_measurement_indicator* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -253,11 +253,11 @@ static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_BEI_B3 static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_NO_FIX = 0x4000; ///< If 1, this GNSS module is reporting no position fix static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_CONFIG_ERROR = 0x8000; ///< If 1, there is likely an issue with the antenna offset for this GNSS module static const mip_gnss_aid_status_flags MIP_GNSS_AID_STATUS_FLAGS_ALL = 0xFFFF; -inline void insert_mip_gnss_aid_status_flags(microstrain_serializer* serializer, const mip_gnss_aid_status_flags self) +static inline void insert_mip_gnss_aid_status_flags(microstrain_serializer* serializer, const mip_gnss_aid_status_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_aid_status_flags(microstrain_serializer* serializer, mip_gnss_aid_status_flags* self) +static inline void extract_mip_gnss_aid_status_flags(microstrain_serializer* serializer, mip_gnss_aid_status_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -729,11 +729,11 @@ enum mip_filter_heading_update_state_data_heading_source }; typedef enum mip_filter_heading_update_state_data_heading_source mip_filter_heading_update_state_data_heading_source; -inline void insert_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self) +static inline void insert_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, const mip_filter_heading_update_state_data_heading_source self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self) +static inline void extract_mip_filter_heading_update_state_data_heading_source(microstrain_serializer* serializer, mip_filter_heading_update_state_data_heading_source* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1280,11 +1280,11 @@ enum mip_filter_head_aid_status_data_heading_aid_type }; typedef enum mip_filter_head_aid_status_data_heading_aid_type mip_filter_head_aid_status_data_heading_aid_type; -inline void insert_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self) +static inline void insert_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, const mip_filter_head_aid_status_data_heading_aid_type self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self) +static inline void extract_mip_filter_head_aid_status_data_heading_aid_type(microstrain_serializer* serializer, mip_filter_head_aid_status_data_heading_aid_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1483,11 +1483,11 @@ enum mip_filter_gnss_dual_antenna_status_data_fix_type }; typedef enum mip_filter_gnss_dual_antenna_status_data_fix_type mip_filter_gnss_dual_antenna_status_data_fix_type; -inline void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self) +static inline void insert_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_fix_type self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self) +static inline void extract_mip_filter_gnss_dual_antenna_status_data_fix_type(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_fix_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1500,11 +1500,11 @@ static const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags static const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_DUAL_ANTENNA_STATUS_FLAGS_RCV_2_DATA_VALID = 0x0002; ///< static const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_DUAL_ANTENNA_STATUS_FLAGS_ANTENNA_OFFSETS_VALID = 0x0004; ///< static const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags MIP_FILTER_GNSS_DUAL_ANTENNA_STATUS_DATA_DUAL_ANTENNA_STATUS_FLAGS_ALL = 0x0007; -inline void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self) +static inline void insert_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, const mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self) +static inline void extract_mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags(microstrain_serializer* serializer, mip_filter_gnss_dual_antenna_status_data_dual_antenna_status_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/c/mip/definitions/data_gnss.h b/src/c/mip/definitions/data_gnss.h index 7c6cfc9dc..9be66b32f 100644 --- a/src/c/mip/definitions/data_gnss.h +++ b/src/c/mip/definitions/data_gnss.h @@ -83,11 +83,11 @@ enum mip_gnss_constellation_id }; typedef enum mip_gnss_constellation_id mip_gnss_constellation_id; -inline void insert_mip_gnss_constellation_id(microstrain_serializer* serializer, const mip_gnss_constellation_id self) +static inline void insert_mip_gnss_constellation_id(microstrain_serializer* serializer, const mip_gnss_constellation_id self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_constellation_id(microstrain_serializer* serializer, mip_gnss_constellation_id* self) +static inline void extract_mip_gnss_constellation_id(microstrain_serializer* serializer, mip_gnss_constellation_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -164,11 +164,11 @@ enum mip_gnss_signal_id }; typedef enum mip_gnss_signal_id mip_gnss_signal_id; -inline void insert_mip_gnss_signal_id(microstrain_serializer* serializer, const mip_gnss_signal_id self) +static inline void insert_mip_gnss_signal_id(microstrain_serializer* serializer, const mip_gnss_signal_id self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_signal_id(microstrain_serializer* serializer, mip_gnss_signal_id* self) +static inline void extract_mip_gnss_signal_id(microstrain_serializer* serializer, mip_gnss_signal_id* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -185,11 +185,11 @@ enum mip_sbas_system }; typedef enum mip_sbas_system mip_sbas_system; -inline void insert_mip_sbas_system(microstrain_serializer* serializer, const mip_sbas_system self) +static inline void insert_mip_sbas_system(microstrain_serializer* serializer, const mip_sbas_system self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_sbas_system(microstrain_serializer* serializer, mip_sbas_system* self) +static inline void extract_mip_sbas_system(microstrain_serializer* serializer, mip_sbas_system* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -218,11 +218,11 @@ static const mip_gnss_pos_llh_data_valid_flags MIP_GNSS_POS_LLH_DATA_VALID_FLAGS static const mip_gnss_pos_llh_data_valid_flags MIP_GNSS_POS_LLH_DATA_VALID_FLAGS_VERTICAL_ACCURACY = 0x0010; ///< static const mip_gnss_pos_llh_data_valid_flags MIP_GNSS_POS_LLH_DATA_VALID_FLAGS_FLAGS = 0x001F; ///< static const mip_gnss_pos_llh_data_valid_flags MIP_GNSS_POS_LLH_DATA_VALID_FLAGS_ALL = 0x001F; -inline void insert_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self) +static inline void insert_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_llh_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self) +static inline void extract_mip_gnss_pos_llh_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_llh_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -261,11 +261,11 @@ static const mip_gnss_pos_ecef_data_valid_flags MIP_GNSS_POS_ECEF_DATA_VALID_FLA static const mip_gnss_pos_ecef_data_valid_flags MIP_GNSS_POS_ECEF_DATA_VALID_FLAGS_POSITION_ACCURACY = 0x0002; ///< static const mip_gnss_pos_ecef_data_valid_flags MIP_GNSS_POS_ECEF_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_pos_ecef_data_valid_flags MIP_GNSS_POS_ECEF_DATA_VALID_FLAGS_ALL = 0x0003; -inline void insert_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self) +static inline void insert_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_pos_ecef_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self) +static inline void extract_mip_gnss_pos_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_pos_ecef_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -304,11 +304,11 @@ static const mip_gnss_vel_ned_data_valid_flags MIP_GNSS_VEL_NED_DATA_VALID_FLAGS static const mip_gnss_vel_ned_data_valid_flags MIP_GNSS_VEL_NED_DATA_VALID_FLAGS_HEADING_ACCURACY = 0x0020; ///< static const mip_gnss_vel_ned_data_valid_flags MIP_GNSS_VEL_NED_DATA_VALID_FLAGS_FLAGS = 0x003F; ///< static const mip_gnss_vel_ned_data_valid_flags MIP_GNSS_VEL_NED_DATA_VALID_FLAGS_ALL = 0x003F; -inline void insert_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self) +static inline void insert_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ned_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self) +static inline void extract_mip_gnss_vel_ned_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ned_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -347,11 +347,11 @@ static const mip_gnss_vel_ecef_data_valid_flags MIP_GNSS_VEL_ECEF_DATA_VALID_FLA static const mip_gnss_vel_ecef_data_valid_flags MIP_GNSS_VEL_ECEF_DATA_VALID_FLAGS_VELOCITY_ACCURACY = 0x0002; ///< static const mip_gnss_vel_ecef_data_valid_flags MIP_GNSS_VEL_ECEF_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_vel_ecef_data_valid_flags MIP_GNSS_VEL_ECEF_DATA_VALID_FLAGS_ALL = 0x0003; -inline void insert_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self) +static inline void insert_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_vel_ecef_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self) +static inline void extract_mip_gnss_vel_ecef_data_valid_flags(microstrain_serializer* serializer, mip_gnss_vel_ecef_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -391,11 +391,11 @@ static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_NDOP = static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_EDOP = 0x0040; ///< static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_FLAGS = 0x007F; ///< static const mip_gnss_dop_data_valid_flags MIP_GNSS_DOP_DATA_VALID_FLAGS_ALL = 0x007F; -inline void insert_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self) +static inline void insert_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dop_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self) +static inline void extract_mip_gnss_dop_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dop_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -435,11 +435,11 @@ static const mip_gnss_utc_time_data_valid_flags MIP_GNSS_UTC_TIME_DATA_VALID_FLA static const mip_gnss_utc_time_data_valid_flags MIP_GNSS_UTC_TIME_DATA_VALID_FLAGS_LEAP_SECONDS_KNOWN = 0x0002; ///< static const mip_gnss_utc_time_data_valid_flags MIP_GNSS_UTC_TIME_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_utc_time_data_valid_flags MIP_GNSS_UTC_TIME_DATA_VALID_FLAGS_ALL = 0x0003; -inline void insert_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self) +static inline void insert_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_utc_time_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self) +static inline void extract_mip_gnss_utc_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_utc_time_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -479,11 +479,11 @@ static const mip_gnss_gps_time_data_valid_flags MIP_GNSS_GPS_TIME_DATA_VALID_FLA static const mip_gnss_gps_time_data_valid_flags MIP_GNSS_GPS_TIME_DATA_VALID_FLAGS_WEEK_NUMBER = 0x0002; ///< static const mip_gnss_gps_time_data_valid_flags MIP_GNSS_GPS_TIME_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_gps_time_data_valid_flags MIP_GNSS_GPS_TIME_DATA_VALID_FLAGS_ALL = 0x0003; -inline void insert_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self) +static inline void insert_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_time_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self) +static inline void extract_mip_gnss_gps_time_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_time_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -519,11 +519,11 @@ static const mip_gnss_clock_info_data_valid_flags MIP_GNSS_CLOCK_INFO_DATA_VALID static const mip_gnss_clock_info_data_valid_flags MIP_GNSS_CLOCK_INFO_DATA_VALID_FLAGS_ACCURACY_ESTIMATE = 0x0004; ///< static const mip_gnss_clock_info_data_valid_flags MIP_GNSS_CLOCK_INFO_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_clock_info_data_valid_flags MIP_GNSS_CLOCK_INFO_DATA_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self) +static inline void insert_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self) +static inline void extract_mip_gnss_clock_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -566,11 +566,11 @@ enum mip_gnss_fix_info_data_fix_type }; typedef enum mip_gnss_fix_info_data_fix_type mip_gnss_fix_info_data_fix_type; -inline void insert_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self) +static inline void insert_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_type self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self) +static inline void extract_mip_gnss_fix_info_data_fix_type(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_type* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -582,11 +582,11 @@ static const mip_gnss_fix_info_data_fix_flags MIP_GNSS_FIX_INFO_DATA_FIX_FLAGS_N static const mip_gnss_fix_info_data_fix_flags MIP_GNSS_FIX_INFO_DATA_FIX_FLAGS_SBAS_USED = 0x0001; ///< static const mip_gnss_fix_info_data_fix_flags MIP_GNSS_FIX_INFO_DATA_FIX_FLAGS_DGNSS_USED = 0x0002; ///< static const mip_gnss_fix_info_data_fix_flags MIP_GNSS_FIX_INFO_DATA_FIX_FLAGS_ALL = 0x0003; -inline void insert_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self) +static inline void insert_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_fix_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self) +static inline void extract_mip_gnss_fix_info_data_fix_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_fix_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -600,11 +600,11 @@ static const mip_gnss_fix_info_data_valid_flags MIP_GNSS_FIX_INFO_DATA_VALID_FLA static const mip_gnss_fix_info_data_valid_flags MIP_GNSS_FIX_INFO_DATA_VALID_FLAGS_FIX_FLAGS = 0x0004; ///< static const mip_gnss_fix_info_data_valid_flags MIP_GNSS_FIX_INFO_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_fix_info_data_valid_flags MIP_GNSS_FIX_INFO_DATA_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self) +static inline void insert_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_fix_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self) +static inline void extract_mip_gnss_fix_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_fix_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -641,11 +641,11 @@ static const mip_gnss_sv_info_data_svflags MIP_GNSS_SV_INFO_DATA_SVFLAGS_NONE static const mip_gnss_sv_info_data_svflags MIP_GNSS_SV_INFO_DATA_SVFLAGS_USED_FOR_NAVIGATION = 0x0001; ///< static const mip_gnss_sv_info_data_svflags MIP_GNSS_SV_INFO_DATA_SVFLAGS_HEALTHY = 0x0002; ///< static const mip_gnss_sv_info_data_svflags MIP_GNSS_SV_INFO_DATA_SVFLAGS_ALL = 0x0003; -inline void insert_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self) +static inline void insert_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_svflags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self) +static inline void extract_mip_gnss_sv_info_data_svflags(microstrain_serializer* serializer, mip_gnss_sv_info_data_svflags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -662,11 +662,11 @@ static const mip_gnss_sv_info_data_valid_flags MIP_GNSS_SV_INFO_DATA_VALID_FLAGS static const mip_gnss_sv_info_data_valid_flags MIP_GNSS_SV_INFO_DATA_VALID_FLAGS_SV_FLAGS = 0x0020; ///< static const mip_gnss_sv_info_data_valid_flags MIP_GNSS_SV_INFO_DATA_VALID_FLAGS_FLAGS = 0x003F; ///< static const mip_gnss_sv_info_data_valid_flags MIP_GNSS_SV_INFO_DATA_VALID_FLAGS_ALL = 0x003F; -inline void insert_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self) +static inline void insert_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sv_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self) +static inline void extract_mip_gnss_sv_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sv_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -707,11 +707,11 @@ enum mip_gnss_hw_status_data_receiver_state }; typedef enum mip_gnss_hw_status_data_receiver_state mip_gnss_hw_status_data_receiver_state; -inline void insert_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self) +static inline void insert_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_receiver_state self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self) +static inline void extract_mip_gnss_hw_status_data_receiver_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_receiver_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -728,11 +728,11 @@ enum mip_gnss_hw_status_data_antenna_state }; typedef enum mip_gnss_hw_status_data_antenna_state mip_gnss_hw_status_data_antenna_state; -inline void insert_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self) +static inline void insert_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_state self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self) +static inline void extract_mip_gnss_hw_status_data_antenna_state(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -747,11 +747,11 @@ enum mip_gnss_hw_status_data_antenna_power }; typedef enum mip_gnss_hw_status_data_antenna_power mip_gnss_hw_status_data_antenna_power; -inline void insert_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self) +static inline void insert_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, const mip_gnss_hw_status_data_antenna_power self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self) +static inline void extract_mip_gnss_hw_status_data_antenna_power(microstrain_serializer* serializer, mip_gnss_hw_status_data_antenna_power* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -765,11 +765,11 @@ static const mip_gnss_hw_status_data_valid_flags MIP_GNSS_HW_STATUS_DATA_VALID_F static const mip_gnss_hw_status_data_valid_flags MIP_GNSS_HW_STATUS_DATA_VALID_FLAGS_ANTENNA_POWER = 0x0004; ///< static const mip_gnss_hw_status_data_valid_flags MIP_GNSS_HW_STATUS_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_hw_status_data_valid_flags MIP_GNSS_HW_STATUS_DATA_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self) +static inline void insert_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_hw_status_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self) +static inline void extract_mip_gnss_hw_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_hw_status_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -819,11 +819,11 @@ static const mip_gnss_dgps_info_data_valid_flags MIP_GNSS_DGPS_INFO_DATA_VALID_F static const mip_gnss_dgps_info_data_valid_flags MIP_GNSS_DGPS_INFO_DATA_VALID_FLAGS_NUM_CHANNELS = 0x0008; ///< static const mip_gnss_dgps_info_data_valid_flags MIP_GNSS_DGPS_INFO_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_dgps_info_data_valid_flags MIP_GNSS_DGPS_INFO_DATA_VALID_FLAGS_ALL = 0x000F; -inline void insert_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self) +static inline void insert_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self) +static inline void extract_mip_gnss_dgps_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -864,11 +864,11 @@ static const mip_gnss_dgps_channel_data_valid_flags MIP_GNSS_DGPS_CHANNEL_DATA_V static const mip_gnss_dgps_channel_data_valid_flags MIP_GNSS_DGPS_CHANNEL_DATA_VALID_FLAGS_RANGE_RATE_CORRECTION = 0x0008; ///< static const mip_gnss_dgps_channel_data_valid_flags MIP_GNSS_DGPS_CHANNEL_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_dgps_channel_data_valid_flags MIP_GNSS_DGPS_CHANNEL_DATA_VALID_FLAGS_ALL = 0x000F; -inline void insert_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self) +static inline void insert_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_dgps_channel_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self) +static inline void extract_mip_gnss_dgps_channel_data_valid_flags(microstrain_serializer* serializer, mip_gnss_dgps_channel_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -909,11 +909,11 @@ static const mip_gnss_clock_info_2_data_valid_flags MIP_GNSS_CLOCK_INFO_2_DATA_V static const mip_gnss_clock_info_2_data_valid_flags MIP_GNSS_CLOCK_INFO_2_DATA_VALID_FLAGS_DRIFT_ACCURACY = 0x0008; ///< static const mip_gnss_clock_info_2_data_valid_flags MIP_GNSS_CLOCK_INFO_2_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_clock_info_2_data_valid_flags MIP_GNSS_CLOCK_INFO_2_DATA_VALID_FLAGS_ALL = 0x000F; -inline void insert_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self) +static inline void insert_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_clock_info_2_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self) +static inline void extract_mip_gnss_clock_info_2_data_valid_flags(microstrain_serializer* serializer, mip_gnss_clock_info_2_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -948,11 +948,11 @@ typedef uint16_t mip_gnss_gps_leap_seconds_data_valid_flags; static const mip_gnss_gps_leap_seconds_data_valid_flags MIP_GNSS_GPS_LEAP_SECONDS_DATA_VALID_FLAGS_NONE = 0x0000; static const mip_gnss_gps_leap_seconds_data_valid_flags MIP_GNSS_GPS_LEAP_SECONDS_DATA_VALID_FLAGS_LEAP_SECONDS = 0x0002; ///< static const mip_gnss_gps_leap_seconds_data_valid_flags MIP_GNSS_GPS_LEAP_SECONDS_DATA_VALID_FLAGS_ALL = 0x0002; -inline void insert_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self) +static inline void insert_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_leap_seconds_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self) +static inline void extract_mip_gnss_gps_leap_seconds_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_leap_seconds_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -987,11 +987,11 @@ static const mip_gnss_sbas_info_data_sbas_status MIP_GNSS_SBAS_INFO_DATA_SBAS_ST static const mip_gnss_sbas_info_data_sbas_status MIP_GNSS_SBAS_INFO_DATA_SBAS_STATUS_INTEGRITY_AVAILABLE = 0x04; ///< static const mip_gnss_sbas_info_data_sbas_status MIP_GNSS_SBAS_INFO_DATA_SBAS_STATUS_TEST_MODE = 0x08; ///< static const mip_gnss_sbas_info_data_sbas_status MIP_GNSS_SBAS_INFO_DATA_SBAS_STATUS_ALL = 0x0F; -inline void insert_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self) +static inline void insert_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_sbas_status self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self) +static inline void extract_mip_gnss_sbas_info_data_sbas_status(microstrain_serializer* serializer, mip_gnss_sbas_info_data_sbas_status* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1008,11 +1008,11 @@ static const mip_gnss_sbas_info_data_valid_flags MIP_GNSS_SBAS_INFO_DATA_VALID_F static const mip_gnss_sbas_info_data_valid_flags MIP_GNSS_SBAS_INFO_DATA_VALID_FLAGS_SBAS_STATUS = 0x0020; ///< static const mip_gnss_sbas_info_data_valid_flags MIP_GNSS_SBAS_INFO_DATA_VALID_FLAGS_FLAGS = 0x003F; ///< static const mip_gnss_sbas_info_data_valid_flags MIP_GNSS_SBAS_INFO_DATA_VALID_FLAGS_ALL = 0x003F; -inline void insert_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self) +static inline void insert_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self) +static inline void extract_mip_gnss_sbas_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1074,11 +1074,11 @@ static const mip_gnss_sbas_correction_data_valid_flags MIP_GNSS_SBAS_CORRECTION_ static const mip_gnss_sbas_correction_data_valid_flags MIP_GNSS_SBAS_CORRECTION_DATA_VALID_FLAGS_IONO_CORRECTION = 0x0004; ///< static const mip_gnss_sbas_correction_data_valid_flags MIP_GNSS_SBAS_CORRECTION_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_sbas_correction_data_valid_flags MIP_GNSS_SBAS_CORRECTION_DATA_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self) +static inline void insert_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_sbas_correction_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self) +static inline void extract_mip_gnss_sbas_correction_data_valid_flags(microstrain_serializer* serializer, mip_gnss_sbas_correction_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1123,11 +1123,11 @@ enum mip_gnss_rf_error_detection_data_rfband }; typedef enum mip_gnss_rf_error_detection_data_rfband mip_gnss_rf_error_detection_data_rfband; -inline void insert_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self) +static inline void insert_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_rfband self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self) +static inline void extract_mip_gnss_rf_error_detection_data_rfband(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_rfband* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1143,11 +1143,11 @@ enum mip_gnss_rf_error_detection_data_jamming_state }; typedef enum mip_gnss_rf_error_detection_data_jamming_state mip_gnss_rf_error_detection_data_jamming_state; -inline void insert_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self) +static inline void insert_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_jamming_state self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self) +static inline void extract_mip_gnss_rf_error_detection_data_jamming_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_jamming_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1163,11 +1163,11 @@ enum mip_gnss_rf_error_detection_data_spoofing_state }; typedef enum mip_gnss_rf_error_detection_data_spoofing_state mip_gnss_rf_error_detection_data_spoofing_state; -inline void insert_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self) +static inline void insert_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_spoofing_state self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self) +static inline void extract_mip_gnss_rf_error_detection_data_spoofing_state(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_spoofing_state* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1181,11 +1181,11 @@ static const mip_gnss_rf_error_detection_data_valid_flags MIP_GNSS_RF_ERROR_DETE static const mip_gnss_rf_error_detection_data_valid_flags MIP_GNSS_RF_ERROR_DETECTION_DATA_VALID_FLAGS_SPOOFING_STATE = 0x0004; ///< static const mip_gnss_rf_error_detection_data_valid_flags MIP_GNSS_RF_ERROR_DETECTION_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< static const mip_gnss_rf_error_detection_data_valid_flags MIP_GNSS_RF_ERROR_DETECTION_DATA_VALID_FLAGS_ALL = 0x0007; -inline void insert_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self) +static inline void insert_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rf_error_detection_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self) +static inline void extract_mip_gnss_rf_error_detection_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rf_error_detection_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1230,11 +1230,11 @@ static const mip_gnss_base_station_info_data_indicator_flags MIP_GNSS_BASE_STATI static const mip_gnss_base_station_info_data_indicator_flags MIP_GNSS_BASE_STATION_INFO_DATA_INDICATOR_FLAGS_QUARTER_CYCLE_BIT2 = 0x0080; ///< static const mip_gnss_base_station_info_data_indicator_flags MIP_GNSS_BASE_STATION_INFO_DATA_INDICATOR_FLAGS_QUARTER_CYCLE_BITS = 0x00C0; ///< static const mip_gnss_base_station_info_data_indicator_flags MIP_GNSS_BASE_STATION_INFO_DATA_INDICATOR_FLAGS_ALL = 0x00FF; -inline void insert_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self) +static inline void insert_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_indicator_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self) +static inline void extract_mip_gnss_base_station_info_data_indicator_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_indicator_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1251,11 +1251,11 @@ static const mip_gnss_base_station_info_data_valid_flags MIP_GNSS_BASE_STATION_I static const mip_gnss_base_station_info_data_valid_flags MIP_GNSS_BASE_STATION_INFO_DATA_VALID_FLAGS_INDICATORS = 0x0020; ///< static const mip_gnss_base_station_info_data_valid_flags MIP_GNSS_BASE_STATION_INFO_DATA_VALID_FLAGS_FLAGS = 0x003F; ///< static const mip_gnss_base_station_info_data_valid_flags MIP_GNSS_BASE_STATION_INFO_DATA_VALID_FLAGS_ALL = 0x003F; -inline void insert_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self) +static inline void insert_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_base_station_info_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self) +static inline void extract_mip_gnss_base_station_info_data_valid_flags(microstrain_serializer* serializer, mip_gnss_base_station_info_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1299,11 +1299,11 @@ static const mip_gnss_rtk_corrections_status_data_valid_flags MIP_GNSS_RTK_CORRE static const mip_gnss_rtk_corrections_status_data_valid_flags MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_VALID_FLAGS_BEIDOU_LATENCY = 0x0080; ///< static const mip_gnss_rtk_corrections_status_data_valid_flags MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_VALID_FLAGS_FLAGS = 0x00FF; ///< static const mip_gnss_rtk_corrections_status_data_valid_flags MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_VALID_FLAGS_ALL = 0x00FF; -inline void insert_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self) +static inline void insert_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self) +static inline void extract_mip_gnss_rtk_corrections_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1322,11 +1322,11 @@ static const mip_gnss_rtk_corrections_status_data_epoch_status MIP_GNSS_RTK_CORR static const mip_gnss_rtk_corrections_status_data_epoch_status MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_EPOCH_STATUS_USING_GLONASS_MSM_MESSAGES = 0x0080; ///< Using MSM messages for GLONASS corrections instead of RTCM messages 1009-1012 static const mip_gnss_rtk_corrections_status_data_epoch_status MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_EPOCH_STATUS_DONGLE_STATUS_READ_FAILED = 0x0100; ///< A read of the dongle status was attempted, but failed static const mip_gnss_rtk_corrections_status_data_epoch_status MIP_GNSS_RTK_CORRECTIONS_STATUS_DATA_EPOCH_STATUS_ALL = 0x01FF; -inline void insert_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self) +static inline void insert_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, const mip_gnss_rtk_corrections_status_data_epoch_status self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self) +static inline void extract_mip_gnss_rtk_corrections_status_data_epoch_status(microstrain_serializer* serializer, mip_gnss_rtk_corrections_status_data_epoch_status* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1373,11 +1373,11 @@ static const mip_gnss_satellite_status_data_valid_flags MIP_GNSS_SATELLITE_STATU static const mip_gnss_satellite_status_data_valid_flags MIP_GNSS_SATELLITE_STATUS_DATA_VALID_FLAGS_HEALTH = 0x0040; ///< static const mip_gnss_satellite_status_data_valid_flags MIP_GNSS_SATELLITE_STATUS_DATA_VALID_FLAGS_FLAGS = 0x007F; ///< static const mip_gnss_satellite_status_data_valid_flags MIP_GNSS_SATELLITE_STATUS_DATA_VALID_FLAGS_ALL = 0x007F; -inline void insert_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self) +static inline void insert_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_satellite_status_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self) +static inline void extract_mip_gnss_satellite_status_data_valid_flags(microstrain_serializer* serializer, mip_gnss_satellite_status_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1424,11 +1424,11 @@ enum mip_gnss_raw_data_gnss_signal_quality }; typedef enum mip_gnss_raw_data_gnss_signal_quality mip_gnss_raw_data_gnss_signal_quality; -inline void insert_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self) +static inline void insert_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, const mip_gnss_raw_data_gnss_signal_quality self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -inline void extract_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self) +static inline void extract_mip_gnss_raw_data_gnss_signal_quality(microstrain_serializer* serializer, mip_gnss_raw_data_gnss_signal_quality* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -1455,11 +1455,11 @@ static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_DOPPLER static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_LOCK_TIME = 0x8000; ///< static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_FLAGS = 0xFFFF; ///< static const mip_gnss_raw_data_valid_flags MIP_GNSS_RAW_DATA_VALID_FLAGS_ALL = 0xFFFF; -inline void insert_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self) +static inline void insert_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_raw_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self) +static inline void extract_mip_gnss_raw_data_valid_flags(microstrain_serializer* serializer, mip_gnss_raw_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1510,11 +1510,11 @@ static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_MODERN_DATA = 0x0002; ///< static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0003; -inline void insert_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) +static inline void insert_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self) +static inline void extract_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1580,11 +1580,11 @@ static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEME static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_MODERN_DATA = 0x0002; ///< static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0003; -inline void insert_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) +static inline void insert_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self) +static inline void extract_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1649,11 +1649,11 @@ static const mip_gnss_glo_ephemeris_data_valid_flags MIP_GNSS_GLO_EPHEMERIS_DATA static const mip_gnss_glo_ephemeris_data_valid_flags MIP_GNSS_GLO_EPHEMERIS_DATA_VALID_FLAGS_EPHEMERIS = 0x0001; ///< static const mip_gnss_glo_ephemeris_data_valid_flags MIP_GNSS_GLO_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0001; ///< static const mip_gnss_glo_ephemeris_data_valid_flags MIP_GNSS_GLO_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0001; -inline void insert_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self) +static inline void insert_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_glo_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self) +static inline void extract_mip_gnss_glo_ephemeris_data_valid_flags(microstrain_serializer* serializer, mip_gnss_glo_ephemeris_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1712,11 +1712,11 @@ static const mip_gnss_gps_iono_corr_data_valid_flags MIP_GNSS_GPS_IONO_CORR_DATA static const mip_gnss_gps_iono_corr_data_valid_flags MIP_GNSS_GPS_IONO_CORR_DATA_VALID_FLAGS_BETA = 0x0008; ///< static const mip_gnss_gps_iono_corr_data_valid_flags MIP_GNSS_GPS_IONO_CORR_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_gps_iono_corr_data_valid_flags MIP_GNSS_GPS_IONO_CORR_DATA_VALID_FLAGS_ALL = 0x000F; -inline void insert_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self) +static inline void insert_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_iono_corr_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self) +static inline void extract_mip_gnss_gps_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_gps_iono_corr_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -1755,11 +1755,11 @@ static const mip_gnss_galileo_iono_corr_data_valid_flags MIP_GNSS_GALILEO_IONO_C static const mip_gnss_galileo_iono_corr_data_valid_flags MIP_GNSS_GALILEO_IONO_CORR_DATA_VALID_FLAGS_DISTURBANCE_FLAGS = 0x0008; ///< static const mip_gnss_galileo_iono_corr_data_valid_flags MIP_GNSS_GALILEO_IONO_CORR_DATA_VALID_FLAGS_FLAGS = 0x000F; ///< static const mip_gnss_galileo_iono_corr_data_valid_flags MIP_GNSS_GALILEO_IONO_CORR_DATA_VALID_FLAGS_ALL = 0x000F; -inline void insert_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self) +static inline void insert_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_iono_corr_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self) +static inline void extract_mip_gnss_galileo_iono_corr_data_valid_flags(microstrain_serializer* serializer, mip_gnss_galileo_iono_corr_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/c/mip/definitions/data_sensor.h b/src/c/mip/definitions/data_sensor.h index 127524b54..a6aac295e 100644 --- a/src/c/mip/definitions/data_sensor.h +++ b/src/c/mip/definitions/data_sensor.h @@ -443,11 +443,11 @@ static const mip_sensor_gps_timestamp_data_valid_flags MIP_SENSOR_GPS_TIMESTAMP_ static const mip_sensor_gps_timestamp_data_valid_flags MIP_SENSOR_GPS_TIMESTAMP_DATA_VALID_FLAGS_TOW_VALID = 0x0008; ///< True if the time of week is valid. static const mip_sensor_gps_timestamp_data_valid_flags MIP_SENSOR_GPS_TIMESTAMP_DATA_VALID_FLAGS_WEEK_NUMBER_VALID = 0x0010; ///< True if the week number is valid. static const mip_sensor_gps_timestamp_data_valid_flags MIP_SENSOR_GPS_TIMESTAMP_DATA_VALID_FLAGS_ALL = 0x001F; -inline void insert_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self) +static inline void insert_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_sensor_gps_timestamp_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self) +static inline void extract_mip_sensor_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_sensor_gps_timestamp_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -560,11 +560,11 @@ static const mip_sensor_overrange_status_data_status MIP_SENSOR_OVERRANGE_STATUS static const mip_sensor_overrange_status_data_status MIP_SENSOR_OVERRANGE_STATUS_DATA_STATUS_MAG_Z = 0x0400; ///< static const mip_sensor_overrange_status_data_status MIP_SENSOR_OVERRANGE_STATUS_DATA_STATUS_PRESS = 0x1000; ///< static const mip_sensor_overrange_status_data_status MIP_SENSOR_OVERRANGE_STATUS_DATA_STATUS_ALL = 0x1777; -inline void insert_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self) +static inline void insert_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, const mip_sensor_overrange_status_data_status self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self) +static inline void extract_mip_sensor_overrange_status_data_status(microstrain_serializer* serializer, mip_sensor_overrange_status_data_status* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/c/mip/definitions/data_shared.h b/src/c/mip/definitions/data_shared.h index fef1f95b0..1149c43bf 100644 --- a/src/c/mip/definitions/data_shared.h +++ b/src/c/mip/definitions/data_shared.h @@ -136,11 +136,11 @@ static const mip_shared_gps_timestamp_data_valid_flags MIP_SHARED_GPS_TIMESTAMP_ static const mip_shared_gps_timestamp_data_valid_flags MIP_SHARED_GPS_TIMESTAMP_DATA_VALID_FLAGS_WEEK_NUMBER = 0x0002; ///< Week number has been set static const mip_shared_gps_timestamp_data_valid_flags MIP_SHARED_GPS_TIMESTAMP_DATA_VALID_FLAGS_TIME_VALID = 0x0003; ///< Both TOW and Week Number have been set static const mip_shared_gps_timestamp_data_valid_flags MIP_SHARED_GPS_TIMESTAMP_DATA_VALID_FLAGS_ALL = 0x0003; -inline void insert_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self) +static inline void insert_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_gps_timestamp_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self) +static inline void extract_mip_shared_gps_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_gps_timestamp_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -263,11 +263,11 @@ typedef uint16_t mip_shared_external_timestamp_data_valid_flags; static const mip_shared_external_timestamp_data_valid_flags MIP_SHARED_EXTERNAL_TIMESTAMP_DATA_VALID_FLAGS_NONE = 0x0000; static const mip_shared_external_timestamp_data_valid_flags MIP_SHARED_EXTERNAL_TIMESTAMP_DATA_VALID_FLAGS_NANOSECONDS = 0x0001; ///< static const mip_shared_external_timestamp_data_valid_flags MIP_SHARED_EXTERNAL_TIMESTAMP_DATA_VALID_FLAGS_ALL = 0x0001; -inline void insert_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self) +static inline void insert_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_timestamp_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self) +static inline void extract_mip_shared_external_timestamp_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_timestamp_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -311,11 +311,11 @@ typedef uint16_t mip_shared_external_time_delta_data_valid_flags; static const mip_shared_external_time_delta_data_valid_flags MIP_SHARED_EXTERNAL_TIME_DELTA_DATA_VALID_FLAGS_NONE = 0x0000; static const mip_shared_external_time_delta_data_valid_flags MIP_SHARED_EXTERNAL_TIME_DELTA_DATA_VALID_FLAGS_DT_NANOS = 0x0001; ///< static const mip_shared_external_time_delta_data_valid_flags MIP_SHARED_EXTERNAL_TIME_DELTA_DATA_VALID_FLAGS_ALL = 0x0001; -inline void insert_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self) +static inline void insert_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, const mip_shared_external_time_delta_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -inline void extract_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self) +static inline void extract_mip_shared_external_time_delta_data_valid_flags(microstrain_serializer* serializer, mip_shared_external_time_delta_data_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index 21b349bbd..638246c63 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -22,14 +22,14 @@ namespace microstrain { -class BaseSerializer +class SerializerBase { public: - BaseSerializer() = default; - BaseSerializer(uint8_t* ptr, size_t capacity, size_t offset=0) : m_ptr(ptr), m_size(capacity), m_offset(offset) {} - BaseSerializer(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} + SerializerBase() = default; + SerializerBase(uint8_t* ptr, size_t capacity, size_t offset=0) : m_ptr(ptr), m_size(capacity), m_offset(offset) {} + SerializerBase(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} #ifdef HAS_SPAN - BaseSerializer(std::span buffer, size_t offset=0) : m_ptr(const_cast(buffer.data())), m_size(buffer.size()), m_offset(offset) {} + SerializerBase(std::span buffer, size_t offset=0) : m_ptr(const_cast(buffer.data())), m_size(buffer.size()), m_offset(offset) {} #endif size_t capacity() const { return m_size; } @@ -52,17 +52,17 @@ class BaseSerializer void invalidate() { m_offset = size_t(-1); } - template - bool insert(const Ts&... values); - - template - bool extract(Ts&... values); - - template - size_t extract_count(T& count, S max_count); - - template - size_t extract_count(T* count, S max_count) { return extract_count(*count, max_count); } + //template + //bool insert(const Ts&... values); + // + //template + //bool extract(Ts&... values); + // + //template + //size_t extract_count(T& count, S max_count); + // + //template + //size_t extract_count(T* count, S max_count) { return extract_count(*count, max_count); } // Sets a new offset and returns the old value. size_t setOffset(size_t offset) { std::swap(m_offset, offset); return offset; } @@ -76,16 +76,16 @@ class BaseSerializer // Serializer that has the endianness built-in template -class Serializer : public BaseSerializer +class Serializer : public SerializerBase { public: - using BaseSerializer::BaseSerializer; + using SerializerBase::SerializerBase; - template bool insert (const Ts&... values) { return BaseSerializer::insert(values...); } - template bool extract(Ts&... values) { return BaseSerializer::extract(values...); } + template bool insert (const Ts&... values); + template bool extract(Ts&... values); - template bool extract_count(T& value, S max_value) { return BaseSerializer::extract_count(value, max_value); } - template bool extract_count(T* value, S max_value) { return BaseSerializer::extract_count(value, max_value); } + template bool extract_count(T& value, S max_value); + template bool extract_count(T* value, S max_value) { return extract_count(*value, max_value); } }; using BigEndianSerializer = Serializer; @@ -192,31 +192,31 @@ size_t extract(Serializer& serializer, const std::tuple +// Generic classes which have an "insert" method. +template typename std::enable_if::value , size_t>::type /*size_t*/ insert(microstrain::Serializer& serializer, const T& object) { size_t offset = serializer.offset(); - object.serialize(serializer); + object.insert(serializer); return serializer.offset() - offset; } -// Generic classes which have an "deserialize" method. -template +// Generic classes which have an "extract" method. +template typename std::enable_if::value , size_t>::type /*size_t*/ extract(microstrain::Serializer& serializer, T& object) { size_t offset = serializer.offset(); - object.deserialize(serializer); + object.extract(serializer); return serializer.offset() - offset; } // -// Arrays +// Arrays of runtime length // template @@ -231,6 +231,7 @@ size_t insert(Serializer& serializer, const T* values, size_t count) for(size_t i=0; i(ptr+i*sizeof(T), values[i]); } + return size; } else // Unknown size, have to check length every time. { @@ -253,6 +254,7 @@ size_t extract(Serializer& serializer, T* values, size_t count) for(size_t i=0; i(ptr+i*sizeof(T), values[i]); } + return size; } else // Unknown size, have to check length every time. { @@ -318,7 +320,7 @@ typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) { size_t offset = 0; - ( ..., (offset += write(ptr+offset, values)) ); + ( ..., (offset += serialization::write(ptr+offset, values)) ); return offset; } @@ -348,7 +350,7 @@ typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) { size_t offset = 0; - ( ..., (offset += read(ptr+offset, values)) ); + ( ..., (offset += serialization::read(ptr+offset, values)) ); return offset; } @@ -400,7 +402,7 @@ bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offse // Deserialize and return by value #ifdef HAS_OPTIONAL -template +template std::optional extract(Serializer& serializer) { T value; @@ -410,7 +412,7 @@ std::optional extract(Serializer& serializer) return std::nullopt; } -template +template std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bool exact_size=false) { T value; @@ -428,35 +430,68 @@ std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bo // // -template -bool BaseSerializer::insert(const Ts&... values) +//template +//bool BaseSerializer::insert(const Ts&... values) +//{ +// // Prevents infinite recursion but allows ADL +// // https://stackoverflow.com/questions/13407205/calling-nonmember-instead-of-member-function +// using microstrain::insert; +// +// microstrain::insert(*this, values...); +// return isOk(); +//} +// +//template +//bool BaseSerializer::extract(Ts&... values) +//{ +// // Prevents infinite recursion but allows ADL +// // https://stackoverflow.com/questions/13407205/calling-nonmember-instead-of-member-function +// using microstrain::extract; +// +// extract(*this, values...); +// return isOk(); +//} + +// +// Endian-specific serializer member functions +// + +template +template +bool Serializer::insert(const Ts&... values) { - microstrain::insert(*this, values...); - return isOk(); + // Prevents infinite recursion but allows ADL + // https://stackoverflow.com/questions/13407205/calling-nonmember-instead-of-member-function + using microstrain::insert; + + return insert(*this, values...); } -template -bool BaseSerializer::extract(Ts&... values) +template +template +bool Serializer::extract(Ts&... values) { - microstrain::extract(*this, values...); - return isOk(); + // Prevents infinite recursion but allows ADL + // https://stackoverflow.com/questions/13407205/calling-nonmember-instead-of-member-function + using microstrain::extract; + + return extract(*this, values...); } // Extract a counter with maximum value. -template -size_t BaseSerializer::extract_count(T& count, S max_count) +template +template +bool Serializer::extract_count(T& count, S max_count) { - size_t size = extract(count); - - if(count > max_count) - { - count = 0; - invalidate(); - } + this->extract(count); - return size; -} + if(count <= max_count) + return true; + count = 0; + invalidate(); + return false; +} } // namespace microstrain diff --git a/src/cpp/mip/definitions/commands_3dm.cpp b/src/cpp/mip/definitions/commands_3dm.cpp index ff42001e5..44f3e61a2 100644 --- a/src/cpp/mip/definitions/commands_3dm.cpp +++ b/src/cpp/mip/definitions/commands_3dm.cpp @@ -1113,6 +1113,33 @@ TypedResult defaultDatastreamControl(C::mip_interface& device return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); } +void ConstellationSettings::Settings::insert(Serializer& serializer) const +{ + serializer.insert(constellation_id); + + serializer.insert(enable); + + serializer.insert(reserved_channels); + + serializer.insert(max_channels); + + serializer.insert(option_flags); + +} +void ConstellationSettings::Settings::extract(Serializer& serializer) +{ + serializer.extract(constellation_id); + + serializer.extract(enable); + + serializer.extract(reserved_channels); + + serializer.extract(max_channels); + + serializer.extract(option_flags); + +} + void ConstellationSettings::insert(Serializer& serializer) const { serializer.insert(function); @@ -2017,6 +2044,21 @@ TypedResult defaultOdometer(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); } +void GetEventSupport::Info::insert(Serializer& serializer) const +{ + serializer.insert(type); + + serializer.insert(count); + +} +void GetEventSupport::Info::extract(Serializer& serializer) +{ + serializer.extract(type); + + serializer.extract(count); + +} + void GetEventSupport::insert(Serializer& serializer) const { serializer.insert(query); @@ -2161,6 +2203,21 @@ TypedResult defaultEventControl(C::mip_interface& device, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); } +void GetEventTriggerStatus::Entry::insert(Serializer& serializer) const +{ + serializer.insert(type); + + serializer.insert(status); + +} +void GetEventTriggerStatus::Entry::extract(Serializer& serializer) +{ + serializer.extract(type); + + serializer.extract(status); + +} + void GetEventTriggerStatus::insert(Serializer& serializer) const { serializer.insert(requested_count); @@ -2207,6 +2264,21 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic } return result; } +void GetEventActionStatus::Entry::insert(Serializer& serializer) const +{ + serializer.insert(action_type); + + serializer.insert(trigger_id); + +} +void GetEventActionStatus::Entry::extract(Serializer& serializer) +{ + serializer.extract(action_type); + + serializer.extract(trigger_id); + +} + void GetEventActionStatus::insert(Serializer& serializer) const { serializer.insert(requested_count); @@ -2253,6 +2325,101 @@ TypedResult getEventActionStatus(C::mip_interface& device, } return result; } +void EventTrigger::GpioParams::insert(Serializer& serializer) const +{ + serializer.insert(pin); + + serializer.insert(mode); + +} +void EventTrigger::GpioParams::extract(Serializer& serializer) +{ + serializer.extract(pin); + + serializer.extract(mode); + +} + +void EventTrigger::ThresholdParams::insert(Serializer& serializer) const +{ + serializer.insert(desc_set); + + serializer.insert(field_desc); + + serializer.insert(param_id); + + serializer.insert(type); + + if( type == EventTrigger::ThresholdParams::Type::WINDOW ) + { + serializer.insert(low_thres); + + } + if( type == EventTrigger::ThresholdParams::Type::INTERVAL ) + { + serializer.insert(int_thres); + + } + if( type == EventTrigger::ThresholdParams::Type::WINDOW ) + { + serializer.insert(high_thres); + + } + if( type == EventTrigger::ThresholdParams::Type::INTERVAL ) + { + serializer.insert(interval); + + } +} +void EventTrigger::ThresholdParams::extract(Serializer& serializer) +{ + serializer.extract(desc_set); + + serializer.extract(field_desc); + + serializer.extract(param_id); + + serializer.extract(type); + + if( type == EventTrigger::ThresholdParams::Type::WINDOW ) + { + serializer.extract(low_thres); + + } + if( type == EventTrigger::ThresholdParams::Type::INTERVAL ) + { + serializer.extract(int_thres); + + } + if( type == EventTrigger::ThresholdParams::Type::WINDOW ) + { + serializer.extract(high_thres); + + } + if( type == EventTrigger::ThresholdParams::Type::INTERVAL ) + { + serializer.extract(interval); + + } +} + +void EventTrigger::CombinationParams::insert(Serializer& serializer) const +{ + serializer.insert(logic_table); + + for(unsigned int i=0; i < 4; i++) + serializer.insert(input_triggers[i]); + +} +void EventTrigger::CombinationParams::extract(Serializer& serializer) +{ + serializer.extract(logic_table); + + for(unsigned int i=0; i < 4; i++) + serializer.extract(input_triggers[i]); + +} + void EventTrigger::insert(Serializer& serializer) const { serializer.insert(function); @@ -2415,6 +2582,45 @@ TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); } +void EventAction::GpioParams::insert(Serializer& serializer) const +{ + serializer.insert(pin); + + serializer.insert(mode); + +} +void EventAction::GpioParams::extract(Serializer& serializer) +{ + serializer.extract(pin); + + serializer.extract(mode); + +} + +void EventAction::MessageParams::insert(Serializer& serializer) const +{ + serializer.insert(desc_set); + + serializer.insert(decimation); + + serializer.insert(num_fields); + + for(unsigned int i=0; i < num_fields; i++) + serializer.insert(descriptors[i]); + +} +void EventAction::MessageParams::extract(Serializer& serializer) +{ + serializer.extract(desc_set); + + serializer.extract(decimation); + + serializer.extract_count(num_fields, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_fields; i++) + serializer.extract(descriptors[i]); + +} + void EventAction::insert(Serializer& serializer) const { serializer.insert(function); @@ -3541,6 +3747,21 @@ TypedResult defaultSensorRange(C::mip_interface& device, SensorRang return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); } +void CalibratedSensorRanges::Entry::insert(Serializer& serializer) const +{ + serializer.insert(setting); + + serializer.insert(range); + +} +void CalibratedSensorRanges::Entry::extract(Serializer& serializer) +{ + serializer.extract(setting); + + serializer.extract(range); + +} + void CalibratedSensorRanges::insert(Serializer& serializer) const { serializer.insert(sensor); diff --git a/src/cpp/mip/definitions/commands_gnss.cpp b/src/cpp/mip/definitions/commands_gnss.cpp index 4434bf7ff..96b032a22 100644 --- a/src/cpp/mip/definitions/commands_gnss.cpp +++ b/src/cpp/mip/definitions/commands_gnss.cpp @@ -20,6 +20,27 @@ using namespace ::mip::C; // Mip Fields //////////////////////////////////////////////////////////////////////////////// +void ReceiverInfo::Info::insert(Serializer& serializer) const +{ + serializer.insert(receiver_id); + + serializer.insert(mip_data_descriptor_set); + + for(unsigned int i=0; i < 32; i++) + serializer.insert(description[i]); + +} +void ReceiverInfo::Info::extract(Serializer& serializer) +{ + serializer.extract(receiver_id); + + serializer.extract(mip_data_descriptor_set); + + for(unsigned int i=0; i < 32; i++) + serializer.extract(description[i]); + +} + void ReceiverInfo::insert(Serializer& serializer) const { (void)serializer; diff --git a/src/cpp/mip/definitions/common.hpp b/src/cpp/mip/definitions/common.hpp index 990893277..be7f4f277 100644 --- a/src/cpp/mip/definitions/common.hpp +++ b/src/cpp/mip/definitions/common.hpp @@ -100,9 +100,9 @@ struct Vector /// Get the size of the array size_t size() const { return N; } - /// Pack vector into a raw byte buffer. - size_t insert(Serializer& serializer) const { return serializer.insert(m_data); } - size_t extract(Serializer& serializer) { return serializer.extract(m_data); } + ///// Pack vector into a raw byte buffer. + //size_t insert(Serializer& serializer) const { return serializer.insert(m_data); } + //size_t extract(Serializer& serializer) { return serializer.extract(m_data); } private: T m_data[N]; @@ -117,11 +117,11 @@ using Matrix3d = Vector; using Quatf = Vector4f; -//template -//void insert(Serializer& serializer, const Vector& v) { for(size_t i =0; i -//void extract(Serializer& serializer, Vector& v) { for(size_t i =0; i +size_t insert(Serializer& serializer, const Vector& v) { return serializer.insert(v.data()); } + +template +size_t extract(Serializer& serializer, Vector& v) { return serializer.extract(v.data()); } ///@} //////////////////////////////////////////////////////////////////////////////// diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index d856895c9..9f709d80a 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -9,6 +9,103 @@ namespace mip::metadata { +template<> +struct MetadataFor +{ + using type = CmdResult; + + static constexpr inline EnumInfo::Entry entries[] = { + { + .value = CmdResult::ACK_OK, + .name = "OK", + .docs = "Command completed successfully", + }, + { + .value = CmdResult::NACK_COMMAND_UNKNOWN, + .name = "Unknown Command", + .docs = "The device did not recognize the command", + }, + { + .value = CmdResult::NACK_INVALID_CHECKSUM, + .name = "Invalid Checksum", + .docs = "An packet with an invalid checksum was received by the device", + }, + { + .value = CmdResult::NACK_INVALID_PARAM, + .name = "Invalid Parameter", + .docs = "One or more parameters to the command were not valid", + }, + { + .value = CmdResult::NACK_COMMAND_FAILED, + .name = "Command Failed", + .docs = "The device could not complete the command", + }, + { + .value = CmdResult::NACK_COMMAND_TIMEOUT, + .name = "Device Timeout", + .docs = "The device reported a timeout condition", + }, + // Status codes not represented here as they don't come from the device. + }; + + static constexpr inline EnumInfo value = { + .name = "CmdResult", + .docs = "Acknowledgement/reply code from the device after a command is issued", + .type = Type::U8, + .entries = entries, + }; +}; + +struct ReplyField +{ + static constexpr inline uint8_t FIELD_DESCRIPTOR = 0xF1; + static constexpr inline CompositeDescriptor DESCRIPTOR = {INVALID_DESCRIPTOR_SET, FIELD_DESCRIPTOR}; + + uint8_t cmd_field_desc; + CmdResult result; + + size_t insert(Serializer& buffer) const { return buffer.insert(cmd_field_desc, result.value); } + size_t extract(Serializer& buffer) { return buffer.extract(cmd_field_desc, result.value); } +}; + +template<> +struct MetadataFor +{ + using type = ReplyField; + + static constexpr inline ParameterInfo parameters[] = { + { + .name = "cmd_field_desc", + .docs = "The field descriptor of the command this field acknowledges.", + .type = {Type::U8}, + .accessor = utils::access, + .functions = NO_FUNCTIONS, + .count = 1, + .condition = {}, + }, + { + .name = "result", + .docs = "Result of the command.", + .type = {Type::ENUM, &MetadataFor::value}, + .accessor = utils::access, + .functions = NO_FUNCTIONS, + .count = 1, + .condition = {}, + }, + }; + + static constexpr inline FieldInfo value = { + /*.name = */ "ReplyField", + /* .title = */ "Command Reply", + /* .docs = */ "Sent by the device to indicate the result of a command.", + /* .parameters = */ parameters, + /* .descriptor = */ type::DESCRIPTOR, + /* .functions = */ NO_FUNCTIONS, + /* .proprietary = */ false, + /* .response = */ nullptr, + }; +}; + template<> struct MetadataFor { @@ -20,12 +117,18 @@ struct MetadataFor .docs = "MIP data descriptor", .type = {Type::U8}, .accessor = utils::access, + .functions = NO_FUNCTIONS, + .count = 1, + .condition = {}, }, { .name = "decimation", .docs = "Decimation from the base rate", .type = {Type::U16}, .accessor = utils::access, + .functions = NO_FUNCTIONS, + .count = 1, + .condition = {}, }, }; @@ -37,40 +140,6 @@ struct MetadataFor }; }; -//template<> -//struct MetadataFor -//{ -// using type = Vector3f; -// -// static constexpr inline ParameterInfo parameters[] = { -// { -// .name = "x", -// .docs = "X axis", -// .type = {Type::FLOAT}, -// .accessor = nullptr, -// }, -// { -// .name = "y", -// .docs = "Y axis", -// .type = {Type::FLOAT}, -// .accessor = nullptr, -// }, -// { -// .name = "z", -// .docs = "Z axis", -// .type = {Type::FLOAT}, -// .accessor = nullptr, -// }, -// }; -// -// static constexpr inline StructInfo value = { -// .name = "Vector3f", -// .title = "3D Vector", -// .docs = "Represents a 3D vector of floats.", -// .parameters = parameters, -// }; -//}; - template struct MetadataFor> @@ -83,24 +152,36 @@ struct MetadataFor> .docs = "X axis", .type = {utils::ParamType::value}, .accessor = nullptr, + .functions = NO_FUNCTIONS, + .count = 1, + .condition = {}, }, { .name = "y", .docs = "Y axis", .type = {utils::ParamType::value}, .accessor = nullptr, + .functions = NO_FUNCTIONS, + .count = 1, + .condition = {}, }, { .name = "z", .docs = "Z axis", .type = {utils::ParamType::value}, .accessor = nullptr, + .functions = NO_FUNCTIONS, + .count = 1, + .condition = {}, }, { .name = "w", .docs = "W axis", .type = {utils::ParamType::value}, .accessor = nullptr, + .functions = NO_FUNCTIONS, + .count = 1, + .condition = {}, }, }; @@ -164,7 +245,9 @@ struct MetadataFor .docs = "Matrix data", .type = {Type::FLOAT}, .accessor = nullptr, + .functions = NO_FUNCTIONS, .count = 3, + .condition = {}, }, }; @@ -187,7 +270,9 @@ struct MetadataFor .docs = "Matrix data", .type = {Type::DOUBLE}, .accessor = nullptr, + .functions = NO_FUNCTIONS, .count = 3, + .condition = {}, }, }; diff --git a/src/cpp/mip/metadata/mip_definitions.cpp b/src/cpp/mip/metadata/mip_definitions.cpp index 7a2a83cbb..e48ef104e 100644 --- a/src/cpp/mip/metadata/mip_definitions.cpp +++ b/src/cpp/mip/metadata/mip_definitions.cpp @@ -2,7 +2,7 @@ #include "mip_definitions.hpp" #include - +#include namespace mip::metadata { @@ -51,6 +51,9 @@ const FieldInfo* Definitions::findField(mip::CompositeDescriptor descriptor) con if(it != mFields.end()) return *it; } + // Reply descriptor? + else if(isCommandDescriptorSet(descriptor.descriptorSet) && isReplyFieldDescriptor(descriptor.fieldDescriptor)) + return &MetadataFor::value; return nullptr; } diff --git a/src/cpp/mip/mip_descriptors.hpp b/src/cpp/mip/mip_descriptors.hpp index 65d007591..d09282095 100644 --- a/src/cpp/mip/mip_descriptors.hpp +++ b/src/cpp/mip/mip_descriptors.hpp @@ -61,8 +61,8 @@ using EnableForFieldTypes = std::enable_if::value, T>; /// template struct Bitfield {}; -template void insert (Serializer& serializer, const Bitfield& bitfield) { insert(serializer, static_cast(bitfield).value); } -template void extract(Serializer& serializer, Bitfield& bitfield) { extract(serializer, static_cast(bitfield).value); } +template size_t insert (Serializer& serializer, const Bitfield& bitfield) { return insert(serializer, static_cast(bitfield).value); } +template size_t extract(Serializer& serializer, Bitfield& bitfield) { return extract(serializer, static_cast(bitfield).value); } enum class FunctionSelector : uint8_t diff --git a/src/cpp/mip/mip_serialization.hpp b/src/cpp/mip/mip_serialization.hpp index fa07650e9..80eb3b33e 100644 --- a/src/cpp/mip/mip_serialization.hpp +++ b/src/cpp/mip/mip_serialization.hpp @@ -17,6 +17,14 @@ namespace serialization using namespace microstrain::serialization::big_endian; } +//template +//size_t insert(const Ts&... values) +//{ +// static_assert(E == microstrain::serialization::Endian::big); +// return insert(values...); +//} + + // //template //size_t insert(Serializer& serializer, const Ts&... values) From 152772b2adc41d25b22ecf893baa574bd48a4341 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 16 Jul 2024 18:49:02 -0400 Subject: [PATCH 050/147] Bump CMake version to 3.0.00. --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c0d38f499..6a95f0771 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,7 +8,7 @@ set(CMAKE_C_STANDARD_REQUIRED ON) project( "MIP SDK" - VERSION "0.0.01" + VERSION "3.0.00" DESCRIPTION "MicroStrain Communications Library for embedded systems" LANGUAGES C CXX ) From 4738b9ec582d7ad945e1a0faec2867c9805cdef9 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 16 Jul 2024 19:10:18 -0400 Subject: [PATCH 051/147] Fix compilation error and clean up a bit. --- .../common/serialization/serializer.hpp | 50 +------------------ src/cpp/mip/mip_field.hpp | 2 +- src/cpp/mip/mip_serialization.hpp | 33 ------------ 3 files changed, 3 insertions(+), 82 deletions(-) diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index 638246c63..c2be2e46c 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -52,18 +52,6 @@ class SerializerBase void invalidate() { m_offset = size_t(-1); } - //template - //bool insert(const Ts&... values); - // - //template - //bool extract(Ts&... values); - // - //template - //size_t extract_count(T& count, S max_count); - // - //template - //size_t extract_count(T* count, S max_count) { return extract_count(*count, max_count); } - // Sets a new offset and returns the old value. size_t setOffset(size_t offset) { std::swap(m_offset, offset); return offset; } @@ -81,6 +69,8 @@ class Serializer : public SerializerBase public: using SerializerBase::SerializerBase; + static const serialization::Endian ENDIAN = E; + template bool insert (const Ts&... values); template bool extract(Ts&... values); @@ -92,12 +82,6 @@ using BigEndianSerializer = Serializer; using LittleEndianSerializer = Serializer; -//template -//size_t insert(BaseSerializer&, Ts...); -//template -//size_t extract(BaseSerializer&, Ts...); - - // // // Non-member functions which the user may overload @@ -390,10 +374,6 @@ bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offse - - - - // // Special Deserialization // @@ -430,32 +410,6 @@ std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bo // // -//template -//bool BaseSerializer::insert(const Ts&... values) -//{ -// // Prevents infinite recursion but allows ADL -// // https://stackoverflow.com/questions/13407205/calling-nonmember-instead-of-member-function -// using microstrain::insert; -// -// microstrain::insert(*this, values...); -// return isOk(); -//} -// -//template -//bool BaseSerializer::extract(Ts&... values) -//{ -// // Prevents infinite recursion but allows ADL -// // https://stackoverflow.com/questions/13407205/calling-nonmember-instead-of-member-function -// using microstrain::extract; -// -// extract(*this, values...); -// return isOk(); -//} - -// -// Endian-specific serializer member functions -// - template template bool Serializer::insert(const Ts&... values) diff --git a/src/cpp/mip/mip_field.hpp b/src/cpp/mip/mip_field.hpp index cf9214cd8..0bb460fed 100644 --- a/src/cpp/mip/mip_field.hpp +++ b/src/cpp/mip/mip_field.hpp @@ -88,7 +88,7 @@ class FieldView : public C::mip_field_view /// too few bytes (or to many if exact_size is specified). The field data is not /// valid unless this function returns true. template - bool extract(FieldType& field, bool exact_size=true) const { return microstrain::extract(field, payload(), payloadLength(), 0, exact_size); } + bool extract(FieldType& field, bool exact_size=true) const { return microstrain::extract(field, payload(), payloadLength(), 0, exact_size); } ///@brief Determines if the field holds data (and not a command, reply, or response). diff --git a/src/cpp/mip/mip_serialization.hpp b/src/cpp/mip/mip_serialization.hpp index 80eb3b33e..0909fa32e 100644 --- a/src/cpp/mip/mip_serialization.hpp +++ b/src/cpp/mip/mip_serialization.hpp @@ -17,39 +17,6 @@ namespace serialization using namespace microstrain::serialization::big_endian; } -//template -//size_t insert(const Ts&... values) -//{ -// static_assert(E == microstrain::serialization::Endian::big); -// return insert(values...); -//} - - -// -//template -//size_t insert(Serializer& serializer, const Ts&... values) -//{ -// return serializer.insert(std::forward(values)...); -//} -// -//template -//size_t extract(Serializer& serializer, Ts&... values) -//{ -// return microstrain::extract(serializer, std::forward(values)...); -//} -// -//template -//size_t extract_count(Serializer& buffer, T* count, size_t max_count) -//{ -// return microstrain::extract_count(buffer, count, max_count); -//} -//template -//size_t extract_count(Serializer& buffer, T& count, size_t max_count) -//{ -// return microstrain::extract_count(buffer, count, max_count); -//} - - } // namespace mip From 3ffbb4218776bcf560928a07e6524d1219ead2ab Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 16 Jul 2024 19:15:10 -0400 Subject: [PATCH 052/147] Test and fix cv7 AHRS and WatchImu examples (C and C++). --- examples/CMakeLists.txt | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 9072586d0..83ec15ccd 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -67,10 +67,10 @@ endif() # C examples need serial support if(MIP_USE_SERIAL) - add_mip_example(WatchImuC "${EXAMPLE_DIR}/watch_imu.c") - add_mip_example(GQ7_ExampleC "${EXAMPLE_DIR}/GQ7/GQ7_example.c") - add_mip_example(CV7_ExampleC "${EXAMPLE_DIR}/CV7/CV7_example.c") - add_mip_example(CX5_GX5_45_ExampleC "${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.c") - add_mip_example(CX5_GX5_CV5_15_25_ExampleC "${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c") + add_mip_example(WatchImuC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.c") + add_mip_example(GQ7_ExampleC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/GQ7/GQ7_example.c") + add_mip_example(CV7_ExampleC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CV7/CV7_example.c") + add_mip_example(CX5_GX5_45_ExampleC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.c") + add_mip_example(CX5_GX5_CV5_15_25_ExampleC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c") endif() From 4dc9b25fdead9e7c0b6c49ba40222969139f4d57 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 19 Jul 2024 11:50:04 -0400 Subject: [PATCH 053/147] Update to latest definitions. --- src/c/mip/definitions/commands_3dm.h | 4 +- src/c/mip/definitions/commands_aiding.c | 98 +++--- src/c/mip/definitions/commands_aiding.h | 275 ++++++++-------- src/c/mip/definitions/commands_filter.h | 12 +- src/c/mip/definitions/data_filter.h | 27 +- src/cpp/mip/definitions/commands_3dm.hpp | 20 ++ src/cpp/mip/definitions/commands_aiding.cpp | 62 ++-- src/cpp/mip/definitions/commands_aiding.hpp | 181 ++++++----- src/cpp/mip/definitions/commands_base.hpp | 54 ++++ src/cpp/mip/definitions/commands_filter.hpp | 38 ++- src/cpp/mip/definitions/commands_rtk.hpp | 52 +++ src/cpp/mip/definitions/data_filter.hpp | 106 ++++++ src/cpp/mip/definitions/data_gnss.hpp | 336 ++++++++++++++++++++ src/cpp/mip/definitions/data_sensor.hpp | 30 ++ src/cpp/mip/definitions/data_shared.hpp | 10 + 15 files changed, 995 insertions(+), 310 deletions(-) diff --git a/src/c/mip/definitions/commands_3dm.h b/src/c/mip/definitions/commands_3dm.h index 480cbf5a3..f13d5e29b 100644 --- a/src/c/mip/definitions/commands_3dm.h +++ b/src/c/mip/definitions/commands_3dm.h @@ -152,8 +152,8 @@ enum mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_VTG = 5, ///< Course over Ground. Source can be the Filter or GNSS1/2 datasets. MIP_NMEA_MESSAGE_MESSAGE_ID_HDT = 6, ///< Heading, True. Source can be the Filter or GNSS1/2 datasets. MIP_NMEA_MESSAGE_MESSAGE_ID_ZDA = 7, ///< Time & Date. Source must be the GNSS1 or GNSS2 datasets. - MIP_NMEA_MESSAGE_MESSAGE_ID_PKRA = 129, ///< Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. - MIP_NMEA_MESSAGE_MESSAGE_ID_PKRR = 130, ///< Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. + MIP_NMEA_MESSAGE_MESSAGE_ID_MSRA = 129, ///< MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. + MIP_NMEA_MESSAGE_MESSAGE_ID_MSRR = 130, ///< MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. }; typedef enum mip_nmea_message_message_id mip_nmea_message_message_id; diff --git a/src/c/mip/definitions/commands_aiding.c b/src/c/mip/definitions/commands_aiding.c index 7beb7f79b..7b787179f 100644 --- a/src/c/mip/definitions/commands_aiding.c +++ b/src/c/mip/definitions/commands_aiding.c @@ -219,28 +219,28 @@ mip_cmd_result mip_aiding_default_frame_config(mip_interface* device, uint8_t fr return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self) +void insert_mip_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_echo_control_command* self) { insert_mip_function_selector(serializer, self->function); if( self->function == MIP_FUNCTION_WRITE ) { - insert_mip_aiding_aiding_echo_control_command_mode(serializer, self->mode); + insert_mip_aiding_echo_control_command_mode(serializer, self->mode); } } -void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self) +void extract_mip_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_echo_control_command* self) { extract_mip_function_selector(serializer, &self->function); if( self->function == MIP_FUNCTION_WRITE ) { - extract_mip_aiding_aiding_echo_control_command_mode(serializer, &self->mode); + extract_mip_aiding_echo_control_command_mode(serializer, &self->mode); } } -mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode) +mip_cmd_result mip_aiding_write_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode mode) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -248,13 +248,13 @@ mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_a insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - insert_mip_aiding_aiding_echo_control_command_mode(&serializer, mode); + insert_mip_aiding_echo_control_command_mode(&serializer, mode); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out) +mip_cmd_result mip_aiding_read_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode* mode_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -273,14 +273,14 @@ mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_ai microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(mode_out); - extract_mip_aiding_aiding_echo_control_command_mode(&deserializer, mode_out); + extract_mip_aiding_echo_control_command_mode(&deserializer, mode_out); if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device) +mip_cmd_result mip_aiding_save_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -292,7 +292,7 @@ mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device) return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device) +mip_cmd_result mip_aiding_load_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -304,7 +304,7 @@ mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device) return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device) +mip_cmd_result mip_aiding_default_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -316,7 +316,7 @@ mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device) return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self) +void insert_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, const mip_aiding_pos_ecef_command* self) { insert_mip_time(serializer, &self->time); @@ -326,10 +326,10 @@ void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, cons insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_ecef_pos_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_pos_ecef_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self) +void extract_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, mip_aiding_pos_ecef_command* self) { extract_mip_time(serializer, &self->time); @@ -339,11 +339,11 @@ void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_ecef_pos_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_pos_ecef_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_pos_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_pos_ecef_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -362,13 +362,13 @@ mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_ecef_pos_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_pos_ecef_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self) +void insert_mip_aiding_pos_llh_command(microstrain_serializer* serializer, const mip_aiding_pos_llh_command* self) { insert_mip_time(serializer, &self->time); @@ -382,10 +382,10 @@ void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_llh_pos_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_pos_llh_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self) +void extract_mip_aiding_pos_llh_command(microstrain_serializer* serializer, mip_aiding_pos_llh_command* self) { extract_mip_time(serializer, &self->time); @@ -399,11 +399,11 @@ void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_ extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_llh_pos_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_pos_llh_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_pos_llh(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_pos_llh_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -424,13 +424,13 @@ mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, u for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_llh_pos_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_pos_llh_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self) +void insert_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, const mip_aiding_height_above_ellipsoid_command* self) { insert_mip_time(serializer, &self->time); @@ -443,7 +443,7 @@ void insert_mip_aiding_height_command(microstrain_serializer* serializer, const microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self) +void extract_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, mip_aiding_height_above_ellipsoid_command* self) { extract_mip_time(serializer, &self->time); @@ -457,7 +457,7 @@ void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_a } -mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) +mip_cmd_result mip_aiding_height_above_ellipsoid(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -476,9 +476,9 @@ mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, ui assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABOVE_ELLIPSOID, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self) +void insert_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, const mip_aiding_vel_ecef_command* self) { insert_mip_time(serializer, &self->time); @@ -488,10 +488,10 @@ void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, cons insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_ecef_vel_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_vel_ecef_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self) +void extract_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, mip_aiding_vel_ecef_command* self) { extract_mip_time(serializer, &self->time); @@ -501,11 +501,11 @@ void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_ecef_vel_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_vel_ecef_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_vel_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ecef_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -524,13 +524,13 @@ mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_ecef_vel_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_vel_ecef_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self) +void insert_mip_aiding_vel_ned_command(microstrain_serializer* serializer, const mip_aiding_vel_ned_command* self) { insert_mip_time(serializer, &self->time); @@ -540,10 +540,10 @@ void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_ned_vel_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_vel_ned_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self) +void extract_mip_aiding_vel_ned_command(microstrain_serializer* serializer, mip_aiding_vel_ned_command* self) { extract_mip_time(serializer, &self->time); @@ -553,11 +553,11 @@ void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_ extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_ned_vel_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_vel_ned_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_vel_ned(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ned_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -576,13 +576,13 @@ mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, u for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_ned_vel_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_vel_ned_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self) +void insert_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, const mip_aiding_vel_body_frame_command* self) { insert_mip_time(serializer, &self->time); @@ -592,10 +592,10 @@ void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializ insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_vel_body_frame_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self) +void extract_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, mip_aiding_vel_body_frame_command* self) { extract_mip_time(serializer, &self->time); @@ -605,11 +605,11 @@ void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_seriali extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_vel_body_frame_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_vel_body_frame(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_body_frame_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -628,13 +628,13 @@ mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, co for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_vel_body_frame_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ODOM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_BODY_FRAME, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self) +void insert_mip_aiding_heading_true_command(microstrain_serializer* serializer, const mip_aiding_heading_true_command* self) { insert_mip_time(serializer, &self->time); @@ -647,7 +647,7 @@ void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self) +void extract_mip_aiding_heading_true_command(microstrain_serializer* serializer, mip_aiding_heading_true_command* self) { extract_mip_time(serializer, &self->time); @@ -661,7 +661,7 @@ void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, } -mip_cmd_result mip_aiding_true_heading(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) +mip_cmd_result mip_aiding_heading_true(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/c/mip/definitions/commands_aiding.h b/src/c/mip/definitions/commands_aiding.h index 81425e141..9245a8711 100644 --- a/src/c/mip/definitions/commands_aiding.h +++ b/src/c/mip/definitions/commands_aiding.h @@ -29,29 +29,29 @@ extern "C" { enum { - MIP_AIDING_CMD_DESC_SET = 0x13, + MIP_AIDING_CMD_DESC_SET = 0x13, - MIP_CMD_DESC_AIDING_FRAME_CONFIG = 0x01, - MIP_CMD_DESC_AIDING_LOCAL_FRAME = 0x03, - MIP_CMD_DESC_AIDING_ECHO_CONTROL = 0x1F, - MIP_CMD_DESC_AIDING_POS_LOCAL = 0x20, - MIP_CMD_DESC_AIDING_POS_ECEF = 0x21, - MIP_CMD_DESC_AIDING_POS_LLH = 0x22, - MIP_CMD_DESC_AIDING_HEIGHT_ABS = 0x23, - MIP_CMD_DESC_AIDING_HEIGHT_REL = 0x24, - MIP_CMD_DESC_AIDING_VEL_ECEF = 0x28, - MIP_CMD_DESC_AIDING_VEL_NED = 0x29, - MIP_CMD_DESC_AIDING_VEL_ODOM = 0x2A, - MIP_CMD_DESC_AIDING_WHEELSPEED = 0x2B, - MIP_CMD_DESC_AIDING_HEADING_TRUE = 0x31, - MIP_CMD_DESC_AIDING_MAGNETIC_FIELD = 0x32, - MIP_CMD_DESC_AIDING_PRESSURE = 0x33, - MIP_CMD_DESC_AIDING_DELTA_POSITION = 0x38, - MIP_CMD_DESC_AIDING_DELTA_ATTITUDE = 0x39, - MIP_CMD_DESC_AIDING_LOCAL_ANGULAR_RATE = 0x3A, + MIP_CMD_DESC_AIDING_FRAME_CONFIG = 0x01, + MIP_CMD_DESC_AIDING_LOCAL_FRAME = 0x03, + MIP_CMD_DESC_AIDING_ECHO_CONTROL = 0x1F, + MIP_CMD_DESC_AIDING_POS_LOCAL = 0x20, + MIP_CMD_DESC_AIDING_POS_ECEF = 0x21, + MIP_CMD_DESC_AIDING_POS_LLH = 0x22, + MIP_CMD_DESC_AIDING_HEIGHT_ABOVE_ELLIPSOID = 0x23, + MIP_CMD_DESC_AIDING_HEIGHT_REL = 0x24, + MIP_CMD_DESC_AIDING_VEL_ECEF = 0x28, + MIP_CMD_DESC_AIDING_VEL_NED = 0x29, + MIP_CMD_DESC_AIDING_VEL_BODY_FRAME = 0x2A, + MIP_CMD_DESC_AIDING_WHEELSPEED = 0x2B, + MIP_CMD_DESC_AIDING_HEADING_TRUE = 0x31, + MIP_CMD_DESC_AIDING_MAGNETIC_FIELD = 0x32, + MIP_CMD_DESC_AIDING_PRESSURE = 0x33, + MIP_CMD_DESC_AIDING_DELTA_POSITION = 0x38, + MIP_CMD_DESC_AIDING_DELTA_ATTITUDE = 0x39, + MIP_CMD_DESC_AIDING_ANGULAR_RATE_LOCAL = 0x3A, - MIP_REPLY_DESC_AIDING_FRAME_CONFIG = 0x81, - MIP_REPLY_DESC_AIDING_ECHO_CONTROL = 0x9F, + MIP_REPLY_DESC_AIDING_FRAME_CONFIG = 0x81, + MIP_REPLY_DESC_AIDING_ECHO_CONTROL = 0x9F, }; //////////////////////////////////////////////////////////////////////////////// @@ -96,8 +96,9 @@ void extract_mip_time(microstrain_serializer* serializer, mip_time* self); //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_aiding_frame_config (0x13,0x01) Frame Config [C] -/// Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command -/// should mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame) +/// Defines an aiding frame associated with a specific sensor frame ID. +/// The frame ID used in this command should mirror the frame ID used in the aiding command +/// (if that aiding measurement is measured in this reference frame). /// /// This transform satisfies the following relationship: /// @@ -184,24 +185,24 @@ mip_cmd_result mip_aiding_default_frame_config(mip_interface* device, uint8_t fr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_aiding_echo_control (0x13,0x1F) Aiding Echo Control [C] +///@defgroup c_aiding_echo_control (0x13,0x1F) Echo Control [C] /// Controls command response behavior to external aiding commands /// ///@{ -enum mip_aiding_aiding_echo_control_command_mode +enum mip_aiding_echo_control_command_mode { - MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_SUPPRESS_ACK = 0, ///< Suppresses the usual command ack field for aiding messages. - MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_STANDARD = 1, ///< Normal ack/nack behavior. - MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_RESPONSE = 2, ///< Echo the data back as a response. + MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_SUPPRESS_ACK = 0, ///< Suppresses the usual command ack field for aiding messages. + MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_STANDARD = 1, ///< Normal ack/nack behavior. + MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_RESPONSE = 2, ///< Echo the data back as a response. }; -typedef enum mip_aiding_aiding_echo_control_command_mode mip_aiding_aiding_echo_control_command_mode; +typedef enum mip_aiding_echo_control_command_mode mip_aiding_echo_control_command_mode; -static inline void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) +static inline void insert_mip_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_echo_control_command_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -static inline void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) +static inline void extract_mip_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_echo_control_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -209,50 +210,50 @@ static inline void extract_mip_aiding_aiding_echo_control_command_mode(microstra } -struct mip_aiding_aiding_echo_control_command +struct mip_aiding_echo_control_command { mip_function_selector function; - mip_aiding_aiding_echo_control_command_mode mode; ///< Controls data echoing. + mip_aiding_echo_control_command_mode mode; ///< Controls data echoing. }; -typedef struct mip_aiding_aiding_echo_control_command mip_aiding_aiding_echo_control_command; +typedef struct mip_aiding_echo_control_command mip_aiding_echo_control_command; -void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self); -void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self); +void insert_mip_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_echo_control_command* self); +void extract_mip_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_echo_control_command* self); -struct mip_aiding_aiding_echo_control_response +struct mip_aiding_echo_control_response { - mip_aiding_aiding_echo_control_command_mode mode; ///< Controls data echoing. + mip_aiding_echo_control_command_mode mode; ///< Controls data echoing. }; -typedef struct mip_aiding_aiding_echo_control_response mip_aiding_aiding_echo_control_response; +typedef struct mip_aiding_echo_control_response mip_aiding_echo_control_response; -void insert_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self); -void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self); +void insert_mip_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_echo_control_response* self); +void extract_mip_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_echo_control_response* self); -mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode); -mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out); -mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device); -mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device); -mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_write_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode mode); +mip_cmd_result mip_aiding_read_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode* mode_out); +mip_cmd_result mip_aiding_save_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_load_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_default_echo_control(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_ecef_pos (0x13,0x21) Ecef Pos [C] +///@defgroup c_aiding_pos_ecef (0x13,0x21) Pos Ecef [C] /// Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system. /// ///@{ -typedef uint16_t mip_aiding_ecef_pos_command_valid_flags; -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) +typedef uint16_t mip_aiding_pos_ecef_command_valid_flags; +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_pos_ecef_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_pos_ecef_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) +static inline void extract_mip_aiding_pos_ecef_command_valid_flags(microstrain_serializer* serializer, mip_aiding_pos_ecef_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -260,41 +261,42 @@ static inline void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_s } -struct mip_aiding_ecef_pos_command +struct mip_aiding_pos_ecef_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3d position; ///< ECEF position [m]. mip_vector3f uncertainty; ///< ECEF position uncertainty [m]. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_ecef_pos_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_pos_ecef_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_ecef_pos_command mip_aiding_ecef_pos_command; +typedef struct mip_aiding_pos_ecef_command mip_aiding_pos_ecef_command; -void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self); -void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self); +void insert_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, const mip_aiding_pos_ecef_command* self); +void extract_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, mip_aiding_pos_ecef_command* self); -mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_pos_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_pos_ecef_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_llh_pos (0x13,0x22) Llh Pos [C] -/// Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. +///@defgroup c_aiding_pos_llh (0x13,0x22) Pos Llh [C] +/// Geodetic position aiding command. +/// Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. /// Uncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height. /// ///@{ -typedef uint16_t mip_aiding_llh_pos_command_valid_flags; -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_LATITUDE = 0x0001; ///< -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_LONGITUDE = 0x0002; ///< -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_HEIGHT = 0x0004; ///< -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) +typedef uint16_t mip_aiding_pos_llh_command_valid_flags; +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_LATITUDE = 0x0001; ///< +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_LONGITUDE = 0x0002; ///< +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_HEIGHT = 0x0004; ///< +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_pos_llh_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_pos_llh_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) +static inline void extract_mip_aiding_pos_llh_command_valid_flags(microstrain_serializer* serializer, mip_aiding_pos_llh_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -302,7 +304,7 @@ static inline void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_se } -struct mip_aiding_llh_pos_command +struct mip_aiding_pos_llh_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). @@ -310,24 +312,24 @@ struct mip_aiding_llh_pos_command double longitude; ///< [deg] double height; ///< [m] mip_vector3f uncertainty; ///< NED position uncertainty. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_llh_pos_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_pos_llh_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_llh_pos_command mip_aiding_llh_pos_command; +typedef struct mip_aiding_pos_llh_command mip_aiding_pos_llh_command; -void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self); -void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self); +void insert_mip_aiding_pos_llh_command(microstrain_serializer* serializer, const mip_aiding_pos_llh_command* self); +void extract_mip_aiding_pos_llh_command(microstrain_serializer* serializer, mip_aiding_pos_llh_command* self); -mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_pos_llh(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_pos_llh_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_height (0x13,0x23) Height [C] -/// Estimated value of height. +///@defgroup c_aiding_height_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [C] +/// Estimated value of the height above ellipsoid. /// ///@{ -struct mip_aiding_height_command +struct mip_aiding_height_above_ellipsoid_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). @@ -335,32 +337,32 @@ struct mip_aiding_height_command float uncertainty; ///< [m] uint16_t valid_flags; }; -typedef struct mip_aiding_height_command mip_aiding_height_command; +typedef struct mip_aiding_height_above_ellipsoid_command mip_aiding_height_above_ellipsoid_command; -void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self); -void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self); +void insert_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, const mip_aiding_height_above_ellipsoid_command* self); +void extract_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, mip_aiding_height_above_ellipsoid_command* self); -mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); +mip_cmd_result mip_aiding_height_above_ellipsoid(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_ecef_vel (0x13,0x28) Ecef Vel [C] +///@defgroup c_aiding_vel_ecef (0x13,0x28) Vel Ecef [C] /// ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame. /// ///@{ -typedef uint16_t mip_aiding_ecef_vel_command_valid_flags; -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) +typedef uint16_t mip_aiding_vel_ecef_command_valid_flags; +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_vel_ecef_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vel_ecef_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) +static inline void extract_mip_aiding_vel_ecef_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vel_ecef_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -368,40 +370,40 @@ static inline void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_s } -struct mip_aiding_ecef_vel_command +struct mip_aiding_vel_ecef_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3f velocity; ///< ECEF velocity [m/s]. mip_vector3f uncertainty; ///< ECEF velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_ecef_vel_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_vel_ecef_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_ecef_vel_command mip_aiding_ecef_vel_command; +typedef struct mip_aiding_vel_ecef_command mip_aiding_vel_ecef_command; -void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self); -void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self); +void insert_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, const mip_aiding_vel_ecef_command* self); +void extract_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, mip_aiding_vel_ecef_command* self); -mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_vel_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ecef_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_ned_vel (0x13,0x29) Ned Vel [C] +///@defgroup c_aiding_vel_ned (0x13,0x29) Vel Ned [C] /// NED velocity aiding command. Coordinates are given in the local North-East-Down frame. /// ///@{ -typedef uint16_t mip_aiding_ned_vel_command_valid_flags; -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) +typedef uint16_t mip_aiding_vel_ned_command_valid_flags; +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_vel_ned_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vel_ned_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) +static inline void extract_mip_aiding_vel_ned_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vel_ned_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -409,41 +411,40 @@ static inline void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_se } -struct mip_aiding_ned_vel_command +struct mip_aiding_vel_ned_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3f velocity; ///< NED velocity [m/s]. mip_vector3f uncertainty; ///< NED velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_ned_vel_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_vel_ned_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_ned_vel_command mip_aiding_ned_vel_command; +typedef struct mip_aiding_vel_ned_command mip_aiding_vel_ned_command; -void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self); -void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self); +void insert_mip_aiding_vel_ned_command(microstrain_serializer* serializer, const mip_aiding_vel_ned_command* self); +void extract_mip_aiding_vel_ned_command(microstrain_serializer* serializer, mip_aiding_vel_ned_command* self); -mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_vel_ned(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ned_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_vehicle_fixed_frame_velocity (0x13,0x2A) Vehicle Fixed Frame Velocity [C] -/// Estimate of velocity of the vehicle in the frame associated -/// with the given sensor ID. +///@defgroup c_aiding_vel_body_frame (0x13,0x2A) Vel Body Frame [C] +/// Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame. /// ///@{ -typedef uint16_t mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags; -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) +typedef uint16_t mip_aiding_vel_body_frame_command_valid_flags; +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_vel_body_frame_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vel_body_frame_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) +static inline void extract_mip_aiding_vel_body_frame_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vel_body_frame_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -451,29 +452,29 @@ static inline void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid } -struct mip_aiding_vehicle_fixed_frame_velocity_command +struct mip_aiding_vel_body_frame_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3f velocity; ///< [m/s] mip_vector3f uncertainty; ///< [m/s] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_vel_body_frame_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_vehicle_fixed_frame_velocity_command mip_aiding_vehicle_fixed_frame_velocity_command; +typedef struct mip_aiding_vel_body_frame_command mip_aiding_vel_body_frame_command; -void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self); -void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self); +void insert_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, const mip_aiding_vel_body_frame_command* self); +void extract_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, mip_aiding_vel_body_frame_command* self); -mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_vel_body_frame(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_body_frame_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_true_heading (0x13,0x31) True Heading [C] +///@defgroup c_aiding_heading_true (0x13,0x31) Heading True [C] /// ///@{ -struct mip_aiding_true_heading_command +struct mip_aiding_heading_true_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). @@ -481,12 +482,12 @@ struct mip_aiding_true_heading_command float uncertainty; ///< Cannot be 0 unless the valid flags are 0. uint16_t valid_flags; }; -typedef struct mip_aiding_true_heading_command mip_aiding_true_heading_command; +typedef struct mip_aiding_heading_true_command mip_aiding_heading_true_command; -void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self); -void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self); +void insert_mip_aiding_heading_true_command(microstrain_serializer* serializer, const mip_aiding_heading_true_command* self); +void extract_mip_aiding_heading_true_command(microstrain_serializer* serializer, mip_aiding_heading_true_command* self); -mip_cmd_result mip_aiding_true_heading(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); +mip_cmd_result mip_aiding_heading_true(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); ///@} /// diff --git a/src/c/mip/definitions/commands_filter.h b/src/c/mip/definitions/commands_filter.h index ac33425dc..00ceac8e5 100644 --- a/src/c/mip/definitions/commands_filter.h +++ b/src/c/mip/definitions/commands_filter.h @@ -761,9 +761,13 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(mip_interface* device /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_filter_antenna_offset (0x0D,0x13) Antenna Offset [C] -/// Set the sensor to GNSS antenna offset. +/// Configure the GNSS antenna offset. /// -/// This is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. +/// For 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. +/// +/// For 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center. +/// +/// This command should also be used for CV7 / GV7-INS NMEA Input over GPIO. /// /// The magnitude of the offset vector is limited to 10 meters /// @@ -1712,7 +1716,7 @@ mip_cmd_result mip_filter_default_reference_position(mip_interface* device); /// /// Adaptive measurements can be enabled/disabled without the need for providing the additional parameters. /// In this case, only the function selector and enable value are required; all other parameters will remain at their previous values. -/// When “auto-adaptive” is selected, the filter and limit parameters are ignored. +/// When auto-adaptive is selected, the filter and limit parameters are ignored. /// Instead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality. /// /// @@ -1879,7 +1883,7 @@ enum mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_HEADING = 5, ///< External heading input MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_ALTIMETER = 6, ///< External pressure altimeter input MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_MAGNETOMETER = 7, ///< External magnetomer input - MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_VEHICLE_FRAME_VEL = 8, ///< External vehicle frame velocity input + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_BODY_FRAME_VEL = 8, ///< External body frame velocity input MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_ALL = 65535, ///< Save/load/reset all options }; typedef enum mip_filter_aiding_measurement_enable_command_aiding_source mip_filter_aiding_measurement_enable_command_aiding_source; diff --git a/src/c/mip/definitions/data_filter.h b/src/c/mip/definitions/data_filter.h index 591778eb9..475f7573b 100644 --- a/src/c/mip/definitions/data_filter.h +++ b/src/c/mip/definitions/data_filter.h @@ -188,18 +188,21 @@ static inline void extract_mip_filter_status_flags(microstrain_serializer* seria enum mip_filter_aiding_measurement_type { - MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_DUAL_ANTENNA = 2, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING = 3, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_PRESSURE = 4, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_MAGNETOMETER = 5, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_SPEED = 6, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_ECEF = 33, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_LLH = 34, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_ECEF = 40, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_NED = 41, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_VEHICLE_FRAME = 42, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING_TRUE = 49, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_DUAL_ANTENNA = 2, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING = 3, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_PRESSURE = 4, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_MAGNETOMETER = 5, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_SPEED = 6, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_POS_ECEF = 33, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_POS_LLH = 34, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_HEIGHT_ABOVE_ELLIPSOID = 35, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_ECEF = 40, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_NED = 41, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_BODY_FRAME = 42, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_HEADING_TRUE = 49, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_MAGNETIC_FIELD = 50, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_PRESSURE = 51, ///< }; typedef enum mip_filter_aiding_measurement_type mip_filter_aiding_measurement_type; diff --git a/src/cpp/mip/definitions/commands_3dm.hpp b/src/cpp/mip/definitions/commands_3dm.hpp index c3a0b1128..d80419d5b 100644 --- a/src/cpp/mip/definitions/commands_3dm.hpp +++ b/src/cpp/mip/definitions/commands_3dm.hpp @@ -1445,6 +1445,8 @@ struct ConstellationSettings OptionFlags& operator|=(uint16_t val) { return *this = value | val; } OptionFlags& operator&=(uint16_t val) { return *this = value & val; } + bool l1saif() const { return (value & L1SAIF) > 0; } + void l1saif(bool val) { if(val) value |= L1SAIF; else value &= ~L1SAIF; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1569,6 +1571,12 @@ struct GnssSbasSettings SBASOptions& operator|=(uint16_t val) { return *this = value | val; } SBASOptions& operator&=(uint16_t val) { return *this = value & val; } + bool enableRanging() const { return (value & ENABLE_RANGING) > 0; } + void enableRanging(bool val) { if(val) value |= ENABLE_RANGING; else value &= ~ENABLE_RANGING; } + bool enableCorrections() const { return (value & ENABLE_CORRECTIONS) > 0; } + void enableCorrections(bool val) { if(val) value |= ENABLE_CORRECTIONS; else value &= ~ENABLE_CORRECTIONS; } + bool applyIntegrity() const { return (value & APPLY_INTEGRITY) > 0; } + void applyIntegrity(bool val) { if(val) value |= APPLY_INTEGRITY; else value &= ~APPLY_INTEGRITY; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2089,6 +2097,12 @@ struct GpioConfig PinMode& operator|=(uint8_t val) { return *this = value | val; } PinMode& operator&=(uint8_t val) { return *this = value & val; } + bool openDrain() const { return (value & OPEN_DRAIN) > 0; } + void openDrain(bool val) { if(val) value |= OPEN_DRAIN; else value &= ~OPEN_DRAIN; } + bool pulldown() const { return (value & PULLDOWN) > 0; } + void pulldown(bool val) { if(val) value |= PULLDOWN; else value &= ~PULLDOWN; } + bool pullup() const { return (value & PULLUP) > 0; } + void pullup(bool val) { if(val) value |= PULLUP; else value &= ~PULLUP; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2578,6 +2592,12 @@ struct GetEventTriggerStatus Status& operator|=(uint8_t val) { return *this = value | val; } Status& operator&=(uint8_t val) { return *this = value & val; } + bool active() const { return (value & ACTIVE) > 0; } + void active(bool val) { if(val) value |= ACTIVE; else value &= ~ACTIVE; } + bool enabled() const { return (value & ENABLED) > 0; } + void enabled(bool val) { if(val) value |= ENABLED; else value &= ~ENABLED; } + bool test() const { return (value & TEST) > 0; } + void test(bool val) { if(val) value |= TEST; else value &= ~TEST; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_aiding.cpp b/src/cpp/mip/definitions/commands_aiding.cpp index a477b84d9..b3f2627c2 100644 --- a/src/cpp/mip/definitions/commands_aiding.cpp +++ b/src/cpp/mip/definitions/commands_aiding.cpp @@ -209,7 +209,7 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); } -void AidingEchoControl::insert(Serializer& serializer) const +void EchoControl::insert(Serializer& serializer) const { serializer.insert(function); @@ -219,7 +219,7 @@ void AidingEchoControl::insert(Serializer& serializer) const } } -void AidingEchoControl::extract(Serializer& serializer) +void EchoControl::extract(Serializer& serializer) { serializer.extract(function); @@ -230,7 +230,7 @@ void AidingEchoControl::extract(Serializer& serializer) } } -TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode) +TypedResult writeEchoControl(C::mip_interface& device, EchoControl::Mode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -242,7 +242,7 @@ TypedResult writeAidingEchoControl(C::mip_interface& device, return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut) +TypedResult readEchoControl(C::mip_interface& device, EchoControl::Mode* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -251,7 +251,7 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -265,7 +265,7 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A } return result; } -TypedResult saveAidingEchoControl(C::mip_interface& device) +TypedResult saveEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -275,7 +275,7 @@ TypedResult saveAidingEchoControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -TypedResult loadAidingEchoControl(C::mip_interface& device) +TypedResult loadEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -285,7 +285,7 @@ TypedResult loadAidingEchoControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -TypedResult defaultAidingEchoControl(C::mip_interface& device) +TypedResult defaultEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -295,7 +295,7 @@ TypedResult defaultAidingEchoControl(C::mip_interface& device return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -void EcefPos::insert(Serializer& serializer) const +void PosEcef::insert(Serializer& serializer) const { serializer.insert(time); @@ -308,7 +308,7 @@ void EcefPos::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void EcefPos::extract(Serializer& serializer) +void PosEcef::extract(Serializer& serializer) { serializer.extract(time); @@ -322,7 +322,7 @@ void EcefPos::extract(Serializer& serializer) } -TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags) +TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, PosEcef::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -345,7 +345,7 @@ TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)serializer.length()); } -void LlhPos::insert(Serializer& serializer) const +void PosLlh::insert(Serializer& serializer) const { serializer.insert(time); @@ -362,7 +362,7 @@ void LlhPos::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void LlhPos::extract(Serializer& serializer) +void PosLlh::extract(Serializer& serializer) { serializer.extract(time); @@ -380,7 +380,7 @@ void LlhPos::extract(Serializer& serializer) } -TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags) +TypedResult posLlh(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, PosLlh::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -405,7 +405,7 @@ TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)serializer.length()); } -void Height::insert(Serializer& serializer) const +void HeightAboveEllipsoid::insert(Serializer& serializer) const { serializer.insert(time); @@ -418,7 +418,7 @@ void Height::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void Height::extract(Serializer& serializer) +void HeightAboveEllipsoid::extract(Serializer& serializer) { serializer.extract(time); @@ -432,7 +432,7 @@ void Height::extract(Serializer& serializer) } -TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) +TypedResult heightAboveEllipsoid(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -449,9 +449,9 @@ TypedResult height(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABOVE_ELLIPSOID, buffer, (uint8_t)serializer.length()); } -void EcefVel::insert(Serializer& serializer) const +void VelEcef::insert(Serializer& serializer) const { serializer.insert(time); @@ -464,7 +464,7 @@ void EcefVel::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void EcefVel::extract(Serializer& serializer) +void VelEcef::extract(Serializer& serializer) { serializer.extract(time); @@ -478,7 +478,7 @@ void EcefVel::extract(Serializer& serializer) } -TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags) +TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelEcef::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -501,7 +501,7 @@ TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)serializer.length()); } -void NedVel::insert(Serializer& serializer) const +void VelNed::insert(Serializer& serializer) const { serializer.insert(time); @@ -514,7 +514,7 @@ void NedVel::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void NedVel::extract(Serializer& serializer) +void VelNed::extract(Serializer& serializer) { serializer.extract(time); @@ -528,7 +528,7 @@ void NedVel::extract(Serializer& serializer) } -TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags) +TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelNed::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -551,7 +551,7 @@ TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)serializer.length()); } -void VehicleFixedFrameVelocity::insert(Serializer& serializer) const +void VelBodyFrame::insert(Serializer& serializer) const { serializer.insert(time); @@ -564,7 +564,7 @@ void VehicleFixedFrameVelocity::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void VehicleFixedFrameVelocity::extract(Serializer& serializer) +void VelBodyFrame::extract(Serializer& serializer) { serializer.extract(time); @@ -578,7 +578,7 @@ void VehicleFixedFrameVelocity::extract(Serializer& serializer) } -TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags) +TypedResult velBodyFrame(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelBodyFrame::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -599,9 +599,9 @@ TypedResult vehicleFixedFrameVelocity(C::mip_interfac assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ODOM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_BODY_FRAME, buffer, (uint8_t)serializer.length()); } -void TrueHeading::insert(Serializer& serializer) const +void HeadingTrue::insert(Serializer& serializer) const { serializer.insert(time); @@ -614,7 +614,7 @@ void TrueHeading::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void TrueHeading::extract(Serializer& serializer) +void HeadingTrue::extract(Serializer& serializer) { serializer.extract(time); @@ -628,7 +628,7 @@ void TrueHeading::extract(Serializer& serializer) } -TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) +TypedResult headingTrue(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); diff --git a/src/cpp/mip/definitions/commands_aiding.hpp b/src/cpp/mip/definitions/commands_aiding.hpp index dd4b9218e..95b9c0d3d 100644 --- a/src/cpp/mip/definitions/commands_aiding.hpp +++ b/src/cpp/mip/definitions/commands_aiding.hpp @@ -28,29 +28,29 @@ namespace commands_aiding { enum { - DESCRIPTOR_SET = 0x13, - - CMD_FRAME_CONFIG = 0x01, - CMD_LOCAL_FRAME = 0x03, - CMD_ECHO_CONTROL = 0x1F, - CMD_POS_LOCAL = 0x20, - CMD_POS_ECEF = 0x21, - CMD_POS_LLH = 0x22, - CMD_HEIGHT_ABS = 0x23, - CMD_HEIGHT_REL = 0x24, - CMD_VEL_ECEF = 0x28, - CMD_VEL_NED = 0x29, - CMD_VEL_ODOM = 0x2A, - CMD_WHEELSPEED = 0x2B, - CMD_HEADING_TRUE = 0x31, - CMD_MAGNETIC_FIELD = 0x32, - CMD_PRESSURE = 0x33, - CMD_DELTA_POSITION = 0x38, - CMD_DELTA_ATTITUDE = 0x39, - CMD_LOCAL_ANGULAR_RATE = 0x3A, - - REPLY_FRAME_CONFIG = 0x81, - REPLY_ECHO_CONTROL = 0x9F, + DESCRIPTOR_SET = 0x13, + + CMD_FRAME_CONFIG = 0x01, + CMD_LOCAL_FRAME = 0x03, + CMD_ECHO_CONTROL = 0x1F, + CMD_POS_LOCAL = 0x20, + CMD_POS_ECEF = 0x21, + CMD_POS_LLH = 0x22, + CMD_HEIGHT_ABOVE_ELLIPSOID = 0x23, + CMD_HEIGHT_REL = 0x24, + CMD_VEL_ECEF = 0x28, + CMD_VEL_NED = 0x29, + CMD_VEL_BODY_FRAME = 0x2A, + CMD_WHEELSPEED = 0x2B, + CMD_HEADING_TRUE = 0x31, + CMD_MAGNETIC_FIELD = 0x32, + CMD_PRESSURE = 0x33, + CMD_DELTA_POSITION = 0x38, + CMD_DELTA_ATTITUDE = 0x39, + CMD_ANGULAR_RATE_LOCAL = 0x3A, + + REPLY_FRAME_CONFIG = 0x81, + REPLY_ECHO_CONTROL = 0x9F, }; //////////////////////////////////////////////////////////////////////////////// @@ -83,8 +83,9 @@ struct Time //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_aiding_frame_config (0x13,0x01) Frame Config [CPP] -/// Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command -/// should mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame) +/// Defines an aiding frame associated with a specific sensor frame ID. +/// The frame ID used in this command should mirror the frame ID used in the aiding command +/// (if that aiding measurement is measured in this reference frame). /// /// This transform satisfies the following relationship: /// @@ -205,12 +206,12 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_aiding_echo_control (0x13,0x1F) Aiding Echo Control [CPP] +///@defgroup cpp_aiding_echo_control (0x13,0x1F) Echo Control [CPP] /// Controls command response behavior to external aiding commands /// ///@{ -struct AidingEchoControl +struct EchoControl { enum class Mode : uint8_t { @@ -227,7 +228,7 @@ struct AidingEchoControl static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_ECHO_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "AidingEchoControl"; + static constexpr const char* NAME = "EchoControl"; static constexpr const char* DOC_NAME = "Aiding Command Echo Control"; static constexpr const bool HAS_FUNCTION_SELECTOR = true; @@ -241,9 +242,9 @@ struct AidingEchoControl return std::make_tuple(std::ref(mode)); } - static AidingEchoControl create_sld_all(::mip::FunctionSelector function) + static EchoControl create_sld_all(::mip::FunctionSelector function) { - AidingEchoControl cmd; + EchoControl cmd; cmd.function = function; return cmd; } @@ -261,7 +262,7 @@ struct AidingEchoControl static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::REPLY_ECHO_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "AidingEchoControl::Response"; + static constexpr const char* NAME = "EchoControl::Response"; static constexpr const char* DOC_NAME = "Aiding Command Echo Control Response"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -281,21 +282,21 @@ struct AidingEchoControl }; }; -TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode); -TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut); -TypedResult saveAidingEchoControl(C::mip_interface& device); -TypedResult loadAidingEchoControl(C::mip_interface& device); -TypedResult defaultAidingEchoControl(C::mip_interface& device); +TypedResult writeEchoControl(C::mip_interface& device, EchoControl::Mode mode); +TypedResult readEchoControl(C::mip_interface& device, EchoControl::Mode* modeOut); +TypedResult saveEchoControl(C::mip_interface& device); +TypedResult loadEchoControl(C::mip_interface& device); +TypedResult defaultEchoControl(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_ecef_pos (0x13,0x21) Ecef Pos [CPP] +///@defgroup cpp_aiding_pos_ecef (0x13,0x21) Pos Ecef [CPP] /// Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system. /// ///@{ -struct EcefPos +struct PosEcef { struct ValidFlags : Bitfield { @@ -318,6 +319,12 @@ struct EcefPos ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { if(val) value |= X; else value &= ~X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { if(val) value |= Y; else value &= ~Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -332,7 +339,7 @@ struct EcefPos static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_POS_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "EcefPos"; + static constexpr const char* NAME = "PosEcef"; static constexpr const char* DOC_NAME = "ECEF Position"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -352,18 +359,19 @@ struct EcefPos typedef void Response; }; -TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags); +TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, PosEcef::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_llh_pos (0x13,0x22) Llh Pos [CPP] -/// Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. +///@defgroup cpp_aiding_pos_llh (0x13,0x22) Pos Llh [CPP] +/// Geodetic position aiding command. +/// Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. /// Uncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height. /// ///@{ -struct LlhPos +struct PosLlh { struct ValidFlags : Bitfield { @@ -386,6 +394,12 @@ struct LlhPos ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool latitude() const { return (value & LATITUDE) > 0; } + void latitude(bool val) { if(val) value |= LATITUDE; else value &= ~LATITUDE; } + bool longitude() const { return (value & LONGITUDE) > 0; } + void longitude(bool val) { if(val) value |= LONGITUDE; else value &= ~LONGITUDE; } + bool height() const { return (value & HEIGHT) > 0; } + void height(bool val) { if(val) value |= HEIGHT; else value &= ~HEIGHT; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -402,7 +416,7 @@ struct LlhPos static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_POS_LLH; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "LlhPos"; + static constexpr const char* NAME = "PosLlh"; static constexpr const char* DOC_NAME = "LLH Position"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -422,17 +436,17 @@ struct LlhPos typedef void Response; }; -TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags); +TypedResult posLlh(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, PosLlh::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_height (0x13,0x23) Height [CPP] -/// Estimated value of height. +///@defgroup cpp_aiding_height_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [CPP] +/// Estimated value of the height above ellipsoid. /// ///@{ -struct Height +struct HeightAboveEllipsoid { /// Parameters Time time; ///< Timestamp of the measurement. @@ -443,10 +457,10 @@ struct Height /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEIGHT_ABS; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEIGHT_ABOVE_ELLIPSOID; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "Height"; - static constexpr const char* DOC_NAME = "Height"; + static constexpr const char* NAME = "HeightAboveEllipsoid"; + static constexpr const char* DOC_NAME = "Height Above Ellipsoid"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; auto asTuple() const @@ -465,17 +479,17 @@ struct Height typedef void Response; }; -TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags); +TypedResult heightAboveEllipsoid(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_ecef_vel (0x13,0x28) Ecef Vel [CPP] +///@defgroup cpp_aiding_vel_ecef (0x13,0x28) Vel Ecef [CPP] /// ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame. /// ///@{ -struct EcefVel +struct VelEcef { struct ValidFlags : Bitfield { @@ -498,6 +512,12 @@ struct EcefVel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { if(val) value |= X; else value &= ~X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { if(val) value |= Y; else value &= ~Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -512,7 +532,7 @@ struct EcefVel static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "EcefVel"; + static constexpr const char* NAME = "VelEcef"; static constexpr const char* DOC_NAME = "ECEF Velocity"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -532,17 +552,17 @@ struct EcefVel typedef void Response; }; -TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags); +TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelEcef::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_ned_vel (0x13,0x29) Ned Vel [CPP] +///@defgroup cpp_aiding_vel_ned (0x13,0x29) Vel Ned [CPP] /// NED velocity aiding command. Coordinates are given in the local North-East-Down frame. /// ///@{ -struct NedVel +struct VelNed { struct ValidFlags : Bitfield { @@ -565,6 +585,12 @@ struct NedVel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { if(val) value |= X; else value &= ~X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { if(val) value |= Y; else value &= ~Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -579,7 +605,7 @@ struct NedVel static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_NED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "NedVel"; + static constexpr const char* NAME = "VelNed"; static constexpr const char* DOC_NAME = "NED Velocity"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -599,18 +625,17 @@ struct NedVel typedef void Response; }; -TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags); +TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelNed::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_vehicle_fixed_frame_velocity (0x13,0x2A) Vehicle Fixed Frame Velocity [CPP] -/// Estimate of velocity of the vehicle in the frame associated -/// with the given sensor ID. +///@defgroup cpp_aiding_vel_body_frame (0x13,0x2A) Vel Body Frame [CPP] +/// Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame. /// ///@{ -struct VehicleFixedFrameVelocity +struct VelBodyFrame { struct ValidFlags : Bitfield { @@ -633,6 +658,12 @@ struct VehicleFixedFrameVelocity ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { if(val) value |= X; else value &= ~X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { if(val) value |= Y; else value &= ~Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -645,10 +676,10 @@ struct VehicleFixedFrameVelocity /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_ODOM; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_BODY_FRAME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "VehicleFixedFrameVelocity"; - static constexpr const char* DOC_NAME = "Vehicle Frame Velocity"; + static constexpr const char* NAME = "VelBodyFrame"; + static constexpr const char* DOC_NAME = "Body Frame Velocity"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; auto asTuple() const @@ -667,16 +698,16 @@ struct VehicleFixedFrameVelocity typedef void Response; }; -TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags); +TypedResult velBodyFrame(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelBodyFrame::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_true_heading (0x13,0x31) True Heading [CPP] +///@defgroup cpp_aiding_heading_true (0x13,0x31) Heading True [CPP] /// ///@{ -struct TrueHeading +struct HeadingTrue { /// Parameters Time time; ///< Timestamp of the measurement. @@ -689,7 +720,7 @@ struct TrueHeading static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEADING_TRUE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "TrueHeading"; + static constexpr const char* NAME = "HeadingTrue"; static constexpr const char* DOC_NAME = "True Heading"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -709,7 +740,7 @@ struct TrueHeading typedef void Response; }; -TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); +TypedResult headingTrue(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); ///@} /// @@ -742,6 +773,12 @@ struct MagneticField ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { if(val) value |= X; else value &= ~X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { if(val) value |= Y; else value &= ~Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index 85fea5d5f..290b030dc 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -121,6 +121,60 @@ struct CommandedTestBitsGq7 : Bitfield CommandedTestBitsGq7& operator|=(uint32_t val) { return *this = value | val; } CommandedTestBitsGq7& operator&=(uint32_t val) { return *this = value & val; } + bool generalHardwareFault() const { return (value & GENERAL_HARDWARE_FAULT) > 0; } + void generalHardwareFault(bool val) { if(val) value |= GENERAL_HARDWARE_FAULT; else value &= ~GENERAL_HARDWARE_FAULT; } + bool generalFirmwareFault() const { return (value & GENERAL_FIRMWARE_FAULT) > 0; } + void generalFirmwareFault(bool val) { if(val) value |= GENERAL_FIRMWARE_FAULT; else value &= ~GENERAL_FIRMWARE_FAULT; } + bool timingOverload() const { return (value & TIMING_OVERLOAD) > 0; } + void timingOverload(bool val) { if(val) value |= TIMING_OVERLOAD; else value &= ~TIMING_OVERLOAD; } + bool bufferOverrun() const { return (value & BUFFER_OVERRUN) > 0; } + void bufferOverrun(bool val) { if(val) value |= BUFFER_OVERRUN; else value &= ~BUFFER_OVERRUN; } + uint32_t reserved() const { return (value & RESERVED) >> 4; } + void reserved(uint32_t val) { value = (value & ~RESERVED) | (val << 4); } + bool ipcImuFault() const { return (value & IPC_IMU_FAULT) > 0; } + void ipcImuFault(bool val) { if(val) value |= IPC_IMU_FAULT; else value &= ~IPC_IMU_FAULT; } + bool ipcNavFault() const { return (value & IPC_NAV_FAULT) > 0; } + void ipcNavFault(bool val) { if(val) value |= IPC_NAV_FAULT; else value &= ~IPC_NAV_FAULT; } + bool ipcGnssFault() const { return (value & IPC_GNSS_FAULT) > 0; } + void ipcGnssFault(bool val) { if(val) value |= IPC_GNSS_FAULT; else value &= ~IPC_GNSS_FAULT; } + bool commsFault() const { return (value & COMMS_FAULT) > 0; } + void commsFault(bool val) { if(val) value |= COMMS_FAULT; else value &= ~COMMS_FAULT; } + bool imuAccelFault() const { return (value & IMU_ACCEL_FAULT) > 0; } + void imuAccelFault(bool val) { if(val) value |= IMU_ACCEL_FAULT; else value &= ~IMU_ACCEL_FAULT; } + bool imuGyroFault() const { return (value & IMU_GYRO_FAULT) > 0; } + void imuGyroFault(bool val) { if(val) value |= IMU_GYRO_FAULT; else value &= ~IMU_GYRO_FAULT; } + bool imuMagFault() const { return (value & IMU_MAG_FAULT) > 0; } + void imuMagFault(bool val) { if(val) value |= IMU_MAG_FAULT; else value &= ~IMU_MAG_FAULT; } + bool imuPressFault() const { return (value & IMU_PRESS_FAULT) > 0; } + void imuPressFault(bool val) { if(val) value |= IMU_PRESS_FAULT; else value &= ~IMU_PRESS_FAULT; } + uint32_t imuReserved() const { return (value & IMU_RESERVED) >> 16; } + void imuReserved(uint32_t val) { value = (value & ~IMU_RESERVED) | (val << 16); } + bool imuCalError() const { return (value & IMU_CAL_ERROR) > 0; } + void imuCalError(bool val) { if(val) value |= IMU_CAL_ERROR; else value &= ~IMU_CAL_ERROR; } + bool imuGeneralFault() const { return (value & IMU_GENERAL_FAULT) > 0; } + void imuGeneralFault(bool val) { if(val) value |= IMU_GENERAL_FAULT; else value &= ~IMU_GENERAL_FAULT; } + uint32_t filtReserved() const { return (value & FILT_RESERVED) >> 20; } + void filtReserved(uint32_t val) { value = (value & ~FILT_RESERVED) | (val << 20); } + bool filtSolutionFault() const { return (value & FILT_SOLUTION_FAULT) > 0; } + void filtSolutionFault(bool val) { if(val) value |= FILT_SOLUTION_FAULT; else value &= ~FILT_SOLUTION_FAULT; } + bool filtGeneralFault() const { return (value & FILT_GENERAL_FAULT) > 0; } + void filtGeneralFault(bool val) { if(val) value |= FILT_GENERAL_FAULT; else value &= ~FILT_GENERAL_FAULT; } + bool gnssReceiver1Fault() const { return (value & GNSS_RECEIVER1_FAULT) > 0; } + void gnssReceiver1Fault(bool val) { if(val) value |= GNSS_RECEIVER1_FAULT; else value &= ~GNSS_RECEIVER1_FAULT; } + bool gnssAntenna1Fault() const { return (value & GNSS_ANTENNA1_FAULT) > 0; } + void gnssAntenna1Fault(bool val) { if(val) value |= GNSS_ANTENNA1_FAULT; else value &= ~GNSS_ANTENNA1_FAULT; } + bool gnssReceiver2Fault() const { return (value & GNSS_RECEIVER2_FAULT) > 0; } + void gnssReceiver2Fault(bool val) { if(val) value |= GNSS_RECEIVER2_FAULT; else value &= ~GNSS_RECEIVER2_FAULT; } + bool gnssAntenna2Fault() const { return (value & GNSS_ANTENNA2_FAULT) > 0; } + void gnssAntenna2Fault(bool val) { if(val) value |= GNSS_ANTENNA2_FAULT; else value &= ~GNSS_ANTENNA2_FAULT; } + bool gnssRtcmFailure() const { return (value & GNSS_RTCM_FAILURE) > 0; } + void gnssRtcmFailure(bool val) { if(val) value |= GNSS_RTCM_FAILURE; else value &= ~GNSS_RTCM_FAILURE; } + bool gnssRtkFault() const { return (value & GNSS_RTK_FAULT) > 0; } + void gnssRtkFault(bool val) { if(val) value |= GNSS_RTK_FAULT; else value &= ~GNSS_RTK_FAULT; } + bool gnssSolutionFault() const { return (value & GNSS_SOLUTION_FAULT) > 0; } + void gnssSolutionFault(bool val) { if(val) value |= GNSS_SOLUTION_FAULT; else value &= ~GNSS_SOLUTION_FAULT; } + bool gnssGeneralFault() const { return (value & GNSS_GENERAL_FAULT) > 0; } + void gnssGeneralFault(bool val) { if(val) value |= GNSS_GENERAL_FAULT; else value &= ~GNSS_GENERAL_FAULT; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_filter.hpp b/src/cpp/mip/definitions/commands_filter.hpp index bab66c5db..e9ab7d652 100644 --- a/src/cpp/mip/definitions/commands_filter.hpp +++ b/src/cpp/mip/definitions/commands_filter.hpp @@ -312,6 +312,20 @@ struct EstimationControl EnableFlags& operator|=(uint16_t val) { return *this = value | val; } EnableFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gyroBias() const { return (value & GYRO_BIAS) > 0; } + void gyroBias(bool val) { if(val) value |= GYRO_BIAS; else value &= ~GYRO_BIAS; } + bool accelBias() const { return (value & ACCEL_BIAS) > 0; } + void accelBias(bool val) { if(val) value |= ACCEL_BIAS; else value &= ~ACCEL_BIAS; } + bool gyroScaleFactor() const { return (value & GYRO_SCALE_FACTOR) > 0; } + void gyroScaleFactor(bool val) { if(val) value |= GYRO_SCALE_FACTOR; else value &= ~GYRO_SCALE_FACTOR; } + bool accelScaleFactor() const { return (value & ACCEL_SCALE_FACTOR) > 0; } + void accelScaleFactor(bool val) { if(val) value |= ACCEL_SCALE_FACTOR; else value &= ~ACCEL_SCALE_FACTOR; } + bool antennaOffset() const { return (value & ANTENNA_OFFSET) > 0; } + void antennaOffset(bool val) { if(val) value |= ANTENNA_OFFSET; else value &= ~ANTENNA_OFFSET; } + bool autoMagHardIron() const { return (value & AUTO_MAG_HARD_IRON) > 0; } + void autoMagHardIron(bool val) { if(val) value |= AUTO_MAG_HARD_IRON; else value &= ~AUTO_MAG_HARD_IRON; } + bool autoMagSoftIron() const { return (value & AUTO_MAG_SOFT_IRON) > 0; } + void autoMagSoftIron(bool val) { if(val) value |= AUTO_MAG_SOFT_IRON; else value &= ~AUTO_MAG_SOFT_IRON; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -580,6 +594,12 @@ struct TareOrientation MipTareAxes& operator|=(uint8_t val) { return *this = value | val; } MipTareAxes& operator&=(uint8_t val) { return *this = value & val; } + bool roll() const { return (value & ROLL) > 0; } + void roll(bool val) { if(val) value |= ROLL; else value &= ~ROLL; } + bool pitch() const { return (value & PITCH) > 0; } + void pitch(bool val) { if(val) value |= PITCH; else value &= ~PITCH; } + bool yaw() const { return (value & YAW) > 0; } + void yaw(bool val) { if(val) value |= YAW; else value &= ~YAW; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1142,9 +1162,13 @@ TypedResult defaultSensorToVehicleOffset(C::mip_interface /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_filter_antenna_offset (0x0D,0x13) Antenna Offset [CPP] -/// Set the sensor to GNSS antenna offset. +/// Configure the GNSS antenna offset. /// -/// This is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. +/// For 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. +/// +/// For 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center. +/// +/// This command should also be used for CV7 / GV7-INS NMEA Input over GPIO. /// /// The magnitude of the offset vector is limited to 10 meters /// @@ -3061,7 +3085,7 @@ TypedResult defaultReferencePosition(C::mip_interface& device /// /// Adaptive measurements can be enabled/disabled without the need for providing the additional parameters. /// In this case, only the function selector and enable value are required; all other parameters will remain at their previous values. -/// When “auto-adaptive” is selected, the filter and limit parameters are ignored. +/// When auto-adaptive is selected, the filter and limit parameters are ignored. /// Instead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality. /// /// @@ -3598,6 +3622,14 @@ struct InitializationConfiguration AlignmentSelector& operator|=(uint8_t val) { return *this = value | val; } AlignmentSelector& operator&=(uint8_t val) { return *this = value & val; } + bool dualAntenna() const { return (value & DUAL_ANTENNA) > 0; } + void dualAntenna(bool val) { if(val) value |= DUAL_ANTENNA; else value &= ~DUAL_ANTENNA; } + bool kinematic() const { return (value & KINEMATIC) > 0; } + void kinematic(bool val) { if(val) value |= KINEMATIC; else value &= ~KINEMATIC; } + bool magnetometer() const { return (value & MAGNETOMETER) > 0; } + void magnetometer(bool val) { if(val) value |= MAGNETOMETER; else value &= ~MAGNETOMETER; } + bool external() const { return (value & EXTERNAL) > 0; } + void external(bool val) { if(val) value |= EXTERNAL; else value &= ~EXTERNAL; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_rtk.hpp b/src/cpp/mip/definitions/commands_rtk.hpp index 144a6839c..97b9137b5 100644 --- a/src/cpp/mip/definitions/commands_rtk.hpp +++ b/src/cpp/mip/definitions/commands_rtk.hpp @@ -112,6 +112,28 @@ struct GetStatusFlags StatusFlagsLegacy& operator|=(uint32_t val) { return *this = value | val; } StatusFlagsLegacy& operator&=(uint32_t val) { return *this = value & val; } + uint32_t controllerstate() const { return (value & CONTROLLERSTATE) >> 0; } + void controllerstate(uint32_t val) { value = (value & ~CONTROLLERSTATE) | (val << 0); } + uint32_t platformstate() const { return (value & PLATFORMSTATE) >> 3; } + void platformstate(uint32_t val) { value = (value & ~PLATFORMSTATE) | (val << 3); } + uint32_t controllerstatuscode() const { return (value & CONTROLLERSTATUSCODE) >> 8; } + void controllerstatuscode(uint32_t val) { value = (value & ~CONTROLLERSTATUSCODE) | (val << 8); } + uint32_t platformstatuscode() const { return (value & PLATFORMSTATUSCODE) >> 11; } + void platformstatuscode(uint32_t val) { value = (value & ~PLATFORMSTATUSCODE) | (val << 11); } + uint32_t resetcode() const { return (value & RESETCODE) >> 14; } + void resetcode(uint32_t val) { value = (value & ~RESETCODE) | (val << 14); } + uint32_t signalquality() const { return (value & SIGNALQUALITY) >> 16; } + void signalquality(uint32_t val) { value = (value & ~SIGNALQUALITY) | (val << 16); } + uint32_t reserved() const { return (value & RESERVED) >> 20; } + void reserved(uint32_t val) { value = (value & ~RESERVED) | (val << 20); } + uint32_t rssi() const { return (value & RSSI) >> 20; } + void rssi(uint32_t val) { value = (value & ~RSSI) | (val << 20); } + uint32_t rsrp() const { return (value & RSRP) >> 26; } + void rsrp(uint32_t val) { value = (value & ~RSRP) | (val << 26); } + uint32_t rsrq() const { return (value & RSRQ) >> 28; } + void rsrq(uint32_t val) { value = (value & ~RSRQ) | (val << 28); } + uint32_t sinr() const { return (value & SINR) >> 30; } + void sinr(uint32_t val) { value = (value & ~SINR) | (val << 30); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -145,6 +167,30 @@ struct GetStatusFlags StatusFlags& operator|=(uint32_t val) { return *this = value | val; } StatusFlags& operator&=(uint32_t val) { return *this = value & val; } + uint32_t modemState() const { return (value & MODEM_STATE) >> 0; } + void modemState(uint32_t val) { value = (value & ~MODEM_STATE) | (val << 0); } + uint32_t connectionType() const { return (value & CONNECTION_TYPE) >> 4; } + void connectionType(uint32_t val) { value = (value & ~CONNECTION_TYPE) | (val << 4); } + uint32_t rssi() const { return (value & RSSI) >> 8; } + void rssi(uint32_t val) { value = (value & ~RSSI) | (val << 8); } + uint32_t signalQuality() const { return (value & SIGNAL_QUALITY) >> 16; } + void signalQuality(uint32_t val) { value = (value & ~SIGNAL_QUALITY) | (val << 16); } + uint32_t towerChangeIndicator() const { return (value & TOWER_CHANGE_INDICATOR) >> 20; } + void towerChangeIndicator(uint32_t val) { value = (value & ~TOWER_CHANGE_INDICATOR) | (val << 20); } + bool nmeaTimeout() const { return (value & NMEA_TIMEOUT) > 0; } + void nmeaTimeout(bool val) { if(val) value |= NMEA_TIMEOUT; else value &= ~NMEA_TIMEOUT; } + bool serverTimeout() const { return (value & SERVER_TIMEOUT) > 0; } + void serverTimeout(bool val) { if(val) value |= SERVER_TIMEOUT; else value &= ~SERVER_TIMEOUT; } + bool correctionsTimeout() const { return (value & CORRECTIONS_TIMEOUT) > 0; } + void correctionsTimeout(bool val) { if(val) value |= CORRECTIONS_TIMEOUT; else value &= ~CORRECTIONS_TIMEOUT; } + bool deviceOutOfRange() const { return (value & DEVICE_OUT_OF_RANGE) > 0; } + void deviceOutOfRange(bool val) { if(val) value |= DEVICE_OUT_OF_RANGE; else value &= ~DEVICE_OUT_OF_RANGE; } + bool correctionsUnavailable() const { return (value & CORRECTIONS_UNAVAILABLE) > 0; } + void correctionsUnavailable(bool val) { if(val) value |= CORRECTIONS_UNAVAILABLE; else value &= ~CORRECTIONS_UNAVAILABLE; } + bool reserved() const { return (value & RESERVED) > 0; } + void reserved(bool val) { if(val) value |= RESERVED; else value &= ~RESERVED; } + uint32_t version() const { return (value & VERSION) >> 30; } + void version(uint32_t val) { value = (value & ~VERSION) | (val << 30); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -690,6 +736,12 @@ struct ServiceStatus ServiceFlags& operator|=(uint8_t val) { return *this = value | val; } ServiceFlags& operator&=(uint8_t val) { return *this = value & val; } + bool throttle() const { return (value & THROTTLE) > 0; } + void throttle(bool val) { if(val) value |= THROTTLE; else value &= ~THROTTLE; } + bool correctionsUnavailable() const { return (value & CORRECTIONS_UNAVAILABLE) > 0; } + void correctionsUnavailable(bool val) { if(val) value |= CORRECTIONS_UNAVAILABLE; else value &= ~CORRECTIONS_UNAVAILABLE; } + uint8_t reserved() const { return (value & RESERVED) >> 2; } + void reserved(uint8_t val) { value = (value & ~RESERVED) | (val << 2); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_filter.hpp b/src/cpp/mip/definitions/data_filter.hpp index 2d5c32261..a64a5c054 100644 --- a/src/cpp/mip/definitions/data_filter.hpp +++ b/src/cpp/mip/definitions/data_filter.hpp @@ -165,6 +165,62 @@ struct FilterStatusFlags : Bitfield FilterStatusFlags& operator|=(uint16_t val) { return *this = value | val; } FilterStatusFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gx5InitNoAttitude() const { return (value & GX5_INIT_NO_ATTITUDE) > 0; } + void gx5InitNoAttitude(bool val) { if(val) value |= GX5_INIT_NO_ATTITUDE; else value &= ~GX5_INIT_NO_ATTITUDE; } + bool gx5InitNoPositionVelocity() const { return (value & GX5_INIT_NO_POSITION_VELOCITY) > 0; } + void gx5InitNoPositionVelocity(bool val) { if(val) value |= GX5_INIT_NO_POSITION_VELOCITY; else value &= ~GX5_INIT_NO_POSITION_VELOCITY; } + bool gx5RunImuUnavailable() const { return (value & GX5_RUN_IMU_UNAVAILABLE) > 0; } + void gx5RunImuUnavailable(bool val) { if(val) value |= GX5_RUN_IMU_UNAVAILABLE; else value &= ~GX5_RUN_IMU_UNAVAILABLE; } + bool gx5RunGpsUnavailable() const { return (value & GX5_RUN_GPS_UNAVAILABLE) > 0; } + void gx5RunGpsUnavailable(bool val) { if(val) value |= GX5_RUN_GPS_UNAVAILABLE; else value &= ~GX5_RUN_GPS_UNAVAILABLE; } + bool gx5RunMatrixSingularity() const { return (value & GX5_RUN_MATRIX_SINGULARITY) > 0; } + void gx5RunMatrixSingularity(bool val) { if(val) value |= GX5_RUN_MATRIX_SINGULARITY; else value &= ~GX5_RUN_MATRIX_SINGULARITY; } + bool gx5RunPositionCovarianceWarning() const { return (value & GX5_RUN_POSITION_COVARIANCE_WARNING) > 0; } + void gx5RunPositionCovarianceWarning(bool val) { if(val) value |= GX5_RUN_POSITION_COVARIANCE_WARNING; else value &= ~GX5_RUN_POSITION_COVARIANCE_WARNING; } + bool gx5RunVelocityCovarianceWarning() const { return (value & GX5_RUN_VELOCITY_COVARIANCE_WARNING) > 0; } + void gx5RunVelocityCovarianceWarning(bool val) { if(val) value |= GX5_RUN_VELOCITY_COVARIANCE_WARNING; else value &= ~GX5_RUN_VELOCITY_COVARIANCE_WARNING; } + bool gx5RunAttitudeCovarianceWarning() const { return (value & GX5_RUN_ATTITUDE_COVARIANCE_WARNING) > 0; } + void gx5RunAttitudeCovarianceWarning(bool val) { if(val) value |= GX5_RUN_ATTITUDE_COVARIANCE_WARNING; else value &= ~GX5_RUN_ATTITUDE_COVARIANCE_WARNING; } + bool gx5RunNanInSolutionWarning() const { return (value & GX5_RUN_NAN_IN_SOLUTION_WARNING) > 0; } + void gx5RunNanInSolutionWarning(bool val) { if(val) value |= GX5_RUN_NAN_IN_SOLUTION_WARNING; else value &= ~GX5_RUN_NAN_IN_SOLUTION_WARNING; } + bool gx5RunGyroBiasEstHighWarning() const { return (value & GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING) > 0; } + void gx5RunGyroBiasEstHighWarning(bool val) { if(val) value |= GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING; else value &= ~GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING; } + bool gx5RunAccelBiasEstHighWarning() const { return (value & GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING) > 0; } + void gx5RunAccelBiasEstHighWarning(bool val) { if(val) value |= GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING; else value &= ~GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING; } + bool gx5RunGyroScaleFactorEstHighWarning() const { return (value & GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING) > 0; } + void gx5RunGyroScaleFactorEstHighWarning(bool val) { if(val) value |= GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING; else value &= ~GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING; } + bool gx5RunAccelScaleFactorEstHighWarning() const { return (value & GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING) > 0; } + void gx5RunAccelScaleFactorEstHighWarning(bool val) { if(val) value |= GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING; else value &= ~GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING; } + bool gx5RunMagBiasEstHighWarning() const { return (value & GX5_RUN_MAG_BIAS_EST_HIGH_WARNING) > 0; } + void gx5RunMagBiasEstHighWarning(bool val) { if(val) value |= GX5_RUN_MAG_BIAS_EST_HIGH_WARNING; else value &= ~GX5_RUN_MAG_BIAS_EST_HIGH_WARNING; } + bool gx5RunAntOffsetCorrectionEstHighWarning() const { return (value & GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING) > 0; } + void gx5RunAntOffsetCorrectionEstHighWarning(bool val) { if(val) value |= GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING; else value &= ~GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING; } + bool gx5RunMagHardIronEstHighWarning() const { return (value & GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING) > 0; } + void gx5RunMagHardIronEstHighWarning(bool val) { if(val) value |= GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING; else value &= ~GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING; } + bool gx5RunMagSoftIronEstHighWarning() const { return (value & GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING) > 0; } + void gx5RunMagSoftIronEstHighWarning(bool val) { if(val) value |= GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING; else value &= ~GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING; } + uint16_t gq7FilterCondition() const { return (value & GQ7_FILTER_CONDITION) >> 0; } + void gq7FilterCondition(uint16_t val) { value = (value & ~GQ7_FILTER_CONDITION) | (val << 0); } + bool gq7RollPitchWarning() const { return (value & GQ7_ROLL_PITCH_WARNING) > 0; } + void gq7RollPitchWarning(bool val) { if(val) value |= GQ7_ROLL_PITCH_WARNING; else value &= ~GQ7_ROLL_PITCH_WARNING; } + bool gq7HeadingWarning() const { return (value & GQ7_HEADING_WARNING) > 0; } + void gq7HeadingWarning(bool val) { if(val) value |= GQ7_HEADING_WARNING; else value &= ~GQ7_HEADING_WARNING; } + bool gq7PositionWarning() const { return (value & GQ7_POSITION_WARNING) > 0; } + void gq7PositionWarning(bool val) { if(val) value |= GQ7_POSITION_WARNING; else value &= ~GQ7_POSITION_WARNING; } + bool gq7VelocityWarning() const { return (value & GQ7_VELOCITY_WARNING) > 0; } + void gq7VelocityWarning(bool val) { if(val) value |= GQ7_VELOCITY_WARNING; else value &= ~GQ7_VELOCITY_WARNING; } + bool gq7ImuBiasWarning() const { return (value & GQ7_IMU_BIAS_WARNING) > 0; } + void gq7ImuBiasWarning(bool val) { if(val) value |= GQ7_IMU_BIAS_WARNING; else value &= ~GQ7_IMU_BIAS_WARNING; } + bool gq7GnssClkWarning() const { return (value & GQ7_GNSS_CLK_WARNING) > 0; } + void gq7GnssClkWarning(bool val) { if(val) value |= GQ7_GNSS_CLK_WARNING; else value &= ~GQ7_GNSS_CLK_WARNING; } + bool gq7AntennaLeverArmWarning() const { return (value & GQ7_ANTENNA_LEVER_ARM_WARNING) > 0; } + void gq7AntennaLeverArmWarning(bool val) { if(val) value |= GQ7_ANTENNA_LEVER_ARM_WARNING; else value &= ~GQ7_ANTENNA_LEVER_ARM_WARNING; } + bool gq7MountingTransformWarning() const { return (value & GQ7_MOUNTING_TRANSFORM_WARNING) > 0; } + void gq7MountingTransformWarning(bool val) { if(val) value |= GQ7_MOUNTING_TRANSFORM_WARNING; else value &= ~GQ7_MOUNTING_TRANSFORM_WARNING; } + bool gq7TimeSyncWarning() const { return (value & GQ7_TIME_SYNC_WARNING) > 0; } + void gq7TimeSyncWarning(bool val) { if(val) value |= GQ7_TIME_SYNC_WARNING; else value &= ~GQ7_TIME_SYNC_WARNING; } + uint16_t gq7SolutionError() const { return (value & GQ7_SOLUTION_ERROR) >> 12; } + void gq7SolutionError(uint16_t val) { value = (value & ~GQ7_SOLUTION_ERROR) | (val << 12); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -211,6 +267,18 @@ struct FilterMeasurementIndicator : Bitfield FilterMeasurementIndicator& operator|=(uint8_t val) { return *this = value | val; } FilterMeasurementIndicator& operator&=(uint8_t val) { return *this = value & val; } + bool enabled() const { return (value & ENABLED) > 0; } + void enabled(bool val) { if(val) value |= ENABLED; else value &= ~ENABLED; } + bool used() const { return (value & USED) > 0; } + void used(bool val) { if(val) value |= USED; else value &= ~USED; } + bool residualHighWarning() const { return (value & RESIDUAL_HIGH_WARNING) > 0; } + void residualHighWarning(bool val) { if(val) value |= RESIDUAL_HIGH_WARNING; else value &= ~RESIDUAL_HIGH_WARNING; } + bool sampleTimeWarning() const { return (value & SAMPLE_TIME_WARNING) > 0; } + void sampleTimeWarning(bool val) { if(val) value |= SAMPLE_TIME_WARNING; else value &= ~SAMPLE_TIME_WARNING; } + bool configurationError() const { return (value & CONFIGURATION_ERROR) > 0; } + void configurationError(bool val) { if(val) value |= CONFIGURATION_ERROR; else value &= ~CONFIGURATION_ERROR; } + bool maxNumMeasExceeded() const { return (value & MAX_NUM_MEAS_EXCEEDED) > 0; } + void maxNumMeasExceeded(bool val) { if(val) value |= MAX_NUM_MEAS_EXCEEDED; else value &= ~MAX_NUM_MEAS_EXCEEDED; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -248,6 +316,38 @@ struct GnssAidStatusFlags : Bitfield GnssAidStatusFlags& operator|=(uint16_t val) { return *this = value | val; } GnssAidStatusFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tightCoupling() const { return (value & TIGHT_COUPLING) > 0; } + void tightCoupling(bool val) { if(val) value |= TIGHT_COUPLING; else value &= ~TIGHT_COUPLING; } + bool differential() const { return (value & DIFFERENTIAL) > 0; } + void differential(bool val) { if(val) value |= DIFFERENTIAL; else value &= ~DIFFERENTIAL; } + bool integerFix() const { return (value & INTEGER_FIX) > 0; } + void integerFix(bool val) { if(val) value |= INTEGER_FIX; else value &= ~INTEGER_FIX; } + bool gpsL1() const { return (value & GPS_L1) > 0; } + void gpsL1(bool val) { if(val) value |= GPS_L1; else value &= ~GPS_L1; } + bool gpsL2() const { return (value & GPS_L2) > 0; } + void gpsL2(bool val) { if(val) value |= GPS_L2; else value &= ~GPS_L2; } + bool gpsL5() const { return (value & GPS_L5) > 0; } + void gpsL5(bool val) { if(val) value |= GPS_L5; else value &= ~GPS_L5; } + bool gloL1() const { return (value & GLO_L1) > 0; } + void gloL1(bool val) { if(val) value |= GLO_L1; else value &= ~GLO_L1; } + bool gloL2() const { return (value & GLO_L2) > 0; } + void gloL2(bool val) { if(val) value |= GLO_L2; else value &= ~GLO_L2; } + bool galE1() const { return (value & GAL_E1) > 0; } + void galE1(bool val) { if(val) value |= GAL_E1; else value &= ~GAL_E1; } + bool galE5() const { return (value & GAL_E5) > 0; } + void galE5(bool val) { if(val) value |= GAL_E5; else value &= ~GAL_E5; } + bool galE6() const { return (value & GAL_E6) > 0; } + void galE6(bool val) { if(val) value |= GAL_E6; else value &= ~GAL_E6; } + bool beiB1() const { return (value & BEI_B1) > 0; } + void beiB1(bool val) { if(val) value |= BEI_B1; else value &= ~BEI_B1; } + bool beiB2() const { return (value & BEI_B2) > 0; } + void beiB2(bool val) { if(val) value |= BEI_B2; else value &= ~BEI_B2; } + bool beiB3() const { return (value & BEI_B3) > 0; } + void beiB3(bool val) { if(val) value |= BEI_B3; else value &= ~BEI_B3; } + bool noFix() const { return (value & NO_FIX) > 0; } + void noFix(bool val) { if(val) value |= NO_FIX; else value &= ~NO_FIX; } + bool configError() const { return (value & CONFIG_ERROR) > 0; } + void configError(bool val) { if(val) value |= CONFIG_ERROR; else value &= ~CONFIG_ERROR; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2438,6 +2538,12 @@ struct GnssDualAntennaStatus DualAntennaStatusFlags& operator|=(uint16_t val) { return *this = value | val; } DualAntennaStatusFlags& operator&=(uint16_t val) { return *this = value & val; } + bool rcv1DataValid() const { return (value & RCV_1_DATA_VALID) > 0; } + void rcv1DataValid(bool val) { if(val) value |= RCV_1_DATA_VALID; else value &= ~RCV_1_DATA_VALID; } + bool rcv2DataValid() const { return (value & RCV_2_DATA_VALID) > 0; } + void rcv2DataValid(bool val) { if(val) value |= RCV_2_DATA_VALID; else value &= ~RCV_2_DATA_VALID; } + bool antennaOffsetsValid() const { return (value & ANTENNA_OFFSETS_VALID) > 0; } + void antennaOffsetsValid(bool val) { if(val) value |= ANTENNA_OFFSETS_VALID; else value &= ~ANTENNA_OFFSETS_VALID; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_gnss.hpp b/src/cpp/mip/definitions/data_gnss.hpp index 6a07b7573..509f6f82d 100644 --- a/src/cpp/mip/definitions/data_gnss.hpp +++ b/src/cpp/mip/definitions/data_gnss.hpp @@ -198,6 +198,18 @@ struct PosLlh ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool latLon() const { return (value & LAT_LON) > 0; } + void latLon(bool val) { if(val) value |= LAT_LON; else value &= ~LAT_LON; } + bool ellipsoidHeight() const { return (value & ELLIPSOID_HEIGHT) > 0; } + void ellipsoidHeight(bool val) { if(val) value |= ELLIPSOID_HEIGHT; else value &= ~ELLIPSOID_HEIGHT; } + bool mslHeight() const { return (value & MSL_HEIGHT) > 0; } + void mslHeight(bool val) { if(val) value |= MSL_HEIGHT; else value &= ~MSL_HEIGHT; } + bool horizontalAccuracy() const { return (value & HORIZONTAL_ACCURACY) > 0; } + void horizontalAccuracy(bool val) { if(val) value |= HORIZONTAL_ACCURACY; else value &= ~HORIZONTAL_ACCURACY; } + bool verticalAccuracy() const { return (value & VERTICAL_ACCURACY) > 0; } + void verticalAccuracy(bool val) { if(val) value |= VERTICAL_ACCURACY; else value &= ~VERTICAL_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -265,6 +277,12 @@ struct PosEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool position() const { return (value & POSITION) > 0; } + void position(bool val) { if(val) value |= POSITION; else value &= ~POSITION; } + bool positionAccuracy() const { return (value & POSITION_ACCURACY) > 0; } + void positionAccuracy(bool val) { if(val) value |= POSITION_ACCURACY; else value &= ~POSITION_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -332,6 +350,20 @@ struct VelNed ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool velocity() const { return (value & VELOCITY) > 0; } + void velocity(bool val) { if(val) value |= VELOCITY; else value &= ~VELOCITY; } + bool speed3d() const { return (value & SPEED_3D) > 0; } + void speed3d(bool val) { if(val) value |= SPEED_3D; else value &= ~SPEED_3D; } + bool groundSpeed() const { return (value & GROUND_SPEED) > 0; } + void groundSpeed(bool val) { if(val) value |= GROUND_SPEED; else value &= ~GROUND_SPEED; } + bool heading() const { return (value & HEADING) > 0; } + void heading(bool val) { if(val) value |= HEADING; else value &= ~HEADING; } + bool speedAccuracy() const { return (value & SPEED_ACCURACY) > 0; } + void speedAccuracy(bool val) { if(val) value |= SPEED_ACCURACY; else value &= ~SPEED_ACCURACY; } + bool headingAccuracy() const { return (value & HEADING_ACCURACY) > 0; } + void headingAccuracy(bool val) { if(val) value |= HEADING_ACCURACY; else value &= ~HEADING_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -399,6 +431,12 @@ struct VelEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool velocity() const { return (value & VELOCITY) > 0; } + void velocity(bool val) { if(val) value |= VELOCITY; else value &= ~VELOCITY; } + bool velocityAccuracy() const { return (value & VELOCITY_ACCURACY) > 0; } + void velocityAccuracy(bool val) { if(val) value |= VELOCITY_ACCURACY; else value &= ~VELOCITY_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -467,6 +505,22 @@ struct Dop ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gdop() const { return (value & GDOP) > 0; } + void gdop(bool val) { if(val) value |= GDOP; else value &= ~GDOP; } + bool pdop() const { return (value & PDOP) > 0; } + void pdop(bool val) { if(val) value |= PDOP; else value &= ~PDOP; } + bool hdop() const { return (value & HDOP) > 0; } + void hdop(bool val) { if(val) value |= HDOP; else value &= ~HDOP; } + bool vdop() const { return (value & VDOP) > 0; } + void vdop(bool val) { if(val) value |= VDOP; else value &= ~VDOP; } + bool tdop() const { return (value & TDOP) > 0; } + void tdop(bool val) { if(val) value |= TDOP; else value &= ~TDOP; } + bool ndop() const { return (value & NDOP) > 0; } + void ndop(bool val) { if(val) value |= NDOP; else value &= ~NDOP; } + bool edop() const { return (value & EDOP) > 0; } + void edop(bool val) { if(val) value |= EDOP; else value &= ~EDOP; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -535,6 +589,12 @@ struct UtcTime ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gnssDateTime() const { return (value & GNSS_DATE_TIME) > 0; } + void gnssDateTime(bool val) { if(val) value |= GNSS_DATE_TIME; else value &= ~GNSS_DATE_TIME; } + bool leapSecondsKnown() const { return (value & LEAP_SECONDS_KNOWN) > 0; } + void leapSecondsKnown(bool val) { if(val) value |= LEAP_SECONDS_KNOWN; else value &= ~LEAP_SECONDS_KNOWN; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -603,6 +663,12 @@ struct GpsTime ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -667,6 +733,14 @@ struct ClockInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool bias() const { return (value & BIAS) > 0; } + void bias(bool val) { if(val) value |= BIAS; else value &= ~BIAS; } + bool drift() const { return (value & DRIFT) > 0; } + void drift(bool val) { if(val) value |= DRIFT; else value &= ~DRIFT; } + bool accuracyEstimate() const { return (value & ACCURACY_ESTIMATE) > 0; } + void accuracyEstimate(bool val) { if(val) value |= ACCURACY_ESTIMATE; else value &= ~ACCURACY_ESTIMATE; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -742,6 +816,10 @@ struct FixInfo FixFlags& operator|=(uint16_t val) { return *this = value | val; } FixFlags& operator&=(uint16_t val) { return *this = value & val; } + bool sbasUsed() const { return (value & SBAS_USED) > 0; } + void sbasUsed(bool val) { if(val) value |= SBAS_USED; else value &= ~SBAS_USED; } + bool dgnssUsed() const { return (value & DGNSS_USED) > 0; } + void dgnssUsed(bool val) { if(val) value |= DGNSS_USED; else value &= ~DGNSS_USED; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -767,6 +845,14 @@ struct FixInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool fixType() const { return (value & FIX_TYPE) > 0; } + void fixType(bool val) { if(val) value |= FIX_TYPE; else value &= ~FIX_TYPE; } + bool numSv() const { return (value & NUM_SV) > 0; } + void numSv(bool val) { if(val) value |= NUM_SV; else value &= ~NUM_SV; } + bool fixFlags() const { return (value & FIX_FLAGS) > 0; } + void fixFlags(bool val) { if(val) value |= FIX_FLAGS; else value &= ~FIX_FLAGS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -832,6 +918,10 @@ struct SvInfo SVFlags& operator|=(uint16_t val) { return *this = value | val; } SVFlags& operator&=(uint16_t val) { return *this = value & val; } + bool usedForNavigation() const { return (value & USED_FOR_NAVIGATION) > 0; } + void usedForNavigation(bool val) { if(val) value |= USED_FOR_NAVIGATION; else value &= ~USED_FOR_NAVIGATION; } + bool healthy() const { return (value & HEALTHY) > 0; } + void healthy(bool val) { if(val) value |= HEALTHY; else value &= ~HEALTHY; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -860,6 +950,20 @@ struct SvInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool channel() const { return (value & CHANNEL) > 0; } + void channel(bool val) { if(val) value |= CHANNEL; else value &= ~CHANNEL; } + bool svId() const { return (value & SV_ID) > 0; } + void svId(bool val) { if(val) value |= SV_ID; else value &= ~SV_ID; } + bool carrierNoiseRatio() const { return (value & CARRIER_NOISE_RATIO) > 0; } + void carrierNoiseRatio(bool val) { if(val) value |= CARRIER_NOISE_RATIO; else value &= ~CARRIER_NOISE_RATIO; } + bool azimuth() const { return (value & AZIMUTH) > 0; } + void azimuth(bool val) { if(val) value |= AZIMUTH; else value &= ~AZIMUTH; } + bool elevation() const { return (value & ELEVATION) > 0; } + void elevation(bool val) { if(val) value |= ELEVATION; else value &= ~ELEVATION; } + bool svFlags() const { return (value & SV_FLAGS) > 0; } + void svFlags(bool val) { if(val) value |= SV_FLAGS; else value &= ~SV_FLAGS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -951,6 +1055,14 @@ struct HwStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool sensorState() const { return (value & SENSOR_STATE) > 0; } + void sensorState(bool val) { if(val) value |= SENSOR_STATE; else value &= ~SENSOR_STATE; } + bool antennaState() const { return (value & ANTENNA_STATE) > 0; } + void antennaState(bool val) { if(val) value |= ANTENNA_STATE; else value &= ~ANTENNA_STATE; } + bool antennaPower() const { return (value & ANTENNA_POWER) > 0; } + void antennaPower(bool val) { if(val) value |= ANTENNA_POWER; else value &= ~ANTENNA_POWER; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1029,6 +1141,16 @@ struct DgpsInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool age() const { return (value & AGE) > 0; } + void age(bool val) { if(val) value |= AGE; else value &= ~AGE; } + bool baseStationId() const { return (value & BASE_STATION_ID) > 0; } + void baseStationId(bool val) { if(val) value |= BASE_STATION_ID; else value &= ~BASE_STATION_ID; } + bool baseStationStatus() const { return (value & BASE_STATION_STATUS) > 0; } + void baseStationStatus(bool val) { if(val) value |= BASE_STATION_STATUS; else value &= ~BASE_STATION_STATUS; } + bool numChannels() const { return (value & NUM_CHANNELS) > 0; } + void numChannels(bool val) { if(val) value |= NUM_CHANNELS; else value &= ~NUM_CHANNELS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1098,6 +1220,16 @@ struct DgpsChannel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool id() const { return (value & ID) > 0; } + void id(bool val) { if(val) value |= ID; else value &= ~ID; } + bool age() const { return (value & AGE) > 0; } + void age(bool val) { if(val) value |= AGE; else value &= ~AGE; } + bool rangeCorrection() const { return (value & RANGE_CORRECTION) > 0; } + void rangeCorrection(bool val) { if(val) value |= RANGE_CORRECTION; else value &= ~RANGE_CORRECTION; } + bool rangeRateCorrection() const { return (value & RANGE_RATE_CORRECTION) > 0; } + void rangeRateCorrection(bool val) { if(val) value |= RANGE_RATE_CORRECTION; else value &= ~RANGE_RATE_CORRECTION; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1167,6 +1299,16 @@ struct ClockInfo2 ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool bias() const { return (value & BIAS) > 0; } + void bias(bool val) { if(val) value |= BIAS; else value &= ~BIAS; } + bool drift() const { return (value & DRIFT) > 0; } + void drift(bool val) { if(val) value |= DRIFT; else value &= ~DRIFT; } + bool biasAccuracy() const { return (value & BIAS_ACCURACY) > 0; } + void biasAccuracy(bool val) { if(val) value |= BIAS_ACCURACY; else value &= ~BIAS_ACCURACY; } + bool driftAccuracy() const { return (value & DRIFT_ACCURACY) > 0; } + void driftAccuracy(bool val) { if(val) value |= DRIFT_ACCURACY; else value &= ~DRIFT_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1230,6 +1372,8 @@ struct GpsLeapSeconds ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool leapSeconds() const { return (value & LEAP_SECONDS) > 0; } + void leapSeconds(bool val) { if(val) value |= LEAP_SECONDS; else value &= ~LEAP_SECONDS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1293,6 +1437,14 @@ struct SbasInfo SbasStatus& operator|=(uint8_t val) { return *this = value | val; } SbasStatus& operator&=(uint8_t val) { return *this = value & val; } + bool rangeAvailable() const { return (value & RANGE_AVAILABLE) > 0; } + void rangeAvailable(bool val) { if(val) value |= RANGE_AVAILABLE; else value &= ~RANGE_AVAILABLE; } + bool correctionsAvailable() const { return (value & CORRECTIONS_AVAILABLE) > 0; } + void correctionsAvailable(bool val) { if(val) value |= CORRECTIONS_AVAILABLE; else value &= ~CORRECTIONS_AVAILABLE; } + bool integrityAvailable() const { return (value & INTEGRITY_AVAILABLE) > 0; } + void integrityAvailable(bool val) { if(val) value |= INTEGRITY_AVAILABLE; else value &= ~INTEGRITY_AVAILABLE; } + bool testMode() const { return (value & TEST_MODE) > 0; } + void testMode(bool val) { if(val) value |= TEST_MODE; else value &= ~TEST_MODE; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1321,6 +1473,20 @@ struct SbasInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } + bool sbasSystem() const { return (value & SBAS_SYSTEM) > 0; } + void sbasSystem(bool val) { if(val) value |= SBAS_SYSTEM; else value &= ~SBAS_SYSTEM; } + bool sbasId() const { return (value & SBAS_ID) > 0; } + void sbasId(bool val) { if(val) value |= SBAS_ID; else value &= ~SBAS_ID; } + bool count() const { return (value & COUNT) > 0; } + void count(bool val) { if(val) value |= COUNT; else value &= ~COUNT; } + bool sbasStatus() const { return (value & SBAS_STATUS) > 0; } + void sbasStatus(bool val) { if(val) value |= SBAS_STATUS; else value &= ~SBAS_STATUS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1411,6 +1577,14 @@ struct SbasCorrection ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool udrei() const { return (value & UDREI) > 0; } + void udrei(bool val) { if(val) value |= UDREI; else value &= ~UDREI; } + bool pseudorangeCorrection() const { return (value & PSEUDORANGE_CORRECTION) > 0; } + void pseudorangeCorrection(bool val) { if(val) value |= PSEUDORANGE_CORRECTION; else value &= ~PSEUDORANGE_CORRECTION; } + bool ionoCorrection() const { return (value & IONO_CORRECTION) > 0; } + void ionoCorrection(bool val) { if(val) value |= IONO_CORRECTION; else value &= ~IONO_CORRECTION; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1506,6 +1680,14 @@ struct RfErrorDetection ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool rfBand() const { return (value & RF_BAND) > 0; } + void rfBand(bool val) { if(val) value |= RF_BAND; else value &= ~RF_BAND; } + bool jammingState() const { return (value & JAMMING_STATE) > 0; } + void jammingState(bool val) { if(val) value |= JAMMING_STATE; else value &= ~JAMMING_STATE; } + bool spoofingState() const { return (value & SPOOFING_STATE) > 0; } + void spoofingState(bool val) { if(val) value |= SPOOFING_STATE; else value &= ~SPOOFING_STATE; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1579,6 +1761,24 @@ struct BaseStationInfo IndicatorFlags& operator|=(uint16_t val) { return *this = value | val; } IndicatorFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gps() const { return (value & GPS) > 0; } + void gps(bool val) { if(val) value |= GPS; else value &= ~GPS; } + bool glonass() const { return (value & GLONASS) > 0; } + void glonass(bool val) { if(val) value |= GLONASS; else value &= ~GLONASS; } + bool galileo() const { return (value & GALILEO) > 0; } + void galileo(bool val) { if(val) value |= GALILEO; else value &= ~GALILEO; } + bool beidou() const { return (value & BEIDOU) > 0; } + void beidou(bool val) { if(val) value |= BEIDOU; else value &= ~BEIDOU; } + bool refStation() const { return (value & REF_STATION) > 0; } + void refStation(bool val) { if(val) value |= REF_STATION; else value &= ~REF_STATION; } + bool singleReceiver() const { return (value & SINGLE_RECEIVER) > 0; } + void singleReceiver(bool val) { if(val) value |= SINGLE_RECEIVER; else value &= ~SINGLE_RECEIVER; } + bool quarterCycleBit1() const { return (value & QUARTER_CYCLE_BIT1) > 0; } + void quarterCycleBit1(bool val) { if(val) value |= QUARTER_CYCLE_BIT1; else value &= ~QUARTER_CYCLE_BIT1; } + bool quarterCycleBit2() const { return (value & QUARTER_CYCLE_BIT2) > 0; } + void quarterCycleBit2(bool val) { if(val) value |= QUARTER_CYCLE_BIT2; else value &= ~QUARTER_CYCLE_BIT2; } + uint16_t quarterCycleBits() const { return (value & QUARTER_CYCLE_BITS) >> 6; } + void quarterCycleBits(uint16_t val) { value = (value & ~QUARTER_CYCLE_BITS) | (val << 6); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1607,6 +1807,20 @@ struct BaseStationInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } + bool ecefPosition() const { return (value & ECEF_POSITION) > 0; } + void ecefPosition(bool val) { if(val) value |= ECEF_POSITION; else value &= ~ECEF_POSITION; } + bool height() const { return (value & HEIGHT) > 0; } + void height(bool val) { if(val) value |= HEIGHT; else value &= ~HEIGHT; } + bool stationId() const { return (value & STATION_ID) > 0; } + void stationId(bool val) { if(val) value |= STATION_ID; else value &= ~STATION_ID; } + bool indicators() const { return (value & INDICATORS) > 0; } + void indicators(bool val) { if(val) value |= INDICATORS; else value &= ~INDICATORS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1679,6 +1893,24 @@ struct RtkCorrectionsStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } + bool epochStatus() const { return (value & EPOCH_STATUS) > 0; } + void epochStatus(bool val) { if(val) value |= EPOCH_STATUS; else value &= ~EPOCH_STATUS; } + bool dongleStatus() const { return (value & DONGLE_STATUS) > 0; } + void dongleStatus(bool val) { if(val) value |= DONGLE_STATUS; else value &= ~DONGLE_STATUS; } + bool gpsLatency() const { return (value & GPS_LATENCY) > 0; } + void gpsLatency(bool val) { if(val) value |= GPS_LATENCY; else value &= ~GPS_LATENCY; } + bool glonassLatency() const { return (value & GLONASS_LATENCY) > 0; } + void glonassLatency(bool val) { if(val) value |= GLONASS_LATENCY; else value &= ~GLONASS_LATENCY; } + bool galileoLatency() const { return (value & GALILEO_LATENCY) > 0; } + void galileoLatency(bool val) { if(val) value |= GALILEO_LATENCY; else value &= ~GALILEO_LATENCY; } + bool beidouLatency() const { return (value & BEIDOU_LATENCY) > 0; } + void beidouLatency(bool val) { if(val) value |= BEIDOU_LATENCY; else value &= ~BEIDOU_LATENCY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1709,6 +1941,24 @@ struct RtkCorrectionsStatus EpochStatus& operator|=(uint16_t val) { return *this = value | val; } EpochStatus& operator&=(uint16_t val) { return *this = value & val; } + bool antennaLocationReceived() const { return (value & ANTENNA_LOCATION_RECEIVED) > 0; } + void antennaLocationReceived(bool val) { if(val) value |= ANTENNA_LOCATION_RECEIVED; else value &= ~ANTENNA_LOCATION_RECEIVED; } + bool antennaDescriptionReceived() const { return (value & ANTENNA_DESCRIPTION_RECEIVED) > 0; } + void antennaDescriptionReceived(bool val) { if(val) value |= ANTENNA_DESCRIPTION_RECEIVED; else value &= ~ANTENNA_DESCRIPTION_RECEIVED; } + bool gpsReceived() const { return (value & GPS_RECEIVED) > 0; } + void gpsReceived(bool val) { if(val) value |= GPS_RECEIVED; else value &= ~GPS_RECEIVED; } + bool glonassReceived() const { return (value & GLONASS_RECEIVED) > 0; } + void glonassReceived(bool val) { if(val) value |= GLONASS_RECEIVED; else value &= ~GLONASS_RECEIVED; } + bool galileoReceived() const { return (value & GALILEO_RECEIVED) > 0; } + void galileoReceived(bool val) { if(val) value |= GALILEO_RECEIVED; else value &= ~GALILEO_RECEIVED; } + bool beidouReceived() const { return (value & BEIDOU_RECEIVED) > 0; } + void beidouReceived(bool val) { if(val) value |= BEIDOU_RECEIVED; else value &= ~BEIDOU_RECEIVED; } + bool usingGpsMsmMessages() const { return (value & USING_GPS_MSM_MESSAGES) > 0; } + void usingGpsMsmMessages(bool val) { if(val) value |= USING_GPS_MSM_MESSAGES; else value &= ~USING_GPS_MSM_MESSAGES; } + bool usingGlonassMsmMessages() const { return (value & USING_GLONASS_MSM_MESSAGES) > 0; } + void usingGlonassMsmMessages(bool val) { if(val) value |= USING_GLONASS_MSM_MESSAGES; else value &= ~USING_GLONASS_MSM_MESSAGES; } + bool dongleStatusReadFailed() const { return (value & DONGLE_STATUS_READ_FAILED) > 0; } + void dongleStatusReadFailed(bool val) { if(val) value |= DONGLE_STATUS_READ_FAILED; else value &= ~DONGLE_STATUS_READ_FAILED; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1784,6 +2034,22 @@ struct SatelliteStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } + bool gnssId() const { return (value & GNSS_ID) > 0; } + void gnssId(bool val) { if(val) value |= GNSS_ID; else value &= ~GNSS_ID; } + bool satelliteId() const { return (value & SATELLITE_ID) > 0; } + void satelliteId(bool val) { if(val) value |= SATELLITE_ID; else value &= ~SATELLITE_ID; } + bool elevation() const { return (value & ELEVATION) > 0; } + void elevation(bool val) { if(val) value |= ELEVATION; else value &= ~ELEVATION; } + bool azimuth() const { return (value & AZIMUTH) > 0; } + void azimuth(bool val) { if(val) value |= AZIMUTH; else value &= ~AZIMUTH; } + bool health() const { return (value & HEALTH) > 0; } + void health(bool val) { if(val) value |= HEALTH; else value &= ~HEALTH; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1878,6 +2144,40 @@ struct Raw ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } + bool receiverId() const { return (value & RECEIVER_ID) > 0; } + void receiverId(bool val) { if(val) value |= RECEIVER_ID; else value &= ~RECEIVER_ID; } + bool trackingChannel() const { return (value & TRACKING_CHANNEL) > 0; } + void trackingChannel(bool val) { if(val) value |= TRACKING_CHANNEL; else value &= ~TRACKING_CHANNEL; } + bool gnssId() const { return (value & GNSS_ID) > 0; } + void gnssId(bool val) { if(val) value |= GNSS_ID; else value &= ~GNSS_ID; } + bool satelliteId() const { return (value & SATELLITE_ID) > 0; } + void satelliteId(bool val) { if(val) value |= SATELLITE_ID; else value &= ~SATELLITE_ID; } + bool signalId() const { return (value & SIGNAL_ID) > 0; } + void signalId(bool val) { if(val) value |= SIGNAL_ID; else value &= ~SIGNAL_ID; } + bool signalStrength() const { return (value & SIGNAL_STRENGTH) > 0; } + void signalStrength(bool val) { if(val) value |= SIGNAL_STRENGTH; else value &= ~SIGNAL_STRENGTH; } + bool quality() const { return (value & QUALITY) > 0; } + void quality(bool val) { if(val) value |= QUALITY; else value &= ~QUALITY; } + bool pseudorange() const { return (value & PSEUDORANGE) > 0; } + void pseudorange(bool val) { if(val) value |= PSEUDORANGE; else value &= ~PSEUDORANGE; } + bool carrierPhase() const { return (value & CARRIER_PHASE) > 0; } + void carrierPhase(bool val) { if(val) value |= CARRIER_PHASE; else value &= ~CARRIER_PHASE; } + bool doppler() const { return (value & DOPPLER) > 0; } + void doppler(bool val) { if(val) value |= DOPPLER; else value &= ~DOPPLER; } + bool rangeUncertainty() const { return (value & RANGE_UNCERTAINTY) > 0; } + void rangeUncertainty(bool val) { if(val) value |= RANGE_UNCERTAINTY; else value &= ~RANGE_UNCERTAINTY; } + bool carrierPhaseUncertainty() const { return (value & CARRIER_PHASE_UNCERTAINTY) > 0; } + void carrierPhaseUncertainty(bool val) { if(val) value |= CARRIER_PHASE_UNCERTAINTY; else value &= ~CARRIER_PHASE_UNCERTAINTY; } + bool dopplerUncertainty() const { return (value & DOPPLER_UNCERTAINTY) > 0; } + void dopplerUncertainty(bool val) { if(val) value |= DOPPLER_UNCERTAINTY; else value &= ~DOPPLER_UNCERTAINTY; } + bool lockTime() const { return (value & LOCK_TIME) > 0; } + void lockTime(bool val) { if(val) value |= LOCK_TIME; else value &= ~LOCK_TIME; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1957,6 +2257,12 @@ struct GpsEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool ephemeris() const { return (value & EPHEMERIS) > 0; } + void ephemeris(bool val) { if(val) value |= EPHEMERIS; else value &= ~EPHEMERIS; } + bool modernData() const { return (value & MODERN_DATA) > 0; } + void modernData(bool val) { if(val) value |= MODERN_DATA; else value &= ~MODERN_DATA; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2051,6 +2357,12 @@ struct GalileoEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool ephemeris() const { return (value & EPHEMERIS) > 0; } + void ephemeris(bool val) { if(val) value |= EPHEMERIS; else value &= ~EPHEMERIS; } + bool modernData() const { return (value & MODERN_DATA) > 0; } + void modernData(bool val) { if(val) value |= MODERN_DATA; else value &= ~MODERN_DATA; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2144,6 +2456,10 @@ struct GloEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool ephemeris() const { return (value & EPHEMERIS) > 0; } + void ephemeris(bool val) { if(val) value |= EPHEMERIS; else value &= ~EPHEMERIS; } + bool flags() const { return (value & FLAGS) > 0; } + void flags(bool val) { if(val) value |= FLAGS; else value &= ~FLAGS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2231,6 +2547,16 @@ struct GpsIonoCorr ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } + bool alpha() const { return (value & ALPHA) > 0; } + void alpha(bool val) { if(val) value |= ALPHA; else value &= ~ALPHA; } + bool beta() const { return (value & BETA) > 0; } + void beta(bool val) { if(val) value |= BETA; else value &= ~BETA; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2298,6 +2624,16 @@ struct GalileoIonoCorr ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } + bool alpha() const { return (value & ALPHA) > 0; } + void alpha(bool val) { if(val) value |= ALPHA; else value &= ~ALPHA; } + bool disturbanceFlags() const { return (value & DISTURBANCE_FLAGS) > 0; } + void disturbanceFlags(bool val) { if(val) value |= DISTURBANCE_FLAGS; else value &= ~DISTURBANCE_FLAGS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_sensor.hpp b/src/cpp/mip/definitions/data_sensor.hpp index be7f62301..dd6eb1217 100644 --- a/src/cpp/mip/definitions/data_sensor.hpp +++ b/src/cpp/mip/definitions/data_sensor.hpp @@ -765,6 +765,16 @@ struct GpsTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool ppsValid() const { return (value & PPS_VALID) > 0; } + void ppsValid(bool val) { if(val) value |= PPS_VALID; else value &= ~PPS_VALID; } + bool timeRefresh() const { return (value & TIME_REFRESH) > 0; } + void timeRefresh(bool val) { if(val) value |= TIME_REFRESH; else value &= ~TIME_REFRESH; } + bool timeInitialized() const { return (value & TIME_INITIALIZED) > 0; } + void timeInitialized(bool val) { if(val) value |= TIME_INITIALIZED; else value &= ~TIME_INITIALIZED; } + bool towValid() const { return (value & TOW_VALID) > 0; } + void towValid(bool val) { if(val) value |= TOW_VALID; else value &= ~TOW_VALID; } + bool weekNumberValid() const { return (value & WEEK_NUMBER_VALID) > 0; } + void weekNumberValid(bool val) { if(val) value |= WEEK_NUMBER_VALID; else value &= ~WEEK_NUMBER_VALID; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -960,6 +970,26 @@ struct OverrangeStatus Status& operator|=(uint16_t val) { return *this = value | val; } Status& operator&=(uint16_t val) { return *this = value & val; } + bool accelX() const { return (value & ACCEL_X) > 0; } + void accelX(bool val) { if(val) value |= ACCEL_X; else value &= ~ACCEL_X; } + bool accelY() const { return (value & ACCEL_Y) > 0; } + void accelY(bool val) { if(val) value |= ACCEL_Y; else value &= ~ACCEL_Y; } + bool accelZ() const { return (value & ACCEL_Z) > 0; } + void accelZ(bool val) { if(val) value |= ACCEL_Z; else value &= ~ACCEL_Z; } + bool gyroX() const { return (value & GYRO_X) > 0; } + void gyroX(bool val) { if(val) value |= GYRO_X; else value &= ~GYRO_X; } + bool gyroY() const { return (value & GYRO_Y) > 0; } + void gyroY(bool val) { if(val) value |= GYRO_Y; else value &= ~GYRO_Y; } + bool gyroZ() const { return (value & GYRO_Z) > 0; } + void gyroZ(bool val) { if(val) value |= GYRO_Z; else value &= ~GYRO_Z; } + bool magX() const { return (value & MAG_X) > 0; } + void magX(bool val) { if(val) value |= MAG_X; else value &= ~MAG_X; } + bool magY() const { return (value & MAG_Y) > 0; } + void magY(bool val) { if(val) value |= MAG_Y; else value &= ~MAG_Y; } + bool magZ() const { return (value & MAG_Z) > 0; } + void magZ(bool val) { if(val) value |= MAG_Z; else value &= ~MAG_Z; } + bool press() const { return (value & PRESS) > 0; } + void press(bool val) { if(val) value |= PRESS; else value &= ~PRESS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_shared.hpp b/src/cpp/mip/definitions/data_shared.hpp index c7cc64d22..2896fb33b 100644 --- a/src/cpp/mip/definitions/data_shared.hpp +++ b/src/cpp/mip/definitions/data_shared.hpp @@ -206,6 +206,12 @@ struct GpsTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } + uint16_t timeValid() const { return (value & TIME_VALID) >> 0; } + void timeValid(uint16_t val) { value = (value & ~TIME_VALID) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -411,6 +417,8 @@ struct ExternalTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool nanoseconds() const { return (value & NANOSECONDS) > 0; } + void nanoseconds(bool val) { if(val) value |= NANOSECONDS; else value &= ~NANOSECONDS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -483,6 +491,8 @@ struct ExternalTimeDelta ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool dtNanos() const { return (value & DT_NANOS) > 0; } + void dtNanos(bool val) { if(val) value |= DT_NANOS; else value &= ~DT_NANOS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; From d5fcf36990958e16f4a579b024b6c8a0e81bdc68 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 24 Jul 2024 14:11:32 -0400 Subject: [PATCH 054/147] Update to latest metadata definitions. --- .../mip/metadata/definitions/commands_3dm.hpp | 114 +++++++-------- .../metadata/definitions/commands_aiding.hpp | 136 +++++++++--------- .../metadata/definitions/commands_base.hpp | 22 +-- .../metadata/definitions/commands_filter.hpp | 114 +++++++-------- .../metadata/definitions/commands_gnss.hpp | 8 +- .../mip/metadata/definitions/commands_rtk.hpp | 4 +- .../metadata/definitions/commands_system.hpp | 2 +- .../mip/metadata/definitions/data_filter.hpp | 47 +++--- .../mip/metadata/definitions/data_gnss.hpp | 18 +-- .../mip/metadata/definitions/data_sensor.hpp | 32 ++--- .../mip/metadata/definitions/data_shared.hpp | 20 +-- .../mip/metadata/definitions/data_system.hpp | 14 +- 12 files changed, 267 insertions(+), 264 deletions(-) diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index df5f7dd75..54572ff85 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -48,7 +48,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollImuMessage", /* .title = */ "None", - /* .docs = */ "Poll the device for an IMU message with the specified format\n\nThis function polls for an IMU message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set IMU Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an IMU Data packet.", + /* .docs = */ "Poll the device for an IMU message with the specified formatnnThis function polls for an IMU message using the provided format. The resulting messagenwill maintain the order of descriptors sent in the command and any unrecognizedndescriptors are ignored. If the format is not provided, the device will attempt to use thenstored format (set with the Set IMU Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as an IMU Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -95,7 +95,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollGnssMessage", /* .title = */ "None", - /* .docs = */ "Poll the device for an GNSS message with the specified format\n\nThis function polls for a GNSS message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set GNSS Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a GNSS Data packet.", + /* .docs = */ "Poll the device for an GNSS message with the specified formatnnThis function polls for a GNSS message using the provided format. The resulting messagenwill maintain the order of descriptors sent in the command and any unrecognizedndescriptors are ignored. If the format is not provided, the device will attempt to use thenstored format (set with the Set GNSS Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as a GNSS Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -142,7 +142,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollFilterMessage", /* .title = */ "None", - /* .docs = */ "Poll the device for an Estimation Filter message with the specified format\n\nThis function polls for an Estimation Filter message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Estimation Filter Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an Estimation Filter Data packet.", + /* .docs = */ "Poll the device for an Estimation Filter message with the specified formatnnThis function polls for an Estimation Filter message using the provided format. The resulting messagenwill maintain the order of descriptors sent in the command and any unrecognizedndescriptors are ignored. If the format is not provided, the device will attempt to use thenstored format (set with the Set Estimation Filter Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as an Estimation Filter Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -219,7 +219,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuMessageFormat", /* .title = */ "None", - /* .docs = */ "Set, read, or save the format of the IMU data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .docs = */ "Set, read, or save the format of the IMU data packet.nnThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -296,7 +296,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpsMessageFormat", /* .title = */ "None", - /* .docs = */ "Set, read, or save the format of the GNSS data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .docs = */ "Set, read, or save the format of the GNSS data packet.nnThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -373,7 +373,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FilterMessageFormat", /* .title = */ "None", - /* .docs = */ "Set, read, or save the format of the Estimation Filter data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .docs = */ "Set, read, or save the format of the Estimation Filter data packet.nnThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -419,7 +419,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuGetBaseRate", /* .title = */ "Get IMU Data Base Rate", - /* .docs = */ "Get the base rate for the IMU data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the IMU Message Format Command to set streaming data at a specified rate.", + /* .docs = */ "Get the base rate for the IMU data in HznnThis is the fastest rate for this type of data available on the device.nThis is used in conjunction with the IMU Message Format Command to set streaming data at a specified rate.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -465,7 +465,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpsGetBaseRate", /* .title = */ "Get GNSS Data Base Rate", - /* .docs = */ "Get the base rate for the GNSS data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the GNSS Message Format Command to set streaming data at a specified rate.", + /* .docs = */ "Get the base rate for the GNSS data in HznnThis is the fastest rate for this type of data available on the device.nThis is used in conjunction with the GNSS Message Format Command to set streaming data at a specified rate.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -511,7 +511,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FilterGetBaseRate", /* .title = */ "Get Estimation Filter Data Base Rate", - /* .docs = */ "Get the base rate for the Estimation Filter data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the Estimation Filter Message Format Command to set streaming data at a specified rate.", + /* .docs = */ "Get the base rate for the Estimation Filter data in HznnThis is the fastest rate for this type of data available on the device.nThis is used in conjunction with the Estimation Filter Message Format Command to set streaming data at a specified rate.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -567,7 +567,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollData", /* .title = */ "None", - /* .docs = */ "Poll the device for a message with the specified descriptor set and format.\n\nThis function polls for a message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a normal Data packet.", + /* .docs = */ "Poll the device for a message with the specified descriptor set and format.nnThis function polls for a message using the provided format. The resulting messagenwill maintain the order of descriptors sent in the command and any unrecognizedndescriptors are ignored. If the format is not provided, the device will attempt to use thenstored format (set with the Set Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as a normal Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -729,7 +729,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MessageFormat", /* .title = */ "None", - /* .docs = */ "Set, read, or save the format for a given data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .docs = */ "Set, read, or save the format for a given data packet.nnThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -751,8 +751,8 @@ struct MetadataFor { 5, "VTG", "Course over Ground. Source can be the Filter or GNSS1/2 datasets." }, { 6, "HDT", "Heading, True. Source can be the Filter or GNSS1/2 datasets." }, { 7, "ZDA", "Time & Date. Source must be the GNSS1 or GNSS2 datasets." }, - { 129, "PKRA", "Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED." }, - { 130, "PKRR", "Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED." }, + { 129, "MSRA", "MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED." }, + { 130, "MSRR", "MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED." }, }; static constexpr inline EnumInfo value = { @@ -876,7 +876,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::NmeaPollData", /* .title = */ "None", - /* .docs = */ "Poll the device for a NMEA message with the specified format.\n\nThis function polls for a NMEA message using the provided format.\nIf the format is not provided, the device will attempt to use the\nstored format (set with the Set NMEA Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as normal NMEA messages.", + /* .docs = */ "Poll the device for a NMEA message with the specified format.nnThis function polls for a NMEA message using the provided format.nIf the format is not provided, the device will attempt to use thenstored format (set with the Set NMEA Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as normal NMEA messages.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -975,7 +975,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::DeviceSettings", /* .title = */ "None", - /* .docs = */ "Save, Load, or Reset to Default the values for all device settings.\n\nWhen a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory.\n\nThis command should have a long timeout as it may take up to 1 second to complete.", + /* .docs = */ "Save, Load, or Reset to Default the values for all device settings.nnWhen a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory.nnThis command should have a long timeout as it may take up to 1 second to complete.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {false, false, true, true, true, true}, @@ -1034,7 +1034,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::UartBaudrate", /* .title = */ "None", - /* .docs = */ "Read, Save, Load, or Reset to Default the baud rate of the main communication channel.\n\nFor all functions except 0x01 (use new settings), the new baud rate value is ignored.\nPlease see the device user manual for supported baud rates.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", + /* .docs = */ "Read, Save, Load, or Reset to Default the baud rate of the main communication channel.nnFor all functions except 0x01 (use new settings), the new baud rate value is ignored.nPlease see the device user manual for supported baud rates.nnThe device will wait until all incoming and outgoing data has been sent, upnto a maximum of 250 ms, before applying any change.nnNo guarantee is provided as to what happens to commands issued during thisndelay period; They may or may not be processed and any responses aren'tnguaranteed to be at one rate or the other. The same applies to data packets.nnIt is highly recommended that the device be idle before issuing this commandnand that it be issued in its own packet. Users should wait 250 ms afternsending this command before further interaction.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1092,7 +1092,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FactoryStreaming", /* .title = */ "None", - /* .docs = */ "Configures the device for recording data for technical support.\n\nThis command will configure all available data streams to predefined\nformats designed to be used with technical support.", + /* .docs = */ "Configures the device for recording data for technical support.nnThis command will configure all available data streams to predefinednformats designed to be used with technical support.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1148,7 +1148,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "desc_set", - /* .docs = */ "The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets.\nOn Generation 5 products, this must be one of the above legacy constants.", + /* .docs = */ "The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets.nOn Generation 5 products, this must be one of the above legacy constants.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, true, true, true, true, true}, @@ -1169,7 +1169,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::DatastreamControl", /* .title = */ "None", - /* .docs = */ "Enable/disable the selected data stream.\n\nEach data stream (descriptor set) can be enabled or disabled.\nThe default for the device is all streams enabled.\nFor all functions except 0x01 (use new setting),\nthe new enable flag value is ignored and can be omitted.", + /* .docs = */ "Enable/disable the selected data stream.nnEach data stream (descriptor set) can be enabled or disabled.nThe default for the device is all streams enabled.nFor all functions except 0x01 (use new setting),nthe new enable flag value is ignored and can be omitted.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1375,7 +1375,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ConstellationSettings", /* .title = */ "None", - /* .docs = */ "This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation.\n\nMaximum number of tracking channels to use (total for all constellations):\n0 to max_channels_available (from reply message)\n\nFor each constellation you wish to use, include a ConstellationSettings struct. Note the following:\n\nTotal number of tracking channels (sum of 'reserved_channels' for all constellations) must be <= 32:\n0 -> 32 Number of reserved channels\n0 -> 32 Max number of channels (>= reserved channels)\n\nThe factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3.\n\nWarning: SBAS functionality shall not be used in 'safety of life' applications!\nWarning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK.\nWarning: You cannot enable GLONASS and BeiDou at the same time.\nNote: Enabling SBAS and QZSS augments GPS accuracy.\nNote: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used.", + /* .docs = */ "This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation.nnMaximum number of tracking channels to use (total for all constellations):n0 to max_channels_available (from reply message)nnFor each constellation you wish to use, include a ConstellationSettings struct. Note the following:nnTotal number of tracking channels (sum of 'reserved_channels' for all constellations) must be <= 32:n0 -> 32 Number of reserved channelsn0 -> 32 Max number of channels (>= reserved channels)nnThe factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3.nnWarning: SBAS functionality shall not be used in 'safety of life' applications!nWarning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK.nWarning: You cannot enable GLONASS and BeiDou at the same time.nNote: Enabling SBAS and QZSS augments GPS accuracy.nNote: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1508,7 +1508,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssSbasSettings", /* .title = */ "SBAS Settings", - /* .docs = */ "Configure the SBAS subsystem\n\n\n", + /* .docs = */ "Configure the SBAS subsystemnnn", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1604,7 +1604,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssAssistedFix", /* .title = */ "GNSS Assisted Fix Settings", - /* .docs = */ "Set the options for assisted GNSS fix.\n\nDevices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM.\nThese storage mechanisms are used to retain information about the last good GNSS fix. This can greatly reduces the TTFF (Time To First Fix) depending on the age of the stored information.\nThe TTFF can be as low as one second, or up to the equivalent of a cold start. There is a small increase in power used when enabling assisted fix.\n\nThe fastest fix will be obtained by supplying the device with a GNSS Assist Time Update message containing the current GPS time immediately after subsequent power up.\nThis allows the device to determine if the last GNSS information saved is still fresh enough to improve the TTFF.\n\nNOTE: Non-volatile GNSS memory is cleared when going from an enabled state to a disabled state.\nWARNING: The clearing operation results in an erase operation on the GNSS Flash. The flash has a limited durability of 100,000 write/erase cycles", + /* .docs = */ "Set the options for assisted GNSS fix.nnDevices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM.nThese storage mechanisms are used to retain information about the last good GNSS fix. This can greatly reduces the TTFF (Time To First Fix) depending on the age of the stored information.nThe TTFF can be as low as one second, or up to the equivalent of a cold start. There is a small increase in power used when enabling assisted fix.nnThe fastest fix will be obtained by supplying the device with a GNSS Assist Time Update message containing the current GPS time immediately after subsequent power up.nThis allows the device to determine if the last GNSS information saved is still fresh enough to improve the TTFF.nnNOTE: Non-volatile GNSS memory is cleared when going from an enabled state to a disabled state.nWARNING: The clearing operation results in an erase operation on the GNSS Flash. The flash has a limited durability of 100,000 write/erase cycles", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1699,7 +1699,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssTimeAssistance", /* .title = */ "None", - /* .docs = */ "Provide the GNSS subsystem with initial time information.\n\nThis message is required immediately after power up if GNSS Assist was enabled when the device was powered off.\nThis will initialize the subsystem clock to help reduce the time to first fix (TTFF).", + /* .docs = */ "Provide the GNSS subsystem with initial time information.nnThis message is required immediately after power up if GNSS Assist was enabled when the device was powered off.nThis will initialize the subsystem clock to help reduce the time to first fix (TTFF).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, false, false, false, true}, @@ -1743,7 +1743,7 @@ struct MetadataFor }, { /* .name = */ "frequency", - /* .docs = */ "The cutoff frequency of the filter. If the filter is in\nauto mode, this value is unspecified.", + /* .docs = */ "The cutoff frequency of the filter. If the filter is innauto mode, this value is unspecified.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -1782,7 +1782,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "target_descriptor", - /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.\nSupported values are accel (0x04), gyro (0x05), mag (0x06), and\npressure (0x17), provided the data is supported by the device.\nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", + /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.nSupported values are accel (0x04), gyro (0x05), mag (0x06), andnpressure (0x17), provided the data is supported by the device.nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, true, true, true, true, true}, @@ -1800,7 +1800,7 @@ struct MetadataFor }, { /* .name = */ "manual", - /* .docs = */ "If false, the cutoff frequency is set to half of the\nstreaming rate as configured by the message format command.\nOtherwise, the cutoff frequency is set according to the\nfollowing 'frequency' parameter.", + /* .docs = */ "If false, the cutoff frequency is set to half of thenstreaming rate as configured by the message format command.nOtherwise, the cutoff frequency is set according to thenfollowing 'frequency' parameter.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -1830,7 +1830,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuLowpassFilter", /* .title = */ "Advanced Low-Pass Filter Settings", - /* .docs = */ "Advanced configuration for the IMU data quantity low-pass filters.\n\nDeprecated, use the lowpass filter (0x0C,0x54) command instead.\n\nThe scaled data quantities are by default filtered through a single-pole IIR low-pass filter\nwhich is configured with a -3dB cutoff frequency of half the reporting frequency (set by\ndecimation factor in the IMU Message Format command) to prevent aliasing on a per data\nquantity basis. This advanced configuration command allows for the cutoff frequency to\nbe configured independently of the data reporting frequency as well as allowing for a\ncomplete bypass of the digital low-pass filter.\n\nPossible data descriptors:\n0x04 - Scaled accelerometer data\n0x05 - Scaled gyro data\n0x06 - Scaled magnetometer data (if applicable)\n0x17 - Scaled pressure data (if applicable)", + /* .docs = */ "Advanced configuration for the IMU data quantity low-pass filters.nnDeprecated, use the lowpass filter (0x0C,0x54) command instead.nnThe scaled data quantities are by default filtered through a single-pole IIR low-pass filternwhich is configured with a -3dB cutoff frequency of half the reporting frequency (set byndecimation factor in the IMU Message Format command) to prevent aliasing on a per datanquantity basis. This advanced configuration command allows for the cutoff frequency tonbe configured independently of the data reporting frequency as well as allowing for ancomplete bypass of the digital low-pass filter.nnPossible data descriptors:n0x04 - Scaled accelerometer datan0x05 - Scaled gyro datan0x06 - Scaled magnetometer data (if applicable)n0x17 - Scaled pressure data (if applicable)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2099,7 +2099,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpioConfig", /* .title = */ "GPIO Configuration", - /* .docs = */ "Configures the user GPIO pins on the connector for use with several built-in functions or for general input or output.\n\nGPIO pins are device-dependent. Some features are only available on\ncertain pins. Some behaviors require specific configurations.\nConsult the device user manual for restrictions and default settings.\n\nTo avoid glitches on GPIOs configured as an output in a mode other than\nGPIO, always configure the relevant function before setting up the pin\nwith this command. Otherwise, the pin state will be undefined between\nthis command and the one to set up the feature. For input pins, use\nthis command first so the state is well-defined when the feature is\ninitialized.\n\nSome configurations can only be active on one pin at a time. If such\nconfiguration is applied to a second pin, the second one will take\nprecedence and the original pin's configuration will be reset.\n", + /* .docs = */ "Configures the user GPIO pins on the connector for use with several built-in functions or for general input or output.nnGPIO pins are device-dependent. Some features are only available onncertain pins. Some behaviors require specific configurations.nConsult the device user manual for restrictions and default settings.nnTo avoid glitches on GPIOs configured as an output in a mode other thannGPIO, always configure the relevant function before setting up the pinnwith this command. Otherwise, the pin state will be undefined betweennthis command and the one to set up the feature. For input pins, usenthis command first so the state is well-defined when the feature isninitialized.nnSome configurations can only be active on one pin at a time. If suchnconfiguration is applied to a second pin, the second one will takenprecedence and the original pin's configuration will be reset.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2176,7 +2176,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpioState", /* .title = */ "GPIO State", - /* .docs = */ "Allows the state of the pin to be read or controlled.\n\nThis command serves two purposes: 1) To allow reading the state of a pin via command,\nrather than polling a data quantity, and 2) to provide a way to set the output state\nwithout also having to specify the operating mode.\n\nThe state read back from the pin is the physical state of the pin, rather than a\nconfiguration value. The state can be read regardless of its configuration as long as\nthe device supports GPIO input on that pin. If the pin is set to an output, the read\nvalue would match the output value.\n\nWhile the state of a pin can always be set, it will only have an observable effect if\nthe pin is set to output mode.\n\nThis command does not support saving, loading, or resetting the state. Instead, use the\nGPIO Configuration command, which allows the initial state to be configured.", + /* .docs = */ "Allows the state of the pin to be read or controlled.nnThis command serves two purposes: 1) To allow reading the state of a pin via command,nrather than polling a data quantity, and 2) to provide a way to set the output statenwithout also having to specify the operating mode.nnThe state read back from the pin is the physical state of the pin, rather than anconfiguration value. The state can be read regardless of its configuration as long asnthe device supports GPIO input on that pin. If the pin is set to an output, the readnvalue would match the output value.nnWhile the state of a pin can always be set, it will only have an observable effect ifnthe pin is set to output mode.nnThis command does not support saving, loading, or resetting the state. Instead, use thenGPIO Configuration command, which allows the initial state to be configured.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, false, false, false, true}, @@ -2221,7 +2221,7 @@ struct MetadataFor }, { /* .name = */ "scaling", - /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", + /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where snis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) andnhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.nMake this value negative if the odometer is mounted so that it rotates backwards.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2269,7 +2269,7 @@ struct MetadataFor }, { /* .name = */ "scaling", - /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", + /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where snis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) andnhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.nMake this value negative if the odometer is mounted so that it rotates backwards.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2290,7 +2290,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Odometer", /* .title = */ "Odometer Settings", - /* .docs = */ "Configures the hardware odometer interface.\n", + /* .docs = */ "Configures the hardware odometer interface.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2369,7 +2369,7 @@ struct MetadataFor }, { /* .name = */ "max_instances", - /* .docs = */ "Number of slots available. The 'instance' number for\nthe configuration or control commands must be between 1 and this value.", + /* .docs = */ "Number of slots available. The 'instance' number fornthe configuration or control commands must be between 1 and this value.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2428,7 +2428,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GetEventSupport", /* .title = */ "Get Supported Events", - /* .docs = */ "Lists the available trigger or action types.\n\nThere are a limited number of trigger and action slots available\nin the device. Up to M triggers and N actions can be configured at once\nin slots 1..M and 1..N respectively. M and N are identified by the\nmax_instances field in the response with the appropriate query selector.\n\nEach slot can be configured as one of a variety of different types of\ntriggers or actions. The supported types are enumerated in the response\nto this command. Additionally, there is a limit on the number of a given\ntype. In other words, while the device may support M triggers in total,\nonly a few of them maybe usable as a given type. This limit helps optimize\ndevice resources. The limit is identified in the count field.\n\nAll of the information in this command is available in the user manual.\nThis command provides a programmatic method for obtaining the information.\n", + /* .docs = */ "Lists the available trigger or action types.nnThere are a limited number of trigger and action slots availablenin the device. Up to M triggers and N actions can be configured at oncenin slots 1..M and 1..N respectively. M and N are identified by thenmax_instances field in the response with the appropriate query selector.nnEach slot can be configured as one of a variety of different types ofntriggers or actions. The supported types are enumerated in the responsento this command. Additionally, there is a limit on the number of a givenntype. In other words, while the device may support M triggers in total,nonly a few of them maybe usable as a given type. This limit helps optimizendevice resources. The limit is identified in the count field.nnAll of the information in this command is available in the user manual.nThis command provides a programmatic method for obtaining the information.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2466,7 +2466,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "instance", - /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", + /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to allnconfigured triggers, except when the function selector is READ.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, true, true, true, true, true}, @@ -2475,7 +2475,7 @@ struct MetadataFor }, { /* .name = */ "mode", - /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", + /* .docs = */ "How to change the trigger state. Except when instance is 0, thencorresponding trigger must be configured, i.e. not have type 0.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2505,7 +2505,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "instance", - /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", + /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to allnconfigured triggers, except when the function selector is READ.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, true, true, true, true, true}, @@ -2514,7 +2514,7 @@ struct MetadataFor }, { /* .name = */ "mode", - /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", + /* .docs = */ "How to change the trigger state. Except when instance is 0, thencorresponding trigger must be configured, i.e. not have type 0.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2526,7 +2526,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::EventControl", /* .title = */ "Event Control", - /* .docs = */ "Enables or disables event triggers.\n\nTriggers can be disabled, enabled, and tested. While disabled, a trigger will\nnot evaluate its logic and effective behave like no trigger is configured.\nA disabled trigger will not activate any actions. Triggers are disabled by default.\n\nUse this command to enable (or disable) a trigger, or to place it into a test mode.\nWhen in test mode, the trigger logic is disabled but the output is forced to\nthe active state, meaning that it will behave as if the trigger logic is satisfied\nand any associated actions will execute.", + /* .docs = */ "Enables or disables event triggers.nnTriggers can be disabled, enabled, and tested. While disabled, a trigger willnnot evaluate its logic and effective behave like no trigger is configured.nA disabled trigger will not activate any actions. Triggers are disabled by default.nnUse this command to enable (or disable) a trigger, or to place it into a test mode.nWhen in test mode, the trigger logic is disabled but the output is forced tonthe active state, meaning that it will behave as if the trigger logic is satisfiednand any associated actions will execute.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2932,7 +2932,7 @@ struct MetadataFor static constexpr inline StructInfo value = { /* .name = */ "ThresholdParams", /* .title = */ "Thresholdparams", - /* .docs = */ "Comparison of a supported MIP field parameter against a set of thresholds.\n\nTriggers when a data quantity meets the comparison criteria. The comparison can be either\na window comparison with high and low thresholds or a periodic interval.\n\nThe data quantity is identified by the MIP descriptor set, field descriptor, and parameter number.\nE.g. Scaled acceleration in the Z direction is specified with desc_set=0x80 (sensor data),\nfield_desc=0x04 (scaled accel), and param_id=3 (the third parameter and Z axis).\n\nThe window comparison can be used for a variety of purposes, such as disabling\na robot's drive motors if it tips over. In this case, a window comparison could\nbe set up to monitor the roll angle, (0x80,0x0C,3). The lower threshold would be set\nto -pi/2 radians and the upper threshold to pi/2 radians.\n\nThe interval trigger can be used to perform an action periodically if used with\na time field. E.g. to execute the action every 16 ms, set an interval comparison on\nthe GPS time of week parameter (0x80,0xD3,1) with high_thres set to 0.016. The lower\nthreshold determines how long the trigger is active within the 16-ms period.\n\nEither comparison type can be inverted by reversing the threshold values; setting\nlow_thres > high_thres will result in the reverse condition.\n", + /* .docs = */ "Comparison of a supported MIP field parameter against a set of thresholds.nnTriggers when a data quantity meets the comparison criteria. The comparison can be eitherna window comparison with high and low thresholds or a periodic interval.nnThe data quantity is identified by the MIP descriptor set, field descriptor, and parameter number.nE.g. Scaled acceleration in the Z direction is specified with desc_set=0x80 (sensor data),nfield_desc=0x04 (scaled accel), and param_id=3 (the third parameter and Z axis).nnThe window comparison can be used for a variety of purposes, such as disablingna robot's drive motors if it tips over. In this case, a window comparison couldnbe set up to monitor the roll angle, (0x80,0x0C,3). The lower threshold would be setnto -pi/2 radians and the upper threshold to pi/2 radians.nnThe interval trigger can be used to perform an action periodically if used withna time field. E.g. to execute the action every 16 ms, set an interval comparison onnthe GPS time of week parameter (0x80,0xD3,1) with high_thres set to 0.016. The lowernthreshold determines how long the trigger is active within the 16-ms period.nnEither comparison type can be inverted by reversing the threshold values; settingnlow_thres > high_thres will result in the reverse condition.n", /* .parameters = */ parameters, }; }; @@ -3204,7 +3204,7 @@ struct MetadataFor }, { /* .name = */ "decimation", - /* .docs = */ "Decimation from the base rate.\nIf 0, a packet is emitted each time the trigger activates.\nOtherwise, packets will be streamed while the trigger is active.\nThe internal decimation counter is reset if the trigger deactivates.", + /* .docs = */ "Decimation from the base rate.nIf 0, a packet is emitted each time the trigger activates.nOtherwise, packets will be streamed while the trigger is active.nThe internal decimation counter is reset if the trigger deactivates.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, @@ -3456,7 +3456,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::AccelBias", /* .title = */ "Configure Accel Bias", - /* .docs = */ "Configures the user specified accelerometer bias\n\nThe user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame.", + /* .docs = */ "Configures the user specified accelerometer biasnnThe user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3515,7 +3515,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GyroBias", /* .title = */ "Configure Gyro Bias", - /* .docs = */ "Configures the user specified gyroscope bias\n\nThe user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame.", + /* .docs = */ "Configures the user specified gyroscope biasnnThe user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3573,7 +3573,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::CaptureGyroBias", /* .title = */ "Capture Gyro Bias", - /* .docs = */ "Samples gyro for a specified time range and writes the averaged result to the Gyro Bias vector in RAM\n\nThe device will average the gyro output for the duration of 'averaging_time_ms.' To store the resulting vector\nin non-volatile memory, use the Set Gyro Bias command.\nIMPORTANT: The device must be stationary and experiencing minimum vibration for the duration of 'averaging_time_ms'\nAveraging Time range: 1000 to 30,000", + /* .docs = */ "Samples gyro for a specified time range and writes the averaged result to the Gyro Bias vector in RAMnnThe device will average the gyro output for the duration of 'averaging_time_ms.' To store the resulting vectornin non-volatile memory, use the Set Gyro Bias command.nIMPORTANT: The device must be stationary and experiencing minimum vibration for the duration of 'averaging_time_ms'nAveraging Time range: 1000 to 30,000", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -3632,7 +3632,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagHardIronOffset", /* .title = */ "Magnetometer Hard Iron Offset", - /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", + /* .docs = */ "Configure the user specified magnetometer hard iron offset vectornnThe values for this offset are determined empirically by external software algorithmsnbased on calibration data taken after the device is installed in its application. These valuesncan be obtained and set by using the LORD 'MIP Iron Calibration' application.nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.nThe offset is applied to the scaled magnetometer vector prior to output.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3691,7 +3691,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagSoftIronMatrix", /* .title = */ "Magnetometer Soft Iron Matrix", - /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \begin{bmatrix} 0 & 1 & 2 \\ 3 & 4 & 5 \\ 6 & 7 & 8 \end{bmatrix} EQEND\n", + /* .docs = */ "Configure the user specified magnetometer soft iron offset matrixnnThe values for this matrix are determined empirically by external software algorithmsnbased on calibration data taken after the device is installed in its application. These valuesncan be obtained and set by using the LORD 'MIP Iron Calibration' application.nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.nThe matrix is applied to the scaled magnetometer vector prior to output.nnThe matrix is in row major order:nEQSTART M = begin{bmatrix} 0 & 1 & 2 3 & 4 & 5 6 & 7 & 8 end{bmatrix} EQENDn", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3845,7 +3845,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformEuler", /* .title = */ "Sensor to Vehicle Frame Transformation Euler", - /* .docs = */ "Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, Roll Euler angles.\nThese are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference,\nand describe the transformation of vectors from the sensor body frame to the vehicle frame.
\nNote: This is the transformation, the inverse of the rotation defined in our legacy products.
\nThe transformation may be stored in the device as a matrix or quaternion. When Euler angles are read back from the device, they may not\nbe exactly equal to the Euler angles used to set the transformation, but they are functionally equivalent, such that they result in the same transformation.
\n

\nThis transformation to the vehicle frame will be applied to the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\nComplementary Filter Orientation
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .docs = */ "Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, Roll Euler angles.nThese are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference,nand describe the transformation of vectors from the sensor body frame to the vehicle frame.
nNote: This is the transformation, the inverse of the rotation defined in our legacy products.
nThe transformation may be stored in the device as a matrix or quaternion. When Euler angles are read back from the device, they may notnbe exactly equal to the Euler angles used to set the transformation, but they are functionally equivalent, such that they result in the same transformation.
n

nThis transformation to the vehicle frame will be applied to the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
nComplementary Filter Orientation
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
n
nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3904,7 +3904,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformQuaternion", /* .title = */ "Sensor to Vehicle Frame Transformation Quaternion", - /* .docs = */ "Set the sensor to vehicle frame transformation using unit length quaternion.\n\nNote: This is the transformation, the inverse of the rotation.\n\nThis quaternion describes the transformation of vectors from the sensor body frame to the vehicle frame of reference, and satisfies the following relationship:
\n\nEQSTART p^{veh} = q^{-1} p^{sen} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the transformation.
\nEQSTART p^{sen} = (0, v^{sen}_x, v^{sen}_y, v^{sen}_z) EQEND and EQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART p^{veh} = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
\n\nThe transformation may be stored in the device as a matrix or a quaternion. When the quaternion is read back from the device, it may not\nbe exactly equal to the quaternion used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .docs = */ "Set the sensor to vehicle frame transformation using unit length quaternion.nnNote: This is the transformation, the inverse of the rotation.nnThis quaternion describes the transformation of vectors from the sensor body frame to the vehicle frame of reference, and satisfies the following relationship:
nnEQSTART p^{veh} = q^{-1} p^{sen} q EQEND
nnWhere:
nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the transformation.
nEQSTART p^{sen} = (0, v^{sen}_x, v^{sen}_y, v^{sen}_z) EQEND and EQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
nEQSTART p^{veh} = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
nnThe transformation may be stored in the device as a matrix or a quaternion. When the quaternion is read back from the device, it may notnbe exactly equal to the quaternion used to set the transformation, but it is functionally equivalent.
n

nThis transformation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
n
nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3963,7 +3963,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformDcm", /* .title = */ "Sensor to Vehicle Frame Transformation Direction Cosine Matrix", - /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.\n\nThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
\nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
\n\nWhere:
\n\nEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND\nThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not\nbe exactly equal to array used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.nnThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
nnWhere:
nnEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
n
nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} end{bmatrix} EQENDnThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may notnbe exactly equal to array used to set the transformation, but it is functionally equivalent.
n

nThis transformation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
n
nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -4076,7 +4076,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ComplementaryFilter", /* .title = */ "Complementary filter settings", - /* .docs = */ "Configure the settings for the complementary filter which produces the following (0x80) descriptor set values: attitude matrix (0x80,09), quaternion (0x80,0A), and Euler angle (0x80,0C) outputs.\n\nThe filter can be configured to correct for pitch and roll using the accelerometer (with the assumption that linear acceleration is minimal),\nand to correct for heading using the magnetometer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field).\nPitch/roll and heading corrections each have their own configurable time constants, with a valid range of 1-1000 seconds. The default time constant is 10 seconds.", + /* .docs = */ "Configure the settings for the complementary filter which produces the following (0x80) descriptor set values: attitude matrix (0x80,09), quaternion (0x80,0A), and Euler angle (0x80,0C) outputs.nnThe filter can be configured to correct for pitch and roll using the accelerometer (with the assumption that linear acceleration is minimal),nand to correct for heading using the magnetometer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field).nPitch/roll and heading corrections each have their own configurable time constants, with a valid range of 1-1000 seconds. The default time constant is 10 seconds.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -4175,7 +4175,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::SensorRange", /* .title = */ "Sensor Range", - /* .docs = */ "Changes the IMU sensor gain.\n\nThis allows you to optimize the range to get the best accuracy and performance\nwhile minimizing over-range events.\n\nUse the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine\nthe appropriate setting value for your application. Using values other than\nthose specified may result in a NACK or inaccurate measurement data.", + /* .docs = */ "Changes the IMU sensor gain.nnThis allows you to optimize the range to get the best accuracy and performancenwhile minimizing over-range events.nnUse the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determinenthe appropriate setting value for your application. Using values other thannthose specified may result in a NACK or inaccurate measurement data.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -4285,7 +4285,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::CalibratedSensorRanges", /* .title = */ "Get Calibrated Sensor Ranges", - /* .docs = */ "Returns the supported sensor ranges which may be used with the 3DM Sensor Range (0x0C,0x52) command.\n\nThe response includes an array of (u8, float) pairs which map each allowed setting\nto the corresponding maximum range in physical units. See SensorRangeType for units.", + /* .docs = */ "Returns the supported sensor ranges which may be used with the 3DM Sensor Range (0x0C,0x52) command.nnThe response includes an array of (u8, float) pairs which map each allowed settingnto the corresponding maximum range in physical units. See SensorRangeType for units.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -4329,7 +4329,7 @@ struct MetadataFor }, { /* .name = */ "manual", - /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", + /* .docs = */ "If false, the frequency parameter is ignored and the filternwill track to half of the configured message format frequency.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -4338,7 +4338,7 @@ struct MetadataFor }, { /* .name = */ "frequency", - /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", + /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequencynwhen read out in automatic mode.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -4395,7 +4395,7 @@ struct MetadataFor }, { /* .name = */ "manual", - /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", + /* .docs = */ "If false, the frequency parameter is ignored and the filternwill track to half of the configured message format frequency.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -4404,7 +4404,7 @@ struct MetadataFor }, { /* .name = */ "frequency", - /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", + /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequencynwhen read out in automatic mode.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -4416,7 +4416,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::LowpassFilter", /* .title = */ "Low-pass anti-aliasing filter", - /* .docs = */ "This command controls the low-pass anti-aliasing filter supported data quantities.\n\nSee the device user manual for data quantities which support the anti-aliasing filter.\n\nIf set to automatic mode, the frequency will track half of the transmission rate\nof the target descriptor according to the configured message format (0x0C,0x0F).\nFor example, if scaled accel (0x80,0x04) is set to stream at 100 Hz, the filter would\nbe set to 50 Hz. Changing the message format to 200 Hz would automatically adjust the\nfilter to 100 Hz.\n\nFor WRITE, SAVE, LOAD, and DEFAULT function selectors, the descriptor set and/or field descriptor\nmay be 0x00 to set, save, load, or reset the setting for all supported descriptors. The\nfield descriptor must be 0x00 if the descriptor set is 0x00.\n", + /* .docs = */ "This command controls the low-pass anti-aliasing filter supported data quantities.nnSee the device user manual for data quantities which support the anti-aliasing filter.nnIf set to automatic mode, the frequency will track half of the transmission ratenof the target descriptor according to the configured message format (0x0C,0x0F).nFor example, if scaled accel (0x80,0x04) is set to stream at 100 Hz, the filter wouldnbe set to 50 Hz. Changing the message format to 200 Hz would automatically adjust thenfilter to 100 Hz.nnFor WRITE, SAVE, LOAD, and DEFAULT function selectors, the descriptor set and/or field descriptornmay be 0x00 to set, save, load, or reset the setting for all supported descriptors. Thenfield descriptor must be 0x00 if the descriptor set is 0x00.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, diff --git a/src/cpp/mip/metadata/definitions/commands_aiding.hpp b/src/cpp/mip/metadata/definitions/commands_aiding.hpp index 7c289a55d..81e106171 100644 --- a/src/cpp/mip/metadata/definitions/commands_aiding.hpp +++ b/src/cpp/mip/metadata/definitions/commands_aiding.hpp @@ -185,7 +185,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_aiding::FrameConfig", /* .title = */ "Frame Configuration", - /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command\nshould mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame)\n\nThis transform satisfies the following relationship:\n\nEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
\n\nWhere:
\nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

\nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
\nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
\n\nRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element\nin the rotation vector is ignored and should be set to 0.\n\nWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.\n\nExample: GNSS antenna lever arm\n\nFrame ID: 1\nFormat: 1 (Euler)\nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)\nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)\n", + /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID.nThe frame ID used in this command should mirror the frame ID used in the aiding commandn(if that aiding measurement is measured in this reference frame).nnThis transform satisfies the following relationship:nnEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
nnWhere:
nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
nnRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth elementnin the rotation vector is ignored and should be set to 0.nnWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.nnExample: GNSS antenna lever armnnFrame ID: 1nFormat: 1 (Euler)nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -195,9 +195,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::AidingEchoControl::Mode; + using type = commands_aiding::EchoControl::Mode; static constexpr inline EnumInfo::Entry entries[] = { { 0, "SUPPRESS_ACK", "Suppresses the usual command ack field for aiding messages." }, @@ -215,16 +215,16 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::AidingEchoControl::Response; + using type = commands_aiding::EchoControl::Response; static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "mode", /* .docs = */ "Controls data echoing.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -232,7 +232,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::AidingEchoControl::Response", + /* .name = */ "commands_aiding::EchoControl::Response", /* .title = */ "None", /* .docs = */ "", /* .parameters = */ parameters, @@ -244,17 +244,17 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::AidingEchoControl; + using type = commands_aiding::EchoControl; static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { /* .name = */ "mode", /* .docs = */ "Controls data echoing.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -262,7 +262,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::AidingEchoControl", + /* .name = */ "commands_aiding::EchoControl", /* .title = */ "Aiding Command Echo Control", /* .docs = */ "Controls command response behavior to external aiding commands", /* .parameters = */ parameters, @@ -337,9 +337,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EcefPos::ValidFlags; + using type = commands_aiding::PosEcef::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -357,9 +357,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EcefPos; + using type = commands_aiding::PosEcef; static constexpr inline ParameterInfo parameters[] = { { @@ -401,8 +401,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -410,7 +410,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::EcefPos", + /* .name = */ "commands_aiding::PosEcef", /* .title = */ "ECEF Position", /* .docs = */ "Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system.", /* .parameters = */ parameters, @@ -422,9 +422,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::LlhPos::ValidFlags; + using type = commands_aiding::PosLlh::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "Latitude", "" }, @@ -442,9 +442,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::LlhPos; + using type = commands_aiding::PosLlh; static constexpr inline ParameterInfo parameters[] = { { @@ -504,8 +504,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -513,9 +513,9 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::LlhPos", + /* .name = */ "commands_aiding::PosLlh", /* .title = */ "LLH Position", - /* .docs = */ "Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid.\nUncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height.", + /* .docs = */ "Geodetic position aiding command.nCoordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid.nUncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -525,9 +525,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::Height; + using type = commands_aiding::HeightAboveEllipsoid; static constexpr inline ParameterInfo parameters[] = { { @@ -578,9 +578,9 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::Height", - /* .title = */ "Height", - /* .docs = */ "Estimated value of height.", + /* .name = */ "commands_aiding::HeightAboveEllipsoid", + /* .title = */ "Height Above Ellipsoid", + /* .docs = */ "Estimated value of the height above ellipsoid.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -590,9 +590,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EcefVel::ValidFlags; + using type = commands_aiding::VelEcef::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -610,9 +610,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EcefVel; + using type = commands_aiding::VelEcef; static constexpr inline ParameterInfo parameters[] = { { @@ -654,8 +654,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -663,7 +663,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::EcefVel", + /* .name = */ "commands_aiding::VelEcef", /* .title = */ "ECEF Velocity", /* .docs = */ "ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame.", /* .parameters = */ parameters, @@ -675,9 +675,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::NedVel::ValidFlags; + using type = commands_aiding::VelNed::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -695,9 +695,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::NedVel; + using type = commands_aiding::VelNed; static constexpr inline ParameterInfo parameters[] = { { @@ -739,8 +739,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -748,7 +748,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::NedVel", + /* .name = */ "commands_aiding::VelNed", /* .title = */ "NED Velocity", /* .docs = */ "NED velocity aiding command. Coordinates are given in the local North-East-Down frame.", /* .parameters = */ parameters, @@ -760,9 +760,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VehicleFixedFrameVelocity::ValidFlags; + using type = commands_aiding::VelBodyFrame::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -780,9 +780,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VehicleFixedFrameVelocity; + using type = commands_aiding::VelBodyFrame; static constexpr inline ParameterInfo parameters[] = { { @@ -824,8 +824,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -833,9 +833,9 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::VehicleFixedFrameVelocity", - /* .title = */ "Vehicle Frame Velocity", - /* .docs = */ "Estimate of velocity of the vehicle in the frame associated\nwith the given sensor ID.", + /* .name = */ "commands_aiding::VelBodyFrame", + /* .title = */ "Body Frame Velocity", + /* .docs = */ "Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -845,9 +845,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::TrueHeading; + using type = commands_aiding::HeadingTrue; static constexpr inline ParameterInfo parameters[] = { { @@ -898,7 +898,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::TrueHeading", + /* .name = */ "commands_aiding::HeadingTrue", /* .title = */ "True Heading", /* .docs = */ "", /* .parameters = */ parameters, @@ -1063,15 +1063,15 @@ struct MetadataFor static constexpr inline std::initializer_list ALL_COMMANDS_AIDING = { &MetadataFor::value, &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, }; diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index 658b31d9e..e3247bdba 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -18,7 +18,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::Ping", /* .title = */ "Ping", - /* .docs = */ "Test Communications with a device.\n\nThe Device will respond with an ACK, if present and operating correctly.\n\nIf the device is not in a normal operating mode, it may NACK.", + /* .docs = */ "Test Communications with a device.nnThe Device will respond with an ACK, if present and operating correctly.nnIf the device is not in a normal operating mode, it may NACK.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -35,7 +35,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::SetIdle", /* .title = */ "Set to idle", - /* .docs = */ "Turn off all device data streams.\n\nThe Device will respond with an ACK, if present and operating correctly.\nThis command will suspend streaming (if enabled) or wake the device from sleep (if sleeping) to allow it to respond to status and setup commands.\nYou may restore the device mode by issuing the Resume command.", + /* .docs = */ "Turn off all device data streams.nnThe Device will respond with an ACK, if present and operating correctly.nThis command will suspend streaming (if enabled) or wake the device from sleep (if sleeping) to allow it to respond to status and setup commands.nYou may restore the device mode by issuing the Resume command.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -197,7 +197,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetDeviceDescriptors", /* .title = */ "Get device descriptors", - /* .docs = */ "Get the command and data descriptors supported by the device.\n\nReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.\nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", + /* .docs = */ "Get the command and data descriptors supported by the device.nnReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -243,7 +243,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::BuiltInTest", /* .title = */ "Built in test", - /* .docs = */ "Run the device Built-In Test (BIT).\n\nThe Built-In Test command always returns a 32 bit value.\nA value of 0 means that all tests passed.\nA non-zero value indicates that not all tests passed.\nReference the device user manual to decode the result.", + /* .docs = */ "Run the device Built-In Test (BIT).nnThe Built-In Test command always returns a 32 bit value.nA value of 0 means that all tests passed.nA non-zero value indicates that not all tests passed.nReference the device user manual to decode the result.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -260,7 +260,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::Resume", /* .title = */ "Resume", - /* .docs = */ "Take the device out of idle mode.\n\nThe device responds with ACK upon success.", + /* .docs = */ "Take the device out of idle mode.nnThe device responds with ACK upon success.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -306,7 +306,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetExtendedDescriptors", /* .title = */ "Get device descriptors (extended)", - /* .docs = */ "Get the command and data descriptors supported by the device.\n\nReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.\nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", + /* .docs = */ "Get the command and data descriptors supported by the device.nnReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -323,7 +323,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "result", - /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", + /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.nBits are least-significant-byte first. For example, bit 0 isnlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],nbit 8 is located at bit 0 of result[1], and bit 127 is located at bitn7 of result[15].", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -352,7 +352,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::ContinuousBit", /* .title = */ "Continuous built-in test", - /* .docs = */ "Report result of continuous built-in test.\n\nThis test is non-disruptive but is not as thorough as the commanded BIT.", + /* .docs = */ "Report result of continuous built-in test.nnThis test is non-disruptive but is not as thorough as the commanded BIT.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -429,7 +429,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::CommSpeed", /* .title = */ "Comm Port Speed", - /* .docs = */ "Controls the baud rate of a specific port on the device.\n\nPlease see the device user manual for supported baud rates on each port.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", + /* .docs = */ "Controls the baud rate of a specific port on the device.nnPlease see the device user manual for supported baud rates on each port.nnThe device will wait until all incoming and outgoing data has been sent, upnto a maximum of 250 ms, before applying any change.nnNo guarantee is provided as to what happens to commands issued during thisndelay period; They may or may not be processed and any responses aren'tnguaranteed to be at one rate or the other. The same applies to data packets.nnIt is highly recommended that the device be idle before issuing this commandnand that it be issued in its own packet. Users should wait 250 ms afternsending this command before further interaction.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -487,7 +487,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GpsTimeUpdate", /* .title = */ "GPS Time Update Command", - /* .docs = */ "Set device internal GPS time\nWhen combined with a PPS input signal applied to the I/O connector, this command enables complete synchronization of data outputs\nwith an external time base, such as GPS system time. Since the hardware PPS synchronization can only detect the fractional number of seconds when pulses arrive,\ncomplete synchronization requires that the user provide the whole number of seconds via this command. After achieving PPS synchronization, this command should be sent twice: once to set the time-of-week and once to set the week number. PPS synchronization can be verified by monitoring the time sync status message (0xA0, 0x02) or the valid flags of any shared external timestamp (0x--, D7) data field.", + /* .docs = */ "Set device internal GPS timenWhen combined with a PPS input signal applied to the I/O connector, this command enables complete synchronization of data outputsnwith an external time base, such as GPS system time. Since the hardware PPS synchronization can only detect the fractional number of seconds when pulses arrive,ncomplete synchronization requires that the user provide the whole number of seconds via this command. After achieving PPS synchronization, this command should be sent twice: once to set the time-of-week and once to set the week number. PPS synchronization can be verified by monitoring the time sync status message (0xA0, 0x02) or the valid flags of any shared external timestamp (0x--, D7) data field.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, false, false, false, false, true}, @@ -504,7 +504,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::SoftReset", /* .title = */ "Reset device", - /* .docs = */ "Resets the device.\n\nDevice responds with ACK and immediately resets.", + /* .docs = */ "Resets the device.nnDevice responds with ACK and immediately resets.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/commands_filter.hpp b/src/cpp/mip/metadata/definitions/commands_filter.hpp index 00e1db970..7674663b6 100644 --- a/src/cpp/mip/metadata/definitions/commands_filter.hpp +++ b/src/cpp/mip/metadata/definitions/commands_filter.hpp @@ -18,7 +18,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::Reset", /* .title = */ "Reset Navigation Filter", - /* .docs = */ "Resets the filter to the initialization state.\n\nIf the auto-initialization feature is disabled, the initial attitude or heading must be set in\norder to enter the run state after a reset.", + /* .docs = */ "Resets the filter to the initialization state.nnIf the auto-initialization feature is disabled, the initial attitude or heading must be set innorder to enter the run state after a reset.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -65,7 +65,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SetInitialAttitude", /* .title = */ "Set Initial Attitude", - /* .docs = */ "Set the sensor initial attitude.\n\nThis command can only be issued in the 'Init' state and should be used with a good\nestimate of the vehicle attitude. The Euler angles are the sensor body frame with respect\nto the NED frame.\n\nThe valid input ranges are as follows:\n\nRoll: [-pi, pi]\nPitch: [-pi/2, pi/2]\nHeading: [-pi, pi]\n", + /* .docs = */ "Set the sensor initial attitude.nnThis command can only be issued in the 'Init' state and should be used with a goodnestimate of the vehicle attitude. The Euler angles are the sensor body frame with respectnto the NED frame.nnThe valid input ranges are as follows:nnRoll: [-pi, pi]nPitch: [-pi/2, pi/2]nHeading: [-pi, pi]n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -148,7 +148,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::EstimationControl", /* .title = */ "Estimation Control Flags", - /* .docs = */ "Estimation Control Flags\n\nControls which parameters are estimated by the Kalman Filter.\n\nDesired settings should be logically ORed together.\n\nExamples:\n\n0x0001 - Enable Gyro Bias Estimation Only\n0x0063 - Enable Gyro Bias, Accel Bias, and Mag Auto Hard and Soft Iron Cal States Only\n", + /* .docs = */ "Estimation Control FlagsnnControls which parameters are estimated by the Kalman Filter.nnDesired settings should be logically ORed together.nnExamples:nn0x0001 - Enable Gyro Bias Estimation Onlyn0x0063 - Enable Gyro Bias, Accel Bias, and Mag Auto Hard and Soft Iron Cal States Onlyn", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -240,7 +240,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::ExternalGnssUpdate", /* .title = */ "External GNSS Update", - /* .docs = */ "Provide a filter measurement from an external GNSS\n\nThe GNSS source control must be set to 'external' for this command to succeed, otherwise it will be NACK'd.\nPlease refer to your device user manual for information on the maximum rate of this message.\n", + /* .docs = */ "Provide a filter measurement from an external GNSSnnThe GNSS source control must be set to 'external' for this command to succeed, otherwise it will be NACK'd.nPlease refer to your device user manual for information on the maximum rate of this message.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -287,7 +287,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::ExternalHeadingUpdate", /* .title = */ "External Heading Update", - /* .docs = */ "Provide a filter measurement from an external heading source\n\nThe heading must be the sensor frame with respect to the NED frame.\n\nThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.\nHeading angle uncertainties of <= 0.0 will be NACK'd\n\nPlease refer to your device user manual for information on the maximum rate of this message.\n\nOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.\nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.\n\n", + /* .docs = */ "Provide a filter measurement from an external heading sourcennThe heading must be the sensor frame with respect to the NED frame.nnThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.nHeading angle uncertainties of <= 0.0 will be NACK'dnnPlease refer to your device user manual for information on the maximum rate of this message.nnOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.nn", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -352,7 +352,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::ExternalHeadingUpdateWithTime", /* .title = */ "External Heading Update With Time", - /* .docs = */ "Provide a filter measurement from an external heading source at a specific GPS time\n\nThis is more accurate than the External Heading Update (0x0D, 0x17) and should be used in applications\nwhere the rate of heading change will cause significant measurement error due to the sampling, transmission,\nand processing time required. Accurate time stamping of the heading information is important.\n\nThe heading must be the sensor frame with respect to the NED frame.\n\nThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.\nHeading angle uncertainties of <= 0.0 will be NACK'd\n\nPlease refer to your device user manual for information on the maximum rate of this message.\n\nOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.\nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.\n\n", + /* .docs = */ "Provide a filter measurement from an external heading source at a specific GPS timennThis is more accurate than the External Heading Update (0x0D, 0x17) and should be used in applicationsnwhere the rate of heading change will cause significant measurement error due to the sampling, transmission,nand processing time required. Accurate time stamping of the heading information is important.nnThe heading must be the sensor frame with respect to the NED frame.nnThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.nHeading angle uncertainties of <= 0.0 will be NACK'dnnPlease refer to your device user manual for information on the maximum rate of this message.nnOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.nn", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -431,7 +431,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::TareOrientation", /* .title = */ "Tare Sensor Orientation", - /* .docs = */ "Tare the device orientation.\n\nThis function uses the current device orientation relative to the NED frame as the current sensor to vehicle transformation.\nThis command is provided as a convenient way to set the sensor to vehicle frame transformation.\nThe filter must be initialized and have a valid attitude output. If the attitude is not valid, an error will be returned.", + /* .docs = */ "Tare the device orientation.nnThis function uses the current device orientation relative to the NED frame as the current sensor to vehicle transformation.nThis command is provided as a convenient way to set the sensor to vehicle frame transformation.nThe filter must be initialized and have a valid attitude output. If the attitude is not valid, an error will be returned.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -606,7 +606,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationEuler", /* .title = */ "Sensor to Vehicle Frame Rotation Euler", - /* .docs = */ "Set the sensor to vehicle frame rotation using Yaw, Pitch, Roll Euler angles.\n\nNote: This is the rotation, the inverse of the transformation.\nThese angles define the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe rotation is stored in the device as a quaternion. When Euler angles are read back from the device, they may not\nbe equivalent in value to the Euler angles used to set the rotation, but they are functionally equivalent.
\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using Yaw, Pitch, Roll Euler angles.nnNote: This is the rotation, the inverse of the transformation.nThese angles define the rotation from the sensor body frame to the fixed vehicle frame.
nPlease reference the device Theory of Operation for more information.
nThe rotation is stored in the device as a quaternion. When Euler angles are read back from the device, they may notnbe equivalent in value to the Euler angles used to set the rotation, but they are functionally equivalent.
n

nThis rotation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -665,7 +665,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationDcm", /* .title = */ "Sensor to Vehicle Frame Rotation DCM", - /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \begin{bmatrix} 0 & 1 & 2\\ 3 & 4 & 5\\ 6 & 7 & 8 \end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.nnNote: This is the rotation, the inverse of the transformation.nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
nPlease reference the device Theory of Operation for more information.
nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may notnbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
n
nMatrix element order:

nnEQSTART T_{SEN}^{VEH} = begin{bmatrix} 0 & 1 & 2 3 & 4 & 5 6 & 7 & 8 end{bmatrix} EQENDnn

nThis rotation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -724,7 +724,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationQuaternion", /* .title = */ "Sensor to Vehicle Frame Rotation Quaternion", - /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.\n\nNote: This is the rotation, the inverse of the transformation.\nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may not\nbe equivalent in value to the quaternion used to set the rotation, due to normalization.
\n
\nQuaternion element definition:

\n
\nEQSTART Q_{SEN}^{VEH} = \begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \end{bmatrix} EQEND\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.nnNote: This is the rotation, the inverse of the transformation.nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
nPlease reference the device Theory of Operation for more information.
nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may notnbe equivalent in value to the quaternion used to set the rotation, due to normalization.
n
nQuaternion element definition:

n
nEQSTART Q_{SEN}^{VEH} = begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k end{bmatrix} EQENDn

nThis rotation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -783,7 +783,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleOffset", /* .title = */ "Sensor to Vehicle Frame Offset", - /* .docs = */ "Set the sensor to vehicle frame offset, expressed in the sensor frame.\n\nThis is a simple offset, not a lever arm. It does not compensate for inertial effects experienced from being offset from the center of gravity/rotation of the vehicle.\nIt simply adds the offset to the position output to express it in the origin of the user's vehicle frame.\n\nThis offset affects the following output quantities:\nEstimated LLH Position\n\nThe magnitude of the offset vector is limited to 10 meters", + /* .docs = */ "Set the sensor to vehicle frame offset, expressed in the sensor frame.nnThis is a simple offset, not a lever arm. It does not compensate for inertial effects experienced from being offset from the center of gravity/rotation of the vehicle.nIt simply adds the offset to the position output to express it in the origin of the user's vehicle frame.nnThis offset affects the following output quantities:nEstimated LLH PositionnnThe magnitude of the offset vector is limited to 10 meters", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -842,7 +842,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AntennaOffset", /* .title = */ "GNSS Antenna Offset Control", - /* .docs = */ "Set the sensor to GNSS antenna offset.\n\nThis is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.\n\nThe magnitude of the offset vector is limited to 10 meters\n", + /* .docs = */ "Configure the GNSS antenna offset.nnFor 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.nnFor 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center.nnThis command should also be used for CV7 / GV7-INS NMEA Input over GPIO.nnThe magnitude of the offset vector is limited to 10 metersn", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -922,7 +922,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GnssSource", /* .title = */ "GNSS Aiding Source Control", - /* .docs = */ "Control the source of GNSS information used to update the Kalman Filter.\n\nChanging the GNSS source while the sensor is in the 'running' state may temporarily place\nit back in the 'init' state until the new source of GNSS data is received.\n", + /* .docs = */ "Control the source of GNSS information used to update the Kalman Filter.nnChanging the GNSS source while the sensor is in the 'running' state may temporarily placenit back in the 'init' state until the new source of GNSS data is received.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1006,7 +1006,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::HeadingSource", /* .title = */ "Heading Aiding Source Control", - /* .docs = */ "Control the source of heading information used to update the Kalman Filter.\n\n1. To use internal GNSS velocity vector for heading updates, the target application\nmust have minimal (preferably no) side-slip. This option is good for wheeled vehicles.\n\n2. On some devices, when using GNSS velocity vector for heading updates, the X-axis of the device\nmust align with the direction of travel. Please reference the user guide for your particular device to\ndetermine if this limitation is applicable.\n\n3. When none is selected, the heading estimate can still converge if GNSS is available and sufficient dynamic motion\n(change in direction of travel and acceleration) is experienced. The heading may drift when: stationary, traveling\nat a constant speed, or during a constant course over ground.", + /* .docs = */ "Control the source of heading information used to update the Kalman Filter.nn1. To use internal GNSS velocity vector for heading updates, the target applicationnmust have minimal (preferably no) side-slip. This option is good for wheeled vehicles.nn2. On some devices, when using GNSS velocity vector for heading updates, the X-axis of the devicenmust align with the direction of travel. Please reference the user guide for your particular device tondetermine if this limitation is applicable.nn3. When none is selected, the heading estimate can still converge if GNSS is available and sufficient dynamic motionn(change in direction of travel and acceleration) is experienced. The heading may drift when: stationary, travelingnat a constant speed, or during a constant course over ground.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1065,7 +1065,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AutoInitControl", /* .title = */ "Auto-initialization Control", - /* .docs = */ "Filter Auto-initialization Control\n\nEnable/Disable automatic initialization upon device startup.\n\nPossible enable values:\n\n0x00 - Disable auto-initialization\n0x01 - Enable auto-initialization\n", + /* .docs = */ "Filter Auto-initialization ControlnnEnable/Disable automatic initialization upon device startup.nnPossible enable values:nn0x00 - Disable auto-initializationn0x01 - Enable auto-initializationn", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1124,7 +1124,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AccelNoise", /* .title = */ "Accelerometer Noise Standard Deviation", - /* .docs = */ "Accelerometer Noise Standard Deviation\n\nEach of the noise values must be greater than 0.0.\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.\nDefault values provide good performance for most laboratory conditions.", + /* .docs = */ "Accelerometer Noise Standard DeviationnnEach of the noise values must be greater than 0.0.nnThe noise value represents process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.nDefault values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1183,7 +1183,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GyroNoise", /* .title = */ "Gyroscope Noise Standard Deviation", - /* .docs = */ "Gyroscope Noise Standard Deviation\n\nEach of the noise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.\nDefault values provide good performance for most laboratory conditions.", + /* .docs = */ "Gyroscope Noise Standard DeviationnnEach of the noise values must be greater than 0.0nnThe noise value represents process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.nDefault values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1260,7 +1260,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AccelBiasModel", /* .title = */ "Accelerometer Bias Model Parameters", - /* .docs = */ "Accelerometer Bias Model Parameters\n\nNoise values must be greater than 0.0\n", + /* .docs = */ "Accelerometer Bias Model ParametersnnNoise values must be greater than 0.0n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1337,7 +1337,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GyroBiasModel", /* .title = */ "Gyroscope Bias Model Parameters", - /* .docs = */ "Gyroscope Bias Model Parameters\n\nNoise values must be greater than 0.0\n", + /* .docs = */ "Gyroscope Bias Model ParametersnnNoise values must be greater than 0.0n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1415,7 +1415,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AltitudeAiding", /* .title = */ "Altitude Aiding Control", - /* .docs = */ "Select altitude input for absolute altitude and/or vertical velocity. The primary altitude reading is always GNSS.\nAiding inputs are used to improve GNSS altitude readings when GNSS is available and to backup GNSS during outages.\n\nPressure altitude is based on 'instant sea level pressure' which is dependent on location and weather conditions and can vary by more than 40 meters.\n", + /* .docs = */ "Select altitude input for absolute altitude and/or vertical velocity. The primary altitude reading is always GNSS.nAiding inputs are used to improve GNSS altitude readings when GNSS is available and to backup GNSS during outages.nnPressure altitude is based on 'instant sea level pressure' which is dependent on location and weather conditions and can vary by more than 40 meters.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1493,7 +1493,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::PitchRollAiding", /* .title = */ "Pitch/Roll Aiding Control", - /* .docs = */ "Select pitch/roll aiding input. Pitch/roll reading is always derived from GNSS corrected inertial solution.\nAiding inputs are used to improve that solution during periods of low dynamics and GNSS outages.", + /* .docs = */ "Select pitch/roll aiding input. Pitch/roll reading is always derived from GNSS corrected inertial solution.nAiding inputs are used to improve that solution during periods of low dynamics and GNSS outages.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1570,7 +1570,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AutoZupt", /* .title = */ "Zero Velocity Update Control", - /* .docs = */ "The ZUPT is triggered when the scalar magnitude of the GNSS reported velocity vector is equal-to or less than the threshold value.\nThe device will NACK threshold values that are less than zero (i.e.negative.)", + /* .docs = */ "The ZUPT is triggered when the scalar magnitude of the GNSS reported velocity vector is equal-to or less than the threshold value.nThe device will NACK threshold values that are less than zero (i.e.negative.)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1647,7 +1647,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AutoAngularZupt", /* .title = */ "Zero Angular Rate Update Control", - /* .docs = */ "Zero Angular Rate Update\nThe ZUPT is triggered when the scalar magnitude of the angular rate vector is equal-to or less than the threshold value.\nThe device will NACK threshold values that are less than zero (i.e.negative.)", + /* .docs = */ "Zero Angular Rate UpdatenThe ZUPT is triggered when the scalar magnitude of the angular rate vector is equal-to or less than the threshold value.nThe device will NACK threshold values that are less than zero (i.e.negative.)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1703,7 +1703,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagCaptureAutoCal", /* .title = */ "Magnetometer Capture Auto Calibration", - /* .docs = */ "This command captures the current value of the auto-calibration, applies it to the current fixed hard and soft iron calibration coefficients, and replaces the current fixed hard and soft iron calibration coefficients with the new values.\nThis may be used in place of (or in addition to) a manual hard and soft iron calibration utility. This command also resets the auto-calibration coefficients.\nFunction selector SAVE is the same as issuing the 0x0C, 0x3A and 0x0C, 0x3B commands with the SAVE function selector.", + /* .docs = */ "This command captures the current value of the auto-calibration, applies it to the current fixed hard and soft iron calibration coefficients, and replaces the current fixed hard and soft iron calibration coefficients with the new values.nThis may be used in place of (or in addition to) a manual hard and soft iron calibration utility. This command also resets the auto-calibration coefficients.nFunction selector SAVE is the same as issuing the 0x0C, 0x3A and 0x0C, 0x3B commands with the SAVE function selector.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, false, true, false, false, true}, @@ -1762,7 +1762,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GravityNoise", /* .title = */ "Gravity Noise Standard Deviation", - /* .docs = */ "Set the expected gravity noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nNote: Noise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter. Changing this value modifies how the filter responds to dynamic input and can be used to tune filter performance.\nDefault values provide good performance for most laboratory conditions.", + /* .docs = */ "Set the expected gravity noise 1-sigma values. This function can be used to tune the filter performance in the target application.nnNote: Noise values must be greater than 0.0nnThe noise value represents process noise in the Estimation Filter. Changing this value modifies how the filter responds to dynamic input and can be used to tune filter performance.nDefault values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1821,7 +1821,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::PressureAltitudeNoise", /* .title = */ "Pressure Altitude Noise Standard Deviation", - /* .docs = */ "Set the expected pressure altitude noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nThe noise value must be greater than 0.0\n\nThis noise value represents pressure altitude model noise in the Estimation Filter.\nA lower value will increase responsiveness of the sensor to pressure changes, however height estimates will be more susceptible to error from air pressure fluctuations not due to changes in altitude. Default values provide good performance for most laboratory conditions.", + /* .docs = */ "Set the expected pressure altitude noise 1-sigma values. This function can be used to tune the filter performance in the target application.nnThe noise value must be greater than 0.0nnThis noise value represents pressure altitude model noise in the Estimation Filter.nA lower value will increase responsiveness of the sensor to pressure changes, however height estimates will be more susceptible to error from air pressure fluctuations not due to changes in altitude. Default values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1880,7 +1880,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::HardIronOffsetNoise", /* .title = */ "Hard Iron Offset Process Noise", - /* .docs = */ "Set the expected hard iron offset noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0\n\nThe noise values represent process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", + /* .docs = */ "Set the expected hard iron offset noise 1-sigma values. This function can be used to tune the filter performance in the target application.nnThis function can be used to tune the filter performance in the target application.nnNoise values must be greater than 0.0nnThe noise values represent process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1939,7 +1939,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SoftIronMatrixNoise", /* .title = */ "Soft Iron Offset Process Noise", - /* .docs = */ "Set the expected soft iron matrix noise 1-sigma values.\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", + /* .docs = */ "Set the expected soft iron matrix noise 1-sigma values.nThis function can be used to tune the filter performance in the target application.nnNoise values must be greater than 0.0nnThe noise value represents process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1998,7 +1998,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagNoise", /* .title = */ "Magnetometer Noise Standard Deviation", - /* .docs = */ "Set the expected magnetometer noise 1-sigma values.\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0 (gauss)\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions", + /* .docs = */ "Set the expected magnetometer noise 1-sigma values.nThis function can be used to tune the filter performance in the target application.nnNoise values must be greater than 0.0 (gauss)nnThe noise value represents process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2095,7 +2095,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::InclinationSource", /* .title = */ "Inclination Source", - /* .docs = */ "Set/Get the local magnetic field inclination angle source.\n\nThis can be used to correct for the local value of inclination (dip angle) of the earthmagnetic field.\nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.\n", + /* .docs = */ "Set/Get the local magnetic field inclination angle source.nnThis can be used to correct for the local value of inclination (dip angle) of the earthmagnetic field.nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2172,7 +2172,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagneticDeclinationSource", /* .title = */ "Magnetic Field Declination Source Control", - /* .docs = */ "Set/Get the local magnetic field declination angle source.\n\nThis can be used to correct for the local value of declination of the earthmagnetic field.\nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.\n", + /* .docs = */ "Set/Get the local magnetic field declination angle source.nnThis can be used to correct for the local value of declination of the earthmagnetic field.nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2249,7 +2249,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagFieldMagnitudeSource", /* .title = */ "Magnetic Field Magnitude Source", - /* .docs = */ "Set/Get the local magnetic field magnitude source.\n\nThis is used to specify the local magnitude of the earth's magnetic field.\nHaving a correct value for magnitude is important for best performance of the auto-mag calibration feature and for the magnetometer adaptive magnitude. If you do not have an accurate value for the local magnetic field magnitude, it is recommended that you leave the auto-mag calibration feature off.", + /* .docs = */ "Set/Get the local magnetic field magnitude source.nnThis is used to specify the local magnitude of the earth's magnetic field.nHaving a correct value for magnitude is important for best performance of the auto-mag calibration feature and for the magnetometer adaptive magnitude. If you do not have an accurate value for the local magnetic field magnitude, it is recommended that you leave the auto-mag calibration feature off.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2362,7 +2362,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::ReferencePosition", /* .title = */ "Set Reference Position", - /* .docs = */ "Set the Lat/Long/Alt reference position for the sensor.\n\nThis position is used by the sensor to calculate the WGS84 gravity and WMM2015 magnetic field parameters.\n", + /* .docs = */ "Set the Lat/Long/Alt reference position for the sensor.nnThis position is used by the sensor to calculate the WGS84 gravity and WMM2015 magnetic field parameters.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2549,7 +2549,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AccelMagnitudeErrorAdaptiveMeasurement", /* .title = */ "Gravity Magnitude Error Adaptive Measurement", - /* .docs = */ "Enable or disable the gravity magnitude error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nAdaptive measurements can be enabled/disabled without the need for providing the additional parameters.\nIn this case, only the function selector and enable value are required; all other parameters will remain at their previous values.\nWhen “auto-adaptive” is selected, the filter and limit parameters are ignored.\nInstead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality.\n", + /* .docs = */ "Enable or disable the gravity magnitude error adaptive measurement.nThis function can be used to tune the filter performance in the target applicationnnPick values that give you the least occurrence of invalid EF attitude output.nThe default values are good for standard low dynamics applications.nIncrease values for higher dynamic conditions, lower values for lower dynamic.nToo low a value will result in excessive heading errors.nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.nnAdaptive measurements can be enabled/disabled without the need for providing the additional parameters.nIn this case, only the function selector and enable value are required; all other parameters will remain at their previous values.nWhen auto-adaptive is selected, the filter and limit parameters are ignored.nInstead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2716,7 +2716,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagMagnitudeErrorAdaptiveMeasurement", /* .title = */ "Magnetometer Magnitude Error Adaptive Measurement", - /* .docs = */ "Enable or disable the magnetometer magnitude error adaptive measurement.\nThis feature will reject magnetometer readings that are out of range of the thresholds specified (fixed adaptive) or calculated internally (auto-adaptive).\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n", + /* .docs = */ "Enable or disable the magnetometer magnitude error adaptive measurement.nThis feature will reject magnetometer readings that are out of range of the thresholds specified (fixed adaptive) or calculated internally (auto-adaptive).nnPick values that give you the least occurrence of invalid EF attitude output.nThe default values are good for standard low dynamics applications.nIncrease values for higher dynamic conditions, lower values for lower dynamic.nToo low a value will result in excessive heading errors.nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2847,7 +2847,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagDipAngleErrorAdaptiveMeasurement", /* .title = */ "Magnetometer Dig Angle Error Adaptive Measurement", - /* .docs = */ "Enable or disable the magnetometer dip angle error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nThe magnetometer dip angle adaptive measurement is ignored if the auto-adaptive magnetometer magnitude or auto-adaptive accel magnitude options are selected.\n", + /* .docs = */ "Enable or disable the magnetometer dip angle error adaptive measurement.nThis function can be used to tune the filter performance in the target applicationnnPick values that give you the least occurrence of invalid EF attitude output.nThe default values are good for standard low dynamics applications.nIncrease values for higher dynamic conditions, lower values for lower dynamic.nToo low a value will result in excessive heading errors.nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.nnThe magnetometer dip angle adaptive measurement is ignored if the auto-adaptive magnetometer magnitude or auto-adaptive accel magnitude options are selected.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2870,7 +2870,7 @@ struct MetadataFor { 5, "EXTERNAL_HEADING", "External heading input" }, { 6, "EXTERNAL_ALTIMETER", "External pressure altimeter input" }, { 7, "EXTERNAL_MAGNETOMETER", "External magnetomer input" }, - { 8, "VEHICLE_FRAME_VEL", "External vehicle frame velocity input" }, + { 8, "BODY_FRAME_VEL", "External body frame velocity input" }, { 65535, "ALL", "Save/load/reset all options" }, }; @@ -2951,7 +2951,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AidingMeasurementEnable", /* .title = */ "Aiding Measurement Control", - /* .docs = */ "Enables / disables the specified aiding measurement source.\n\n", + /* .docs = */ "Enables / disables the specified aiding measurement source.nn", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2968,7 +2968,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::Run", /* .title = */ "Run Navigation Filter", - /* .docs = */ "Manual run command.\n\nIf the initialization configuration has the 'wait_for_run_command' option enabled, the filter will wait until it receives this command before commencing integration and enabling the Kalman filter. Prior to the receipt of this command, the filter will remain in the filter initialization mode.", + /* .docs = */ "Manual run command.nnIf the initialization configuration has the 'wait_for_run_command' option enabled, the filter will wait until it receives this command before commencing integration and enabling the Kalman filter. Prior to the receipt of this command, the filter will remain in the filter initialization mode.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2985,7 +2985,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "acceleration_constraint_selection", - /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", + /* .docs = */ "Acceleration constraint:
n0=None (default),
n1=Zero-acceleration.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2994,7 +2994,7 @@ struct MetadataFor }, { /* .name = */ "velocity_constraint_selection", - /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", + /* .docs = */ "0=None (default),
n1=Zero-velocity,
n2=Wheeled-vehicle.
", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3003,7 +3003,7 @@ struct MetadataFor }, { /* .name = */ "angular_constraint_selection", - /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", + /* .docs = */ "0=None (default),n1=Zero-angular rate (ZUPT).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3033,7 +3033,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "acceleration_constraint_selection", - /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", + /* .docs = */ "Acceleration constraint:
n0=None (default),
n1=Zero-acceleration.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3042,7 +3042,7 @@ struct MetadataFor }, { /* .name = */ "velocity_constraint_selection", - /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", + /* .docs = */ "0=None (default),
n1=Zero-velocity,
n2=Wheeled-vehicle.
", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3051,7 +3051,7 @@ struct MetadataFor }, { /* .name = */ "angular_constraint_selection", - /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", + /* .docs = */ "0=None (default),n1=Zero-angular rate (ZUPT).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3063,7 +3063,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::KinematicConstraint", /* .title = */ "Kinematic Constraint Control", - /* .docs = */ "Controls kinematic constraint model selection for the navigation filter.\n\nSee manual for explanation of how the kinematic constraints are applied.", + /* .docs = */ "Controls kinematic constraint model selection for the navigation filter.nnSee manual for explanation of how the kinematic constraints are applied.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3327,7 +3327,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::InitializationConfiguration", /* .title = */ "Navigation Filter Initialization", - /* .docs = */ "Controls the source and values used for initial conditions of the navigation solution.\n\nNotes: Initial conditions are the position, velocity, and attitude of the platform used when the filter starts running or is reset.\nFor the user specified position array, the units are meters if the ECEF frame is selected, and degrees latitude, degrees longitude, and meters above ellipsoid if the latitude/longitude/height frame is selected.\nFor the user specified velocity array, the units are meters per second, but the reference frame depends on the reference frame selector (ECEF or NED).", + /* .docs = */ "Controls the source and values used for initial conditions of the navigation solution.nnNotes: Initial conditions are the position, velocity, and attitude of the platform used when the filter starts running or is reset.nFor the user specified position array, the units are meters if the ECEF frame is selected, and degrees latitude, degrees longitude, and meters above ellipsoid if the latitude/longitude/height frame is selected.nFor the user specified velocity array, the units are meters per second, but the reference frame depends on the reference frame selector (ECEF or NED).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3344,7 +3344,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "level", - /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", + /* .docs = */ "Auto-adaptive operating level:
n0=Off,
n1=Conservative,
n2=Moderate (default),
n3=Aggressive.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3383,7 +3383,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "level", - /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", + /* .docs = */ "Auto-adaptive operating level:
n0=Off,
n1=Conservative,
n2=Moderate (default),
n3=Aggressive.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3481,7 +3481,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MultiAntennaOffset", /* .title = */ "GNSS Multi-Antenna Offset Control", - /* .docs = */ "Set the antenna lever arm.\n\nThis command works with devices that utilize multiple antennas.\n

Offset Limit: 10 m magnitude (default)", + /* .docs = */ "Set the antenna lever arm.nnThis command works with devices that utilize multiple antennas.n

Offset Limit: 10 m magnitude (default)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3671,7 +3671,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::RefPointLeverArm", /* .title = */ "Reference point lever arm", - /* .docs = */ "Lever arm offset with respect to the sensor for the indicated point of reference.\nThis is used to change the location of the indicated point of reference, and will affect filter position and velocity outputs.\nChanging this setting from default will result in a global position offset that depends on vehicle attitude,\nand a velocity offset that depends on vehicle attitude and angular rate.\n
The lever arm is defined by a 3-element vector that points from the sensor to the desired reference point, with (x,y,z) components given in the vehicle's reference frame.\n

Note, if the reference point selector is set to VEH (1), this setting will affect the following data fields: (0x82, 0x01), (0x82, 0x02), (0x82, 0x40), (0x82, 0x41), and (0x82, 42)\n

Offset Limits\n
Reference Point VEH (1): 10 m magnitude (default)", + /* .docs = */ "Lever arm offset with respect to the sensor for the indicated point of reference.nThis is used to change the location of the indicated point of reference, and will affect filter position and velocity outputs.nChanging this setting from default will result in a global position offset that depends on vehicle attitude,nand a velocity offset that depends on vehicle attitude and angular rate.n
The lever arm is defined by a 3-element vector that points from the sensor to the desired reference point, with (x,y,z) components given in the vehicle's reference frame.n

Note, if the reference point selector is set to VEH (1), this setting will affect the following data fields: (0x82, 0x01), (0x82, 0x02), (0x82, 0x40), (0x82, 0x41), and (0x82, 42)n

Offset Limitsn
Reference Point VEH (1): 10 m magnitude (default)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3727,7 +3727,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SpeedMeasurement", /* .title = */ "Input speed measurement", - /* .docs = */ "Speed aiding measurement, where speed is defined as rate of motion along the vehicle's x-axis direction.\nCan be used by an external odometer/speedometer, for example.\nThis command cannot be used if the internal odometer is configured.", + /* .docs = */ "Speed aiding measurement, where speed is defined as rate of motion along the vehicle's x-axis direction.nCan be used by an external odometer/speedometer, for example.nThis command cannot be used if the internal odometer is configured.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -3804,7 +3804,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SpeedLeverArm", /* .title = */ "Measurement speed lever arm", - /* .docs = */ "Lever arm offset for speed measurements.\nThis is used to compensate for an off-center measurement point\nhaving a different speed due to rotation of the vehicle.\nThe typical use case for this would be an odometer attached to a wheel\non a standard 4-wheeled vehicle. If the odometer is on the left wheel,\nit will report higher speed on right turns and lower speed on left turns.\nThis is because the outside edge of the curve is longer than the inside edge.", + /* .docs = */ "Lever arm offset for speed measurements.nThis is used to compensate for an off-center measurement pointnhaving a different speed due to rotation of the vehicle.nThe typical use case for this would be an odometer attached to a wheelnon a standard 4-wheeled vehicle. If the odometer is on the left wheel,nit will report higher speed on right turns and lower speed on left turns.nThis is because the outside edge of the curve is longer than the inside edge.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3863,7 +3863,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::WheeledVehicleConstraintControl", /* .title = */ "Wheeled Vehicle Constraint Control", - /* .docs = */ "Configure the wheeled vehicle kinematic constraint.\n\nWhen enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis.\nBy convention, the primary vehicle axis is the vehicle X-axis (note: the sensor may be physically installed in\nany orientation on the vehicle if the appropriate mounting transformation has been specified).\nThis constraint will typically improve heading estimates for vehicles where the assumption is valid, such\nas an automobile, particularly when GNSS coverage is intermittent.", + /* .docs = */ "Configure the wheeled vehicle kinematic constraint.nnWhen enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis.nBy convention, the primary vehicle axis is the vehicle X-axis (note: the sensor may be physically installed innany orientation on the vehicle if the appropriate mounting transformation has been specified).nThis constraint will typically improve heading estimates for vehicles where the assumption is valid, suchnas an automobile, particularly when GNSS coverage is intermittent.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3922,7 +3922,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::VerticalGyroConstraintControl", /* .title = */ "Vertical Gyro Constraint Control", - /* .docs = */ "Configure the vertical gyro kinematic constraint.\n\nWhen enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track pitch\nand roll under the assumption that the sensor platform is not undergoing linear acceleration.\nThis constraint is useful to maintain accurate pitch and roll during GNSS signal outages.", + /* .docs = */ "Configure the vertical gyro kinematic constraint.nnWhen enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track pitchnand roll under the assumption that the sensor platform is not undergoing linear acceleration.nThis constraint is useful to maintain accurate pitch and roll during GNSS signal outages.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3999,7 +3999,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GnssAntennaCalControl", /* .title = */ "GNSS Antenna Offset Calibration Control", - /* .docs = */ "Configure the GNSS antenna lever arm calibration.\n\nWhen enabled, the filter will enable lever arm error tracking, up to the maximum offset specified.", + /* .docs = */ "Configure the GNSS antenna lever arm calibration.nnWhen enabled, the filter will enable lever arm error tracking, up to the maximum offset specified.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -4028,7 +4028,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SetInitialHeading", /* .title = */ "Set Initial Heading Control", - /* .docs = */ "Set the initial heading angle.\n\nThe estimation filter will reset the heading estimate to provided value. If the product supports magnetometer aiding and this feature has been enabled, the heading\nargument will be ignored and the filter will initialize using the inferred magnetic heading.", + /* .docs = */ "Set the initial heading angle.nnThe estimation filter will reset the heading estimate to provided value. If the product supports magnetometer aiding and this feature has been enabled, the headingnargument will be ignored and the filter will initialize using the inferred magnetic heading.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/commands_gnss.hpp b/src/cpp/mip/metadata/definitions/commands_gnss.hpp index dbfdecfba..2790fd045 100644 --- a/src/cpp/mip/metadata/definitions/commands_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/commands_gnss.hpp @@ -36,7 +36,7 @@ struct MetadataFor }, { /* .name = */ "description", - /* .docs = */ "Ascii description of receiver. Contains the following info (comma-delimited):
\nModule name/model
\nFirmware version info", + /* .docs = */ "Ascii description of receiver. Contains the following info (comma-delimited):
nModule name/model
nFirmware version info", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, @@ -99,7 +99,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::ReceiverInfo", /* .title = */ "None", - /* .docs = */ "Return information about the GNSS receivers in the device.\n", + /* .docs = */ "Return information about the GNSS receivers in the device.n", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -230,7 +230,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::SignalConfiguration", /* .title = */ "None", - /* .docs = */ "Configure the GNSS signals used by the device.\n", + /* .docs = */ "Configure the GNSS signals used by the device.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -307,7 +307,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::RtkDongleConfiguration", /* .title = */ "None", - /* .docs = */ "Configure the communications with the RTK Dongle connected to the device.\n", + /* .docs = */ "Configure the communications with the RTK Dongle connected to the device.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, diff --git a/src/cpp/mip/metadata/definitions/commands_rtk.hpp b/src/cpp/mip/metadata/definitions/commands_rtk.hpp index eddf293a5..21750f015 100644 --- a/src/cpp/mip/metadata/definitions/commands_rtk.hpp +++ b/src/cpp/mip/metadata/definitions/commands_rtk.hpp @@ -638,7 +638,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::ProdEraseStorage", /* .title = */ "None", - /* .docs = */ "This command will erase the selected media to a raw and uninitialized state. ALL DATA WILL BE LOST.\nThis command is only available in calibration mode.", + /* .docs = */ "This command will erase the selected media to a raw and uninitialized state. ALL DATA WILL BE LOST.nThis command is only available in calibration mode.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -731,7 +731,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::ModemHardReset", /* .title = */ "None", - /* .docs = */ "This command will clear the modem flash. THIS MUST NOT BE DONE OFTEN AS IT CAN DAMAGE THE FLASH!\nThis command is only available in calibration mode.", + /* .docs = */ "This command will clear the modem flash. THIS MUST NOT BE DONE OFTEN AS IT CAN DAMAGE THE FLASH!nThis command is only available in calibration mode.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/commands_system.hpp b/src/cpp/mip/metadata/definitions/commands_system.hpp index 2a9f7adcf..0154590a0 100644 --- a/src/cpp/mip/metadata/definitions/commands_system.hpp +++ b/src/cpp/mip/metadata/definitions/commands_system.hpp @@ -60,7 +60,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_system::CommMode", /* .title = */ "None", - /* .docs = */ "Advanced specialized communication modes.\n\nThis command allows the user to communicate directly with various subsystems which may be present in MIP devices (i.e. IMU, GNSS, etc.)\nPlease see the specific device's user manual for possible modes.\n\nThis command responds with an ACK/NACK just prior to switching to the new protocol.\nFor all functions except 0x01 (use new settings), the new communications mode value is ignored.\n\n", + /* .docs = */ "Advanced specialized communication modes.nnThis command allows the user to communicate directly with various subsystems which may be present in MIP devices (i.e. IMU, GNSS, etc.)nPlease see the specific device's user manual for possible modes.nnThis command responds with an ACK/NACK just prior to switching to the new protocol.nFor all functions except 0x01 (use new settings), the new communications mode value is ignored.nn", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, false, false, true, true}, diff --git a/src/cpp/mip/metadata/definitions/data_filter.hpp b/src/cpp/mip/metadata/definitions/data_filter.hpp index 58ba47315..d0156c156 100644 --- a/src/cpp/mip/metadata/definitions/data_filter.hpp +++ b/src/cpp/mip/metadata/definitions/data_filter.hpp @@ -151,7 +151,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AttitudeQuaternion", /* .title = */ "None", - /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.\nThis quaternion satisfies the following relationship:\n\nEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
\nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", + /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.nThis quaternion satisfies the following relationship:nnEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
nnWhere:
nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -189,7 +189,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AttitudeDcm", /* .title = */ "None", - /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.nThis matrix satisfies the following relationship:nnEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
nnWhere:
nnEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
n
nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} end{bmatrix} EQEND", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -245,7 +245,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::EulerAngles", /* .title = */ "None", - /* .docs = */ "Filter reported Euler angles describing the orientation of the device with respect to the NED local-level frame.\nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", + /* .docs = */ "Filter reported Euler angles describing the orientation of the device with respect to the NED local-level frame.nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -489,7 +489,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::EulerAnglesUncertainty", /* .title = */ "None", - /* .docs = */ "Filter reported 1-sigma Euler angle uncertainties.\nThe uncertainties are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", + /* .docs = */ "Filter reported 1-sigma Euler angle uncertainties.nThe uncertainties are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -612,7 +612,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::Timestamp", /* .title = */ "None", - /* .docs = */ "GPS timestamp of the Filter data\n\nShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.\nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.\nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.\n\nNote: this data field may be deprecated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead.", + /* .docs = */ "GPS timestamp of the Filter datannShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.nnNote: this data field may be deprecated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -788,7 +788,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::LinearAccel", /* .title = */ "None", - /* .docs = */ "Filter-compensated linear acceleration expressed in the vehicle frame.\nNote: The estimated gravity has been removed from this data leaving only linear acceleration.", + /* .docs = */ "Filter-compensated linear acceleration expressed in the vehicle frame.nNote: The estimated gravity has been removed from this data leaving only linear acceleration.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1056,7 +1056,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::HeadingUpdateState", /* .title = */ "None", - /* .docs = */ "Filter reported heading update state.\n\nHeading updates can be applied from the sources listed below. Note, some of these sources may be combined.\nThe heading value is always relative to true north.", + /* .docs = */ "Filter reported heading update state.nnHeading updates can be applied from the sources listed below. Note, some of these sources may be combined.nThe heading value is always relative to true north.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1130,7 +1130,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagneticModel", /* .title = */ "None", - /* .docs = */ "The World Magnetic Model is used for this data. Please refer to the device user manual for the current version of the model.\nA valid GNSS location is required for the model to be valid.", + /* .docs = */ "The World Magnetic Model is used for this data. Please refer to the device user manual for the current version of the model.nA valid GNSS location is required for the model to be valid.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1432,7 +1432,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::StandardAtmosphere", /* .title = */ "None", - /* .docs = */ "Filter reported standard atmosphere parameters.\n\nThe US 1976 Standard Atmosphere Model is used. A valid GNSS location is required for the model to be valid.", + /* .docs = */ "Filter reported standard atmosphere parameters.nnThe US 1976 Standard Atmosphere Model is used. A valid GNSS location is required for the model to be valid.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1470,7 +1470,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::PressureAltitude", /* .title = */ "None", - /* .docs = */ "Filter reported pressure altitude.\n\nThe US 1976 Standard Atmosphere Model is used to calculate the pressure altitude in meters.\nA valid pressure sensor reading is required for the pressure altitude to be valid.\nThe minimum pressure reading supported by the model is 0.0037 mBar, corresponding to an altitude of 84,852 meters.", + /* .docs = */ "Filter reported pressure altitude.nnThe US 1976 Standard Atmosphere Model is used to calculate the pressure altitude in meters.nA valid pressure sensor reading is required for the pressure altitude to be valid.nThe minimum pressure reading supported by the model is 0.0037 mBar, corresponding to an altitude of 84,852 meters.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1546,7 +1546,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AntennaOffsetCorrection", /* .title = */ "None", - /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.\n\nThis offset added to any previously stored offset vector to compensate for errors in definition.", + /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.nnThis offset added to any previously stored offset vector to compensate for errors in definition.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1631,7 +1631,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MultiAntennaOffsetCorrection", /* .title = */ "None", - /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.\n\nThis offset added to any previously stored offset vector to compensate for errors in definition.", + /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.nnThis offset added to any previously stored offset vector to compensate for errors in definition.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1716,7 +1716,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerOffset", /* .title = */ "None", - /* .docs = */ "Filter reported magnetometer hard iron offset in sensor frame.\n\nThis offset added to any previously stored hard iron offset vector to compensate for magnetometer in-run bias errors.", + /* .docs = */ "Filter reported magnetometer hard iron offset in sensor frame.nnThis offset added to any previously stored hard iron offset vector to compensate for magnetometer in-run bias errors.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1754,7 +1754,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerMatrix", /* .title = */ "None", - /* .docs = */ "Filter reported magnetometer soft iron matrix in sensor frame.\n\nThis matrix is post multiplied to any previously stored soft iron matrix to compensate for magnetometer in-run errors.", + /* .docs = */ "Filter reported magnetometer soft iron matrix in sensor frame.nnThis matrix is post multiplied to any previously stored soft iron matrix to compensate for magnetometer in-run errors.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2431,12 +2431,15 @@ struct MetadataFor { 4, "PRESSURE", "" }, { 5, "MAGNETOMETER", "" }, { 6, "SPEED", "" }, - { 33, "POS_ECEF", "" }, - { 34, "POS_LLH", "" }, - { 40, "VEL_ECEF", "" }, - { 41, "VEL_NED", "" }, - { 42, "VEL_VEHICLE_FRAME", "" }, - { 49, "HEADING_TRUE", "" }, + { 33, "AIDING_POS_ECEF", "" }, + { 34, "AIDING_POS_LLH", "" }, + { 35, "AIDING_HEIGHT_ABOVE_ELLIPSOID", "" }, + { 40, "AIDING_VEL_ECEF", "" }, + { 41, "AIDING_VEL_NED", "" }, + { 42, "AIDING_VEL_BODY_FRAME", "" }, + { 49, "AIDING_HEADING_TRUE", "" }, + { 50, "AIDING_MAGNETIC_FIELD", "" }, + { 51, "AIDING_PRESSURE", "" }, }; static constexpr inline EnumInfo value = { @@ -2755,7 +2758,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AidingFrameConfigError", /* .title = */ "Aiding Frame Configuration Error", - /* .docs = */ "Filter reported aiding source frame configuration error\n\nThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", + /* .docs = */ "Filter reported aiding source frame configuration errornnThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2802,7 +2805,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AidingFrameConfigErrorUncertainty", /* .title = */ "Aiding Frame Configuration Error Uncertainty", - /* .docs = */ "Filter reported aiding source frame configuration error uncertainty\n\nThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", + /* .docs = */ "Filter reported aiding source frame configuration error uncertaintynnThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/data_gnss.hpp b/src/cpp/mip/metadata/definitions/data_gnss.hpp index 5b9d66848..e977c3ed3 100644 --- a/src/cpp/mip/metadata/definitions/data_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/data_gnss.hpp @@ -968,7 +968,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::SvInfo", /* .title = */ "None", - /* .docs = */ "GNSS reported space vehicle information\n\nWhen enabled, these fields will arrive in separate MIP packets", + /* .docs = */ "GNSS reported space vehicle informationnnWhen enabled, these fields will arrive in separate MIP packets", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1194,7 +1194,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::DgpsInfo", /* .title = */ "None", - /* .docs = */ "GNSS reported DGNSS status\n\n
Possible Base Station Status Values:
\n
  0 - UDRE Scale Factor = 1.0
\n
  1 - UDRE Scale Factor = 0.75
\n
  2 - UDRE Scale Factor = 0.5
\n
  3 - UDRE Scale Factor = 0.3
\n
  4 - UDRE Scale Factor = 0.2
\n
  5 - UDRE Scale Factor = 0.1
\n
  6 - Reference Station Transmission Not Monitored
\n
  7 - Reference Station Not Working
\n\n(UDRE = User Differential Range Error)", + /* .docs = */ "GNSS reported DGNSS statusnn
Possible Base Station Status Values:
n
  0 - UDRE Scale Factor = 1.0
n
  1 - UDRE Scale Factor = 0.75
n
  2 - UDRE Scale Factor = 0.5
n
  3 - UDRE Scale Factor = 0.3
n
  4 - UDRE Scale Factor = 0.2
n
  5 - UDRE Scale Factor = 0.1
n
  6 - Reference Station Transmission Not Monitored
n
  7 - Reference Station Not Working
nn(UDRE = User Differential Range Error)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1281,7 +1281,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::DgpsChannel", /* .title = */ "None", - /* .docs = */ "GNSS reported DGPS Channel Status status\n\nWhen enabled, a separate field for each active space vehicle will be sent in the packet.", + /* .docs = */ "GNSS reported DGPS Channel Status statusnnWhen enabled, a separate field for each active space vehicle will be sent in the packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1368,7 +1368,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::ClockInfo2", /* .title = */ "None", - /* .docs = */ "GNSS reported receiver clock parameters\n\nThis supersedes MIP_DATA_DESC_GNSS_CLOCK_INFO with additional information.", + /* .docs = */ "GNSS reported receiver clock parametersnnThis supersedes MIP_DATA_DESC_GNSS_CLOCK_INFO with additional information.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1728,7 +1728,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::SbasCorrection", /* .title = */ "None", - /* .docs = */ "GNSS calculated SBAS Correction\n\nUDREI - the variance of a normal distribution associated with the user differential range errors for a\nsatellite after application of fast and long-term corrections, excluding atmospheric effects\n\n
UDREI  Variance
\n
-----------------------
\n
0      0.0520 m^2
\n
1      0.0924 m^2
\n
2      0.1444 m^2
\n
3      0.2830 m^2
\n
4      0.4678 m^2
\n
5      0.8315 m^2
\n
6      1.2992 m^2
\n
7      1.8709 m^2
\n
8      2.5465 m^2
\n
9      3.3260 m^2
\n
10     5.1968 m^2
\n
11     20.7870 m^2
\n
12     230.9661 m^2
\n
13     2078.695 m^2
\n
14     'Not Monitored'
\n
15     'Do Not Use'
", + /* .docs = */ "GNSS calculated SBAS CorrectionnnUDREI - the variance of a normal distribution associated with the user differential range errors for ansatellite after application of fast and long-term corrections, excluding atmospheric effectsnn
UDREI  Variance
n
-----------------------
n
0      0.0520 m^2
n
1      0.0924 m^2
n
2      0.1444 m^2
n
3      0.2830 m^2
n
4      0.4678 m^2
n
5      0.8315 m^2
n
6      1.2992 m^2
n
7      1.8709 m^2
n
8      2.5465 m^2
n
9      3.3260 m^2
n
10     5.1968 m^2
n
11     20.7870 m^2
n
12     230.9661 m^2
n
13     2078.695 m^2
n
14     'Not Monitored'
n
15     'Do Not Use'
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2010,7 +2010,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::BaseStationInfo", /* .title = */ "None", - /* .docs = */ "RTCM reported base station information (sourced from RTCM Message 1005 or 1006)\n\nValid Flag Mapping:", + /* .docs = */ "RTCM reported base station information (sourced from RTCM Message 1005 or 1006)nnValid Flag Mapping:", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2616,7 +2616,7 @@ struct MetadataFor }, { /* .name = */ "lock_time", - /* .docs = */ "DOC\nMinimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver.", + /* .docs = */ "DOCnMinimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2728,7 +2728,7 @@ struct MetadataFor }, { /* .name = */ "iodc", - /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", + /* .docs = */ "Issue of Data Clock. This increments each time the data changes andnrolls over at 4. It is used to make sure various raw data elements fromndifferent sources line up correctly.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3074,7 +3074,7 @@ struct MetadataFor }, { /* .name = */ "iodc", - /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", + /* .docs = */ "Issue of Data Clock. This increments each time the data changes andnrolls over at 4. It is used to make sure various raw data elements fromndifferent sources line up correctly.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index cf7d8052c..ec37446ac 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -30,7 +30,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawAccel", /* .title = */ "None", - /* .docs = */ "Three element vector representing the sensed acceleration.\nThis quantity is temperature compensated and expressed in the sensor body frame.", + /* .docs = */ "Three element vector representing the sensed acceleration.nThis quantity is temperature compensated and expressed in the sensor body frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -59,7 +59,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawGyro", /* .title = */ "None", - /* .docs = */ "Three element vector representing the sensed angular rate.\nThis quantity is temperature compensated and expressed in the sensor body frame.", + /* .docs = */ "Three element vector representing the sensed angular rate.nThis quantity is temperature compensated and expressed in the sensor body frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -88,7 +88,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawMag", /* .title = */ "None", - /* .docs = */ "Three element vector representing the sensed magnetic field.\nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .docs = */ "Three element vector representing the sensed magnetic field.nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -117,7 +117,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawPressure", /* .title = */ "None", - /* .docs = */ "Scalar value representing the sensed ambient pressure.\nThis quantity is temperature compensated.", + /* .docs = */ "Scalar value representing the sensed ambient pressure.nThis quantity is temperature compensated.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -146,7 +146,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledAccel", /* .title = */ "None", - /* .docs = */ "3-element vector representing the sensed acceleration.\nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the sensed acceleration.nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -175,7 +175,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledGyro", /* .title = */ "None", - /* .docs = */ "3-element vector representing the sensed angular rate.\nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the sensed angular rate.nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -204,7 +204,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledMag", /* .title = */ "None", - /* .docs = */ "3-element vector representing the sensed magnetic field.\nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the sensed magnetic field.nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -262,7 +262,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::DeltaTheta", /* .title = */ "None", - /* .docs = */ "3-element vector representing the time integral of angular rate.\nThis quantity is the integral of sensed angular rate over the period set by the IMU message format. It is expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the time integral of angular rate.nThis quantity is the integral of sensed angular rate over the period set by the IMU message format. It is expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -291,7 +291,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::DeltaVelocity", /* .title = */ "None", - /* .docs = */ "3-element vector representing the time integral of acceleration.\nThis quantity is the integral of sensed acceleration over the period set by the IMU message format. It is expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the time integral of acceleration.nThis quantity is the integral of sensed acceleration over the period set by the IMU message format. It is expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -320,7 +320,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::CompOrientationMatrix", /* .title = */ "Complementary Filter Orientation Matrix", - /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.nThis matrix satisfies the following relationship:nnEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
nnWhere:
nnEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
n
nThe matrix elements are stored is row-major order: EQSTART M = begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} end{bmatrix} EQEND", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -349,7 +349,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::CompQuaternion", /* .title = */ "Complementary Filter Quaternion", - /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.\nThis quaternion satisfies the following relationship:\n\nEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
\nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", + /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.nThis quaternion satisfies the following relationship:nnEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
nnWhere:
nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -396,7 +396,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::CompEulerAngles", /* .title = */ "Complementary Filter Euler Angles", - /* .docs = */ "Euler angles describing the orientation of the device with respect to the NED local-level frame.\nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", + /* .docs = */ "Euler angles describing the orientation of the device with respect to the NED local-level frame.nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -590,7 +590,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::GpsTimestamp", /* .title = */ "None", - /* .docs = */ "GPS timestamp of the SENSOR data\n\nShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.\nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.\nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.\n\nNote: this data field may be deprecated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead.", + /* .docs = */ "GPS timestamp of the SENSOR datannShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.nnNote: this data field may be deprecated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -637,7 +637,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::TemperatureAbs", /* .title = */ "Temperature Statistics", - /* .docs = */ "SENSOR reported temperature statistics\n\nTemperature may originate from the MEMS sensors, or be calculated in combination with board temperature sensors.\nAll quantities are calculated with respect to the last power on or reset, whichever is later.\n", + /* .docs = */ "SENSOR reported temperature statisticsnnTemperature may originate from the MEMS sensors, or be calculated in combination with board temperature sensors.nAll quantities are calculated with respect to the last power on or reset, whichever is later.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -666,7 +666,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::UpVector", /* .title = */ "None", - /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimated vertical direction.\nThis quantity is expressed in the vehicle frame.\n\nThis quantity is sensitive to non-gravitational accelerations, which may cause notable deviations from the true vertical direction.\n\nFor legacy reasons, this vector is the inverse of the gravity vector.\n", + /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimated vertical direction.nThis quantity is expressed in the vehicle frame.nnThis quantity is sensitive to non-gravitational accelerations, which may cause notable deviations from the true vertical direction.nnFor legacy reasons, this vector is the inverse of the gravity vector.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -695,7 +695,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::NorthVector", /* .title = */ "None", - /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimate of magnetic north.\nThis quantity is expressed in the vehicle frame.\n\nThis quantity is sensitive to local magnetic field perturbations, which may cause notable deviations from true magnetic north.", + /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimate of magnetic north.nThis quantity is expressed in the vehicle frame.nnThis quantity is sensitive to local magnetic field perturbations, which may cause notable deviations from true magnetic north.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/data_shared.hpp b/src/cpp/mip/metadata/definitions/data_shared.hpp index 24409e893..3719eec0e 100644 --- a/src/cpp/mip/metadata/definitions/data_shared.hpp +++ b/src/cpp/mip/metadata/definitions/data_shared.hpp @@ -18,7 +18,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "trigger_id", - /* .docs = */ "Trigger ID number. If 0, this message was emitted due to being\nscheduled in the 3DM Message Format Command (0x0C,0x0F).", + /* .docs = */ "Trigger ID number. If 0, this message was emitted due to beingnscheduled in the 3DM Message Format Command (0x0C,0x0F).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -30,7 +30,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::EventSource", /* .title = */ "None", - /* .docs = */ "Identifies which event trigger caused this packet to be emitted.\n\nGenerally this is used to determine whether a packet was emitted\ndue to scheduled streaming or due to an event.", + /* .docs = */ "Identifies which event trigger caused this packet to be emitted.nnGenerally this is used to determine whether a packet was emittedndue to scheduled streaming or due to an event.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -59,7 +59,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::Ticks", /* .title = */ "None", - /* .docs = */ "Time since powerup in multiples of the base rate.\n\nThe counter will wrap around to 0 after approximately 50 days.\nOne tick is equivalent to one base period (reciprocal of the base rate).", + /* .docs = */ "Time since powerup in multiples of the base rate.nnThe counter will wrap around to 0 after approximately 50 days.nOne tick is equivalent to one base period (reciprocal of the base rate).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -88,7 +88,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::DeltaTicks", /* .title = */ "None", - /* .docs = */ "Ticks since the last output of this field.\n\nThis field can be used to track the amount of time passed between\nevent occurrences.\nOne tick is equivalent to one base period (reciprocal of the base rate).", + /* .docs = */ "Ticks since the last output of this field.nnThis field can be used to track the amount of time passed betweennevent occurrences.nOne tick is equivalent to one base period (reciprocal of the base rate).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -155,7 +155,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::GpsTimestamp", /* .title = */ "None", - /* .docs = */ "Outputs the current GPS system time in time-of-week and week number format.\n\nFor events, this is the time of the event trigger.\nIn order to be valid, a PPS signal needs to be present, and both a valid GPS time-of-week and week number command (0x0C, 0x72) need to be received after PPS sync has been achieved.", + /* .docs = */ "Outputs the current GPS system time in time-of-week and week number format.nnFor events, this is the time of the event trigger.nIn order to be valid, a PPS signal needs to be present, and both a valid GPS time-of-week and week number command (0x0C, 0x72) need to be received after PPS sync has been achieved.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -184,7 +184,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::DeltaTime", /* .title = */ "None", - /* .docs = */ "Time in the synchronized clock domain since the last output of this field within the same descriptor set and event instance.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.\n\nThis field contains the same value as the delta external time field, 0xD8,\nbut is expressed in seconds. Transmission of either of these fields\nrestarts a shared counter, so only one should be streamed at a time to\navoid confusion. The counter is not shared across descriptors sets or\nbetween event instances.", + /* .docs = */ "Time in the synchronized clock domain since the last output of this field within the same descriptor set and event instance.nnThis can be used to track the amount of time passed betweennevent occurrences. See the manual page on delta time quantities.nnThis field contains the same value as the delta external time field, 0xD8,nbut is expressed in seconds. Transmission of either of these fieldsnrestarts a shared counter, so only one should be streamed at a time tonavoid confusion. The counter is not shared across descriptors sets ornbetween event instances.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -213,7 +213,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ReferenceTimestamp", /* .title = */ "None", - /* .docs = */ "Internal reference timestamp.\n\nThis timestamp represents the time at which the corresponding\ndata was sampled, according to the internal reference clock.\n\nThis is a monotonic clock which never jumps. The value is always valid.\n\nFor events, this is the time of the event trigger.", + /* .docs = */ "Internal reference timestamp.nnThis timestamp represents the time at which the correspondingndata was sampled, according to the internal reference clock.nnThis is a monotonic clock which never jumps. The value is always valid.nnFor events, this is the time of the event trigger.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -242,7 +242,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ReferenceTimeDelta", /* .title = */ "None", - /* .docs = */ "Delta time since the last packet.\n\nDifference between the time as reported by the shared reference time field, 0xD5,\nand the previous output of this delta quantity within the same descriptor set and event instance.\n\nThe delta is based on the reference time which never jumps. The value\nis always valid.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.", + /* .docs = */ "Delta time since the last packet.nnDifference between the time as reported by the shared reference time field, 0xD5,nand the previous output of this delta quantity within the same descriptor set and event instance.nnThe delta is based on the reference time which never jumps. The valuenis always valid.nnThis can be used to track the amount of time passed betweennevent occurrences. See the manual page on delta time quantities.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -298,7 +298,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ExternalTimestamp", /* .title = */ "None", - /* .docs = */ "External timestamp in nanoseconds.\n\nThis timestamp represents the time at which the corresponding\ndata was sampled in the external clock domain.\nEquivalent to the GPS Timestamp but in nanoseconds.\n\nFor events, this is the time of the event trigger.\n\nTo be valid, external clock sync must be achieved using the PPS input.", + /* .docs = */ "External timestamp in nanoseconds.nnThis timestamp represents the time at which the correspondingndata was sampled in the external clock domain.nEquivalent to the GPS Timestamp but in nanoseconds.nnFor events, this is the time of the event trigger.nnTo be valid, external clock sync must be achieved using the PPS input.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -354,7 +354,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ExternalTimeDelta", /* .title = */ "None", - /* .docs = */ "Delta time since the last packet containing delta external (0xFF,0xD4) or delta gps time (0xFF,0xD8).\n\nDifference between the time as reported by the shared external time field, 0xD7,\nand the previous output of this delta quantity within the same descriptor set and event instance.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.\n\nThis field contains the same value as the delta gps time field, 0xD4,\nbut is expressed in nanoseconds. Transmission of either of these fields\nrestarts a shared counter, so only one should be streamed at a time to\navoid confusion. The counter is not shared across descriptors sets or\nbetween event instances.", + /* .docs = */ "Delta time since the last packet containing delta external (0xFF,0xD4) or delta gps time (0xFF,0xD8).nnDifference between the time as reported by the shared external time field, 0xD7,nand the previous output of this delta quantity within the same descriptor set and event instance.nnThis can be used to track the amount of time passed betweennevent occurrences. See the manual page on delta time quantities.nnThis field contains the same value as the delta gps time field, 0xD4,nbut is expressed in nanoseconds. Transmission of either of these fieldsnrestarts a shared counter, so only one should be streamed at a time tonavoid confusion. The counter is not shared across descriptors sets ornbetween event instances.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/data_system.hpp b/src/cpp/mip/metadata/definitions/data_system.hpp index de699bd71..a8660f42c 100644 --- a/src/cpp/mip/metadata/definitions/data_system.hpp +++ b/src/cpp/mip/metadata/definitions/data_system.hpp @@ -18,7 +18,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "result", - /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", + /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.nBits are least-significant-byte first. For example, bit 0 isnlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],nbit 8 is located at bit 0 of result[1], and bit 127 is located at bitn7 of result[15].", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -30,7 +30,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::BuiltInTest", /* .title = */ "None", - /* .docs = */ "Contains the continuous built-in-test (BIT) results.\n\nDue to the large size of this field, it is recommended to stream it at\na low rate or poll it on demand.\n\nThese bits are 'sticky' until the next output message. If a fault occurs\nin between scheduled messages or while the device is idle, the next\npacket with this field will have the corresponding flags set. The flag\nis then cleared unless the fault persists.\n\nUnlike the commanded BIT, some bits may be 1 in certain\nnon-fault situations, so simply checking if the result is all 0s is\nnot very useful. For example, on devices with a built-in GNSS receiver,\na 'solution fault' bit may be set before the receiver has obtained\na position fix. Consult the device manual to determine which bits are\nof interest for your application.\n\nAll unspecified bits are reserved for future use and must be ignored.\n", + /* .docs = */ "Contains the continuous built-in-test (BIT) results.nnDue to the large size of this field, it is recommended to stream it atna low rate or poll it on demand.nnThese bits are 'sticky' until the next output message. If a fault occursnin between scheduled messages or while the device is idle, the nextnpacket with this field will have the corresponding flags set. The flagnis then cleared unless the fault persists.nnUnlike the commanded BIT, some bits may be 1 in certainnnon-fault situations, so simply checking if the result is all 0s isnnot very useful. For example, on devices with a built-in GNSS receiver,na 'solution fault' bit may be set before the receiver has obtainedna position fix. Consult the device manual to determine which bits arenof interest for your application.nnAll unspecified bits are reserved for future use and must be ignored.n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -47,7 +47,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "time_sync", - /* .docs = */ "True if sync with the PPS signal is currently valid. False if PPS\nfeature is disabled or a PPS signal is not detected.", + /* .docs = */ "True if sync with the PPS signal is currently valid. False if PPSnfeature is disabled or a PPS signal is not detected.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -56,7 +56,7 @@ struct MetadataFor }, { /* .name = */ "last_pps_rcvd", - /* .docs = */ "Elapsed time in seconds since last PPS was received, with a maximum\nvalue of 255.", + /* .docs = */ "Elapsed time in seconds since last PPS was received, with a maximumnvalue of 255.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -85,7 +85,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "states", - /* .docs = */ "Bitfield containing the states for each GPIO pin.
\nBit 0 (0x01): pin 1
\nBit 1 (0x02): pin 2
\nBit 2 (0x04): pin 3
\nBit 3 (0x08): pin 4
\nBits for pins that don't exist will read as 0.", + /* .docs = */ "Bitfield containing the states for each GPIO pin.
nBit 0 (0x01): pin 1
nBit 1 (0x02): pin 2
nBit 2 (0x04): pin 3
nBit 3 (0x08): pin 4
nBits for pins that don't exist will read as 0.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -97,7 +97,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::GpioState", /* .title = */ "None", - /* .docs = */ "Indicates the state of all of the user GPIO pins.\n\nThis message can be used to correlate external signals\nwith the device time or other data quantities. It should\ngenerally be used with slow GPIO signals as brief pulses\nshorter than the scheduled data rate will be missed.\n\nTo synchronize with faster signals and pulses, or for more accurate timestamping,\nutilize the event system and set the GPIO feature to TIMESTAMP in the 3DM GPIO\nConfiguration command (0x0C,0x41).\n\nThese GPIO states are sampled within one base period\nof the system data descriptor set.\n\nTo obtain valid readings, the desired pin(s) must be configured to the GPIO feature\n(either input or output behavior) using the 3DM GPIO Configuration command\n(0x0C,0x41). Other gpio features may work on some devices but this is not guaranteed.\nConsult the factory before producing a design relying on reading pins configured\nto other feature types.", + /* .docs = */ "Indicates the state of all of the user GPIO pins.nnThis message can be used to correlate external signalsnwith the device time or other data quantities. It shouldngenerally be used with slow GPIO signals as brief pulsesnshorter than the scheduled data rate will be missed.nnTo synchronize with faster signals and pulses, or for more accurate timestamping,nutilize the event system and set the GPIO feature to TIMESTAMP in the 3DM GPIOnConfiguration command (0x0C,0x41).nnThese GPIO states are sampled within one base periodnof the system data descriptor set.nnTo obtain valid readings, the desired pin(s) must be configured to the GPIO featuren(either input or output behavior) using the 3DM GPIO Configuration commandn(0x0C,0x41). Other gpio features may work on some devices but this is not guaranteed.nConsult the factory before producing a design relying on reading pins configurednto other feature types.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -135,7 +135,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::GpioAnalogValue", /* .title = */ "None", - /* .docs = */ "Indicates the analog value of the given user GPIO.\nThe pin must be configured for analog input.", + /* .docs = */ "Indicates the analog value of the given user GPIO.nThe pin must be configured for analog input.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, From cdc720279cc141ab465c1b4072063b8f008a607b Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 24 Jul 2024 14:12:49 -0400 Subject: [PATCH 055/147] Fix compilation of some examples and tests. --- docs/serialization.svg | 4 ++++ .../CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c | 2 +- .../CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp | 2 +- .../microstrain/common/serialization/serializer.hpp | 8 ++++---- src/cpp/mip/definitions/common.hpp | 2 +- test/mip/test_mip.cpp | 12 +++++++----- 6 files changed, 18 insertions(+), 12 deletions(-) create mode 100644 docs/serialization.svg diff --git a/docs/serialization.svg b/docs/serialization.svg new file mode 100644 index 000000000..638d406d6 --- /dev/null +++ b/docs/serialization.svg @@ -0,0 +1,4 @@ + + + +
template<Endian> class Serializer
template<Endian> class Serializer
level 3
level 3
level 1
level 1
level 2
level 2
SerializerBase
SerializerBase
arithmetic / builtin types
(u)int8/16/32/64, float, bool, char
arithmetic / builtin types...
Enum types
using std::underlying_type
Enum types...
Fixed-size arrays
std::array, T array[N]
Fixed-size arrays...
Runtime-size arrays
std::vector, std::span, ptr+size
Runtime-size arrays...
std::tuple, multiple parameters
std::tuple, multiple parameters
Class types
if class has insert,extract members
Class types...
raw buffer helpers
insert(T, buffer, size)
extract(T, buffer, size)
raw buffer helpers...
extract and return value
optional<T> extract(serializer)
extract and return value...
serializer insert/extract member fns
Redirects to non-member functions
serializer insert/extract member...
serializer extract_count member fn
Gets an integer with maximum limit
serializer extract_count member f...
namespace microstrain
namespace microstrain
namespace serialization
namespace serialization
namespace little_endian
namespace little_endian
namespace big_endian
namespace big_endian
write<Endian>(buffer, T)
read<Endian>(buffer, T)
write<Endian>(buffer, T)...
write(uint8_t* buffer, T value)
read(const uint8_t* buffer, T& value)
write(uint8_t* buffer, T value)...
write(uint8_t* buffer, T value)
read(const uint8_t* buffer, T& value)
write(uint8_t* buffer, T value)...
microstrain:: insert/extract non-member functions
microstrain:: insert/extract non-member functio...
mip namespace
mip namespace
template<class T>
insert(Serializer, Bitfield<T>)
extract(Serializer, Bitfield<T>)
template<class T>...
DescriptorRate::
insert, extract
Called from ms::insert(class)
DescriptorRate::...
insert(Serializer, Vector<T,N>)
extract(Serializer, vector<T,N>)
insert(Serializer, Vector<T,N>)...
mip field classes & structs
insert, extract member functions
mip field classes & structs...
Non-member functions in the mip namespace are found via argument-dependent lookup (ADL)
See https://en.cppreference.com/w/cpp/language/adl
(use "using microstrain::insert" and then call just "insert"
 to include mip::insert when the type is in the mip namespace)
Non-member functions in the mip namespace are found via argument-dependent lookup (AD...
\ No newline at end of file diff --git a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c index 4721360cc..293d618f3 100644 --- a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c @@ -28,7 +28,7 @@ //////////////////////////////////////////////////////////////////////////////// #include -#include +#include #include #include diff --git a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp index 74bd0b228..31e060489 100644 --- a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp @@ -75,7 +75,7 @@ int main(int argc, const char* argv[]) { std::unique_ptr utils = handleCommonArgs(argc, argv); - std::unique_ptr& device = utils->device; + std::unique_ptr& device = utils->device; printf("Connecting to and configuring sensor.\n"); diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index c2be2e46c..95e6263c1 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -37,10 +37,10 @@ class SerializerBase size_t offset() const { return m_offset; } int remaining() const { return int(m_size - m_offset); } - bool noRemaining() const { return m_offset == m_size; } bool isOverrun() const { return m_offset > m_size; } bool isOk() const { return !isOverrun(); } - bool hasRemaining(size_t count) const { return m_offset+count <= m_size; } + bool isFinished() const { return m_offset == m_size; } + bool hasRemaining(size_t count=0) const { return m_offset+count <= m_size; } const uint8_t* basePointer() const { return m_ptr; } uint8_t* basePointer() { return m_ptr; } @@ -361,7 +361,7 @@ bool insert(const T& value, uint8_t* buffer, size_t buffer_length, size_t offset { Serializer serializer(buffer, buffer_length, offset); serializer.insert(value); - return exact_size ? serializer.noRemaining() : serializer.isOk(); + return exact_size ? serializer.isFinished() : serializer.isOk(); } template @@ -369,7 +369,7 @@ bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offse { Serializer serializer(buffer, buffer_length, offset); extract(serializer, value); - return exact_size ? serializer.noRemaining() : serializer.isOk(); + return exact_size ? serializer.isFinished() : serializer.isOk(); } diff --git a/src/cpp/mip/definitions/common.hpp b/src/cpp/mip/definitions/common.hpp index be7f4f277..2f8817382 100644 --- a/src/cpp/mip/definitions/common.hpp +++ b/src/cpp/mip/definitions/common.hpp @@ -95,7 +95,7 @@ struct Vector ///@param ptr Pointer to data. Can be NULL if n==0. ///@param n Number of elements in ptr. Clamped to N. template - void copyFrom(const U* ptr, size_t n) { if(n>N) n=N; for(size_t i=0; iN) n=N; for(size_t i=0; i Date: Wed, 24 Jul 2024 14:41:02 -0400 Subject: [PATCH 056/147] Incorporate new generated definitions. --- .../mip/metadata/definitions/commands_3dm.hpp | 110 ++++++++--------- .../metadata/definitions/commands_aiding.hpp | 4 +- .../metadata/definitions/commands_base.hpp | 22 ++-- .../metadata/definitions/commands_filter.hpp | 112 +++++++++--------- .../metadata/definitions/commands_gnss.hpp | 8 +- .../mip/metadata/definitions/commands_rtk.hpp | 4 +- .../metadata/definitions/commands_system.hpp | 2 +- .../mip/metadata/definitions/data_filter.hpp | 32 ++--- .../mip/metadata/definitions/data_gnss.hpp | 18 +-- .../mip/metadata/definitions/data_sensor.hpp | 32 ++--- .../mip/metadata/definitions/data_shared.hpp | 20 ++-- .../mip/metadata/definitions/data_system.hpp | 14 +-- 12 files changed, 189 insertions(+), 189 deletions(-) diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index 54572ff85..7e7d1a913 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -48,7 +48,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollImuMessage", /* .title = */ "None", - /* .docs = */ "Poll the device for an IMU message with the specified formatnnThis function polls for an IMU message using the provided format. The resulting messagenwill maintain the order of descriptors sent in the command and any unrecognizedndescriptors are ignored. If the format is not provided, the device will attempt to use thenstored format (set with the Set IMU Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as an IMU Data packet.", + /* .docs = */ "Poll the device for an IMU message with the specified format\n\nThis function polls for an IMU message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set IMU Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an IMU Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -95,7 +95,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollGnssMessage", /* .title = */ "None", - /* .docs = */ "Poll the device for an GNSS message with the specified formatnnThis function polls for a GNSS message using the provided format. The resulting messagenwill maintain the order of descriptors sent in the command and any unrecognizedndescriptors are ignored. If the format is not provided, the device will attempt to use thenstored format (set with the Set GNSS Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as a GNSS Data packet.", + /* .docs = */ "Poll the device for an GNSS message with the specified format\n\nThis function polls for a GNSS message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set GNSS Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a GNSS Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -142,7 +142,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollFilterMessage", /* .title = */ "None", - /* .docs = */ "Poll the device for an Estimation Filter message with the specified formatnnThis function polls for an Estimation Filter message using the provided format. The resulting messagenwill maintain the order of descriptors sent in the command and any unrecognizedndescriptors are ignored. If the format is not provided, the device will attempt to use thenstored format (set with the Set Estimation Filter Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as an Estimation Filter Data packet.", + /* .docs = */ "Poll the device for an Estimation Filter message with the specified format\n\nThis function polls for an Estimation Filter message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Estimation Filter Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an Estimation Filter Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -219,7 +219,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuMessageFormat", /* .title = */ "None", - /* .docs = */ "Set, read, or save the format of the IMU data packet.nnThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .docs = */ "Set, read, or save the format of the IMU data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -296,7 +296,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpsMessageFormat", /* .title = */ "None", - /* .docs = */ "Set, read, or save the format of the GNSS data packet.nnThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .docs = */ "Set, read, or save the format of the GNSS data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -373,7 +373,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FilterMessageFormat", /* .title = */ "None", - /* .docs = */ "Set, read, or save the format of the Estimation Filter data packet.nnThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .docs = */ "Set, read, or save the format of the Estimation Filter data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -419,7 +419,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuGetBaseRate", /* .title = */ "Get IMU Data Base Rate", - /* .docs = */ "Get the base rate for the IMU data in HznnThis is the fastest rate for this type of data available on the device.nThis is used in conjunction with the IMU Message Format Command to set streaming data at a specified rate.", + /* .docs = */ "Get the base rate for the IMU data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the IMU Message Format Command to set streaming data at a specified rate.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -465,7 +465,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpsGetBaseRate", /* .title = */ "Get GNSS Data Base Rate", - /* .docs = */ "Get the base rate for the GNSS data in HznnThis is the fastest rate for this type of data available on the device.nThis is used in conjunction with the GNSS Message Format Command to set streaming data at a specified rate.", + /* .docs = */ "Get the base rate for the GNSS data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the GNSS Message Format Command to set streaming data at a specified rate.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -511,7 +511,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FilterGetBaseRate", /* .title = */ "Get Estimation Filter Data Base Rate", - /* .docs = */ "Get the base rate for the Estimation Filter data in HznnThis is the fastest rate for this type of data available on the device.nThis is used in conjunction with the Estimation Filter Message Format Command to set streaming data at a specified rate.", + /* .docs = */ "Get the base rate for the Estimation Filter data in Hz\n\nThis is the fastest rate for this type of data available on the device.\nThis is used in conjunction with the Estimation Filter Message Format Command to set streaming data at a specified rate.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -567,7 +567,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollData", /* .title = */ "None", - /* .docs = */ "Poll the device for a message with the specified descriptor set and format.nnThis function polls for a message using the provided format. The resulting messagenwill maintain the order of descriptors sent in the command and any unrecognizedndescriptors are ignored. If the format is not provided, the device will attempt to use thenstored format (set with the Set Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as a normal Data packet.", + /* .docs = */ "Poll the device for a message with the specified descriptor set and format.\n\nThis function polls for a message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a normal Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -729,7 +729,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MessageFormat", /* .title = */ "None", - /* .docs = */ "Set, read, or save the format for a given data packet.nnThe resulting data messages will maintain the order of descriptors sent in the command.", + /* .docs = */ "Set, read, or save the format for a given data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -876,7 +876,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::NmeaPollData", /* .title = */ "None", - /* .docs = */ "Poll the device for a NMEA message with the specified format.nnThis function polls for a NMEA message using the provided format.nIf the format is not provided, the device will attempt to use thenstored format (set with the Set NMEA Message Format command.) If no format is providednand there is no stored format, the device will respond with a NACK. The reply packet containsnan ACK/NACK field. The polled data packet is sent separately as normal NMEA messages.", + /* .docs = */ "Poll the device for a NMEA message with the specified format.\n\nThis function polls for a NMEA message using the provided format.\nIf the format is not provided, the device will attempt to use the\nstored format (set with the Set NMEA Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as normal NMEA messages.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -975,7 +975,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::DeviceSettings", /* .title = */ "None", - /* .docs = */ "Save, Load, or Reset to Default the values for all device settings.nnWhen a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory.nnThis command should have a long timeout as it may take up to 1 second to complete.", + /* .docs = */ "Save, Load, or Reset to Default the values for all device settings.\n\nWhen a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory.\n\nThis command should have a long timeout as it may take up to 1 second to complete.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {false, false, true, true, true, true}, @@ -1034,7 +1034,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::UartBaudrate", /* .title = */ "None", - /* .docs = */ "Read, Save, Load, or Reset to Default the baud rate of the main communication channel.nnFor all functions except 0x01 (use new settings), the new baud rate value is ignored.nPlease see the device user manual for supported baud rates.nnThe device will wait until all incoming and outgoing data has been sent, upnto a maximum of 250 ms, before applying any change.nnNo guarantee is provided as to what happens to commands issued during thisndelay period; They may or may not be processed and any responses aren'tnguaranteed to be at one rate or the other. The same applies to data packets.nnIt is highly recommended that the device be idle before issuing this commandnand that it be issued in its own packet. Users should wait 250 ms afternsending this command before further interaction.", + /* .docs = */ "Read, Save, Load, or Reset to Default the baud rate of the main communication channel.\n\nFor all functions except 0x01 (use new settings), the new baud rate value is ignored.\nPlease see the device user manual for supported baud rates.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1092,7 +1092,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FactoryStreaming", /* .title = */ "None", - /* .docs = */ "Configures the device for recording data for technical support.nnThis command will configure all available data streams to predefinednformats designed to be used with technical support.", + /* .docs = */ "Configures the device for recording data for technical support.\n\nThis command will configure all available data streams to predefined\nformats designed to be used with technical support.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1148,7 +1148,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "desc_set", - /* .docs = */ "The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets.nOn Generation 5 products, this must be one of the above legacy constants.", + /* .docs = */ "The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets.\nOn Generation 5 products, this must be one of the above legacy constants.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, true, true, true, true, true}, @@ -1169,7 +1169,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::DatastreamControl", /* .title = */ "None", - /* .docs = */ "Enable/disable the selected data stream.nnEach data stream (descriptor set) can be enabled or disabled.nThe default for the device is all streams enabled.nFor all functions except 0x01 (use new setting),nthe new enable flag value is ignored and can be omitted.", + /* .docs = */ "Enable/disable the selected data stream.\n\nEach data stream (descriptor set) can be enabled or disabled.\nThe default for the device is all streams enabled.\nFor all functions except 0x01 (use new setting),\nthe new enable flag value is ignored and can be omitted.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1375,7 +1375,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ConstellationSettings", /* .title = */ "None", - /* .docs = */ "This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation.nnMaximum number of tracking channels to use (total for all constellations):n0 to max_channels_available (from reply message)nnFor each constellation you wish to use, include a ConstellationSettings struct. Note the following:nnTotal number of tracking channels (sum of 'reserved_channels' for all constellations) must be <= 32:n0 -> 32 Number of reserved channelsn0 -> 32 Max number of channels (>= reserved channels)nnThe factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3.nnWarning: SBAS functionality shall not be used in 'safety of life' applications!nWarning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK.nWarning: You cannot enable GLONASS and BeiDou at the same time.nNote: Enabling SBAS and QZSS augments GPS accuracy.nNote: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used.", + /* .docs = */ "This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation.\n\nMaximum number of tracking channels to use (total for all constellations):\n0 to max_channels_available (from reply message)\n\nFor each constellation you wish to use, include a ConstellationSettings struct. Note the following:\n\nTotal number of tracking channels (sum of 'reserved_channels' for all constellations) must be <= 32:\n0 -> 32 Number of reserved channels\n0 -> 32 Max number of channels (>= reserved channels)\n\nThe factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3.\n\nWarning: SBAS functionality shall not be used in 'safety of life' applications!\nWarning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK.\nWarning: You cannot enable GLONASS and BeiDou at the same time.\nNote: Enabling SBAS and QZSS augments GPS accuracy.\nNote: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1508,7 +1508,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssSbasSettings", /* .title = */ "SBAS Settings", - /* .docs = */ "Configure the SBAS subsystemnnn", + /* .docs = */ "Configure the SBAS subsystem\n\n\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1604,7 +1604,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssAssistedFix", /* .title = */ "GNSS Assisted Fix Settings", - /* .docs = */ "Set the options for assisted GNSS fix.nnDevices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM.nThese storage mechanisms are used to retain information about the last good GNSS fix. This can greatly reduces the TTFF (Time To First Fix) depending on the age of the stored information.nThe TTFF can be as low as one second, or up to the equivalent of a cold start. There is a small increase in power used when enabling assisted fix.nnThe fastest fix will be obtained by supplying the device with a GNSS Assist Time Update message containing the current GPS time immediately after subsequent power up.nThis allows the device to determine if the last GNSS information saved is still fresh enough to improve the TTFF.nnNOTE: Non-volatile GNSS memory is cleared when going from an enabled state to a disabled state.nWARNING: The clearing operation results in an erase operation on the GNSS Flash. The flash has a limited durability of 100,000 write/erase cycles", + /* .docs = */ "Set the options for assisted GNSS fix.\n\nDevices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM.\nThese storage mechanisms are used to retain information about the last good GNSS fix. This can greatly reduces the TTFF (Time To First Fix) depending on the age of the stored information.\nThe TTFF can be as low as one second, or up to the equivalent of a cold start. There is a small increase in power used when enabling assisted fix.\n\nThe fastest fix will be obtained by supplying the device with a GNSS Assist Time Update message containing the current GPS time immediately after subsequent power up.\nThis allows the device to determine if the last GNSS information saved is still fresh enough to improve the TTFF.\n\nNOTE: Non-volatile GNSS memory is cleared when going from an enabled state to a disabled state.\nWARNING: The clearing operation results in an erase operation on the GNSS Flash. The flash has a limited durability of 100,000 write/erase cycles", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1699,7 +1699,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssTimeAssistance", /* .title = */ "None", - /* .docs = */ "Provide the GNSS subsystem with initial time information.nnThis message is required immediately after power up if GNSS Assist was enabled when the device was powered off.nThis will initialize the subsystem clock to help reduce the time to first fix (TTFF).", + /* .docs = */ "Provide the GNSS subsystem with initial time information.\n\nThis message is required immediately after power up if GNSS Assist was enabled when the device was powered off.\nThis will initialize the subsystem clock to help reduce the time to first fix (TTFF).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, false, false, false, true}, @@ -1743,7 +1743,7 @@ struct MetadataFor }, { /* .name = */ "frequency", - /* .docs = */ "The cutoff frequency of the filter. If the filter is innauto mode, this value is unspecified.", + /* .docs = */ "The cutoff frequency of the filter. If the filter is in\nauto mode, this value is unspecified.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -1782,7 +1782,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "target_descriptor", - /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.nSupported values are accel (0x04), gyro (0x05), mag (0x06), andnpressure (0x17), provided the data is supported by the device.nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", + /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.\nSupported values are accel (0x04), gyro (0x05), mag (0x06), and\npressure (0x17), provided the data is supported by the device.\nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, true, true, true, true, true}, @@ -1800,7 +1800,7 @@ struct MetadataFor }, { /* .name = */ "manual", - /* .docs = */ "If false, the cutoff frequency is set to half of thenstreaming rate as configured by the message format command.nOtherwise, the cutoff frequency is set according to thenfollowing 'frequency' parameter.", + /* .docs = */ "If false, the cutoff frequency is set to half of the\nstreaming rate as configured by the message format command.\nOtherwise, the cutoff frequency is set according to the\nfollowing 'frequency' parameter.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -1830,7 +1830,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuLowpassFilter", /* .title = */ "Advanced Low-Pass Filter Settings", - /* .docs = */ "Advanced configuration for the IMU data quantity low-pass filters.nnDeprecated, use the lowpass filter (0x0C,0x54) command instead.nnThe scaled data quantities are by default filtered through a single-pole IIR low-pass filternwhich is configured with a -3dB cutoff frequency of half the reporting frequency (set byndecimation factor in the IMU Message Format command) to prevent aliasing on a per datanquantity basis. This advanced configuration command allows for the cutoff frequency tonbe configured independently of the data reporting frequency as well as allowing for ancomplete bypass of the digital low-pass filter.nnPossible data descriptors:n0x04 - Scaled accelerometer datan0x05 - Scaled gyro datan0x06 - Scaled magnetometer data (if applicable)n0x17 - Scaled pressure data (if applicable)", + /* .docs = */ "Advanced configuration for the IMU data quantity low-pass filters.\n\nDeprecated, use the lowpass filter (0x0C,0x54) command instead.\n\nThe scaled data quantities are by default filtered through a single-pole IIR low-pass filter\nwhich is configured with a -3dB cutoff frequency of half the reporting frequency (set by\ndecimation factor in the IMU Message Format command) to prevent aliasing on a per data\nquantity basis. This advanced configuration command allows for the cutoff frequency to\nbe configured independently of the data reporting frequency as well as allowing for a\ncomplete bypass of the digital low-pass filter.\n\nPossible data descriptors:\n0x04 - Scaled accelerometer data\n0x05 - Scaled gyro data\n0x06 - Scaled magnetometer data (if applicable)\n0x17 - Scaled pressure data (if applicable)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2099,7 +2099,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpioConfig", /* .title = */ "GPIO Configuration", - /* .docs = */ "Configures the user GPIO pins on the connector for use with several built-in functions or for general input or output.nnGPIO pins are device-dependent. Some features are only available onncertain pins. Some behaviors require specific configurations.nConsult the device user manual for restrictions and default settings.nnTo avoid glitches on GPIOs configured as an output in a mode other thannGPIO, always configure the relevant function before setting up the pinnwith this command. Otherwise, the pin state will be undefined betweennthis command and the one to set up the feature. For input pins, usenthis command first so the state is well-defined when the feature isninitialized.nnSome configurations can only be active on one pin at a time. If suchnconfiguration is applied to a second pin, the second one will takenprecedence and the original pin's configuration will be reset.n", + /* .docs = */ "Configures the user GPIO pins on the connector for use with several built-in functions or for general input or output.\n\nGPIO pins are device-dependent. Some features are only available on\ncertain pins. Some behaviors require specific configurations.\nConsult the device user manual for restrictions and default settings.\n\nTo avoid glitches on GPIOs configured as an output in a mode other than\nGPIO, always configure the relevant function before setting up the pin\nwith this command. Otherwise, the pin state will be undefined between\nthis command and the one to set up the feature. For input pins, use\nthis command first so the state is well-defined when the feature is\ninitialized.\n\nSome configurations can only be active on one pin at a time. If such\nconfiguration is applied to a second pin, the second one will take\nprecedence and the original pin's configuration will be reset.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2176,7 +2176,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpioState", /* .title = */ "GPIO State", - /* .docs = */ "Allows the state of the pin to be read or controlled.nnThis command serves two purposes: 1) To allow reading the state of a pin via command,nrather than polling a data quantity, and 2) to provide a way to set the output statenwithout also having to specify the operating mode.nnThe state read back from the pin is the physical state of the pin, rather than anconfiguration value. The state can be read regardless of its configuration as long asnthe device supports GPIO input on that pin. If the pin is set to an output, the readnvalue would match the output value.nnWhile the state of a pin can always be set, it will only have an observable effect ifnthe pin is set to output mode.nnThis command does not support saving, loading, or resetting the state. Instead, use thenGPIO Configuration command, which allows the initial state to be configured.", + /* .docs = */ "Allows the state of the pin to be read or controlled.\n\nThis command serves two purposes: 1) To allow reading the state of a pin via command,\nrather than polling a data quantity, and 2) to provide a way to set the output state\nwithout also having to specify the operating mode.\n\nThe state read back from the pin is the physical state of the pin, rather than a\nconfiguration value. The state can be read regardless of its configuration as long as\nthe device supports GPIO input on that pin. If the pin is set to an output, the read\nvalue would match the output value.\n\nWhile the state of a pin can always be set, it will only have an observable effect if\nthe pin is set to output mode.\n\nThis command does not support saving, loading, or resetting the state. Instead, use the\nGPIO Configuration command, which allows the initial state to be configured.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, false, false, false, true}, @@ -2221,7 +2221,7 @@ struct MetadataFor }, { /* .name = */ "scaling", - /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where snis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) andnhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.nMake this value negative if the odometer is mounted so that it rotates backwards.", + /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2269,7 +2269,7 @@ struct MetadataFor }, { /* .name = */ "scaling", - /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where snis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) andnhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.nMake this value negative if the odometer is mounted so that it rotates backwards.", + /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2290,7 +2290,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Odometer", /* .title = */ "Odometer Settings", - /* .docs = */ "Configures the hardware odometer interface.n", + /* .docs = */ "Configures the hardware odometer interface.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2369,7 +2369,7 @@ struct MetadataFor }, { /* .name = */ "max_instances", - /* .docs = */ "Number of slots available. The 'instance' number fornthe configuration or control commands must be between 1 and this value.", + /* .docs = */ "Number of slots available. The 'instance' number for\nthe configuration or control commands must be between 1 and this value.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2428,7 +2428,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GetEventSupport", /* .title = */ "Get Supported Events", - /* .docs = */ "Lists the available trigger or action types.nnThere are a limited number of trigger and action slots availablenin the device. Up to M triggers and N actions can be configured at oncenin slots 1..M and 1..N respectively. M and N are identified by thenmax_instances field in the response with the appropriate query selector.nnEach slot can be configured as one of a variety of different types ofntriggers or actions. The supported types are enumerated in the responsento this command. Additionally, there is a limit on the number of a givenntype. In other words, while the device may support M triggers in total,nonly a few of them maybe usable as a given type. This limit helps optimizendevice resources. The limit is identified in the count field.nnAll of the information in this command is available in the user manual.nThis command provides a programmatic method for obtaining the information.n", + /* .docs = */ "Lists the available trigger or action types.\n\nThere are a limited number of trigger and action slots available\nin the device. Up to M triggers and N actions can be configured at once\nin slots 1..M and 1..N respectively. M and N are identified by the\nmax_instances field in the response with the appropriate query selector.\n\nEach slot can be configured as one of a variety of different types of\ntriggers or actions. The supported types are enumerated in the response\nto this command. Additionally, there is a limit on the number of a given\ntype. In other words, while the device may support M triggers in total,\nonly a few of them maybe usable as a given type. This limit helps optimize\ndevice resources. The limit is identified in the count field.\n\nAll of the information in this command is available in the user manual.\nThis command provides a programmatic method for obtaining the information.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2466,7 +2466,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "instance", - /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to allnconfigured triggers, except when the function selector is READ.", + /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, true, true, true, true, true}, @@ -2475,7 +2475,7 @@ struct MetadataFor }, { /* .name = */ "mode", - /* .docs = */ "How to change the trigger state. Except when instance is 0, thencorresponding trigger must be configured, i.e. not have type 0.", + /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2505,7 +2505,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "instance", - /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to allnconfigured triggers, except when the function selector is READ.", + /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, true, true, true, true, true}, @@ -2514,7 +2514,7 @@ struct MetadataFor }, { /* .name = */ "mode", - /* .docs = */ "How to change the trigger state. Except when instance is 0, thencorresponding trigger must be configured, i.e. not have type 0.", + /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2526,7 +2526,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::EventControl", /* .title = */ "Event Control", - /* .docs = */ "Enables or disables event triggers.nnTriggers can be disabled, enabled, and tested. While disabled, a trigger willnnot evaluate its logic and effective behave like no trigger is configured.nA disabled trigger will not activate any actions. Triggers are disabled by default.nnUse this command to enable (or disable) a trigger, or to place it into a test mode.nWhen in test mode, the trigger logic is disabled but the output is forced tonthe active state, meaning that it will behave as if the trigger logic is satisfiednand any associated actions will execute.", + /* .docs = */ "Enables or disables event triggers.\n\nTriggers can be disabled, enabled, and tested. While disabled, a trigger will\nnot evaluate its logic and effective behave like no trigger is configured.\nA disabled trigger will not activate any actions. Triggers are disabled by default.\n\nUse this command to enable (or disable) a trigger, or to place it into a test mode.\nWhen in test mode, the trigger logic is disabled but the output is forced to\nthe active state, meaning that it will behave as if the trigger logic is satisfied\nand any associated actions will execute.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2932,7 +2932,7 @@ struct MetadataFor static constexpr inline StructInfo value = { /* .name = */ "ThresholdParams", /* .title = */ "Thresholdparams", - /* .docs = */ "Comparison of a supported MIP field parameter against a set of thresholds.nnTriggers when a data quantity meets the comparison criteria. The comparison can be eitherna window comparison with high and low thresholds or a periodic interval.nnThe data quantity is identified by the MIP descriptor set, field descriptor, and parameter number.nE.g. Scaled acceleration in the Z direction is specified with desc_set=0x80 (sensor data),nfield_desc=0x04 (scaled accel), and param_id=3 (the third parameter and Z axis).nnThe window comparison can be used for a variety of purposes, such as disablingna robot's drive motors if it tips over. In this case, a window comparison couldnbe set up to monitor the roll angle, (0x80,0x0C,3). The lower threshold would be setnto -pi/2 radians and the upper threshold to pi/2 radians.nnThe interval trigger can be used to perform an action periodically if used withna time field. E.g. to execute the action every 16 ms, set an interval comparison onnthe GPS time of week parameter (0x80,0xD3,1) with high_thres set to 0.016. The lowernthreshold determines how long the trigger is active within the 16-ms period.nnEither comparison type can be inverted by reversing the threshold values; settingnlow_thres > high_thres will result in the reverse condition.n", + /* .docs = */ "Comparison of a supported MIP field parameter against a set of thresholds.\n\nTriggers when a data quantity meets the comparison criteria. The comparison can be either\na window comparison with high and low thresholds or a periodic interval.\n\nThe data quantity is identified by the MIP descriptor set, field descriptor, and parameter number.\nE.g. Scaled acceleration in the Z direction is specified with desc_set=0x80 (sensor data),\nfield_desc=0x04 (scaled accel), and param_id=3 (the third parameter and Z axis).\n\nThe window comparison can be used for a variety of purposes, such as disabling\na robot's drive motors if it tips over. In this case, a window comparison could\nbe set up to monitor the roll angle, (0x80,0x0C,3). The lower threshold would be set\nto -pi/2 radians and the upper threshold to pi/2 radians.\n\nThe interval trigger can be used to perform an action periodically if used with\na time field. E.g. to execute the action every 16 ms, set an interval comparison on\nthe GPS time of week parameter (0x80,0xD3,1) with high_thres set to 0.016. The lower\nthreshold determines how long the trigger is active within the 16-ms period.\n\nEither comparison type can be inverted by reversing the threshold values; setting\nlow_thres > high_thres will result in the reverse condition.\n", /* .parameters = */ parameters, }; }; @@ -3204,7 +3204,7 @@ struct MetadataFor }, { /* .name = */ "decimation", - /* .docs = */ "Decimation from the base rate.nIf 0, a packet is emitted each time the trigger activates.nOtherwise, packets will be streamed while the trigger is active.nThe internal decimation counter is reset if the trigger deactivates.", + /* .docs = */ "Decimation from the base rate.\nIf 0, a packet is emitted each time the trigger activates.\nOtherwise, packets will be streamed while the trigger is active.\nThe internal decimation counter is reset if the trigger deactivates.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, @@ -3456,7 +3456,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::AccelBias", /* .title = */ "Configure Accel Bias", - /* .docs = */ "Configures the user specified accelerometer biasnnThe user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame.", + /* .docs = */ "Configures the user specified accelerometer bias\n\nThe user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3515,7 +3515,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GyroBias", /* .title = */ "Configure Gyro Bias", - /* .docs = */ "Configures the user specified gyroscope biasnnThe user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame.", + /* .docs = */ "Configures the user specified gyroscope bias\n\nThe user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3573,7 +3573,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::CaptureGyroBias", /* .title = */ "Capture Gyro Bias", - /* .docs = */ "Samples gyro for a specified time range and writes the averaged result to the Gyro Bias vector in RAMnnThe device will average the gyro output for the duration of 'averaging_time_ms.' To store the resulting vectornin non-volatile memory, use the Set Gyro Bias command.nIMPORTANT: The device must be stationary and experiencing minimum vibration for the duration of 'averaging_time_ms'nAveraging Time range: 1000 to 30,000", + /* .docs = */ "Samples gyro for a specified time range and writes the averaged result to the Gyro Bias vector in RAM\n\nThe device will average the gyro output for the duration of 'averaging_time_ms.' To store the resulting vector\nin non-volatile memory, use the Set Gyro Bias command.\nIMPORTANT: The device must be stationary and experiencing minimum vibration for the duration of 'averaging_time_ms'\nAveraging Time range: 1000 to 30,000", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -3632,7 +3632,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagHardIronOffset", /* .title = */ "Magnetometer Hard Iron Offset", - /* .docs = */ "Configure the user specified magnetometer hard iron offset vectornnThe values for this offset are determined empirically by external software algorithmsnbased on calibration data taken after the device is installed in its application. These valuesncan be obtained and set by using the LORD 'MIP Iron Calibration' application.nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.nThe offset is applied to the scaled magnetometer vector prior to output.", + /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3691,7 +3691,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagSoftIronMatrix", /* .title = */ "Magnetometer Soft Iron Matrix", - /* .docs = */ "Configure the user specified magnetometer soft iron offset matrixnnThe values for this matrix are determined empirically by external software algorithmsnbased on calibration data taken after the device is installed in its application. These valuesncan be obtained and set by using the LORD 'MIP Iron Calibration' application.nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.nThe matrix is applied to the scaled magnetometer vector prior to output.nnThe matrix is in row major order:nEQSTART M = begin{bmatrix} 0 & 1 & 2 3 & 4 & 5 6 & 7 & 8 end{bmatrix} EQENDn", + /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \\begin{bmatrix} 0 & 1 & 2 \\\ 3 & 4 & 5 \\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3845,7 +3845,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformEuler", /* .title = */ "Sensor to Vehicle Frame Transformation Euler", - /* .docs = */ "Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, Roll Euler angles.nThese are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference,nand describe the transformation of vectors from the sensor body frame to the vehicle frame.
nNote: This is the transformation, the inverse of the rotation defined in our legacy products.
nThe transformation may be stored in the device as a matrix or quaternion. When Euler angles are read back from the device, they may notnbe exactly equal to the Euler angles used to set the transformation, but they are functionally equivalent, such that they result in the same transformation.
n

nThis transformation to the vehicle frame will be applied to the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
nComplementary Filter Orientation
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
n
nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .docs = */ "Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, Roll Euler angles.\nThese are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference,\nand describe the transformation of vectors from the sensor body frame to the vehicle frame.
\nNote: This is the transformation, the inverse of the rotation defined in our legacy products.
\nThe transformation may be stored in the device as a matrix or quaternion. When Euler angles are read back from the device, they may not\nbe exactly equal to the Euler angles used to set the transformation, but they are functionally equivalent, such that they result in the same transformation.
\n

\nThis transformation to the vehicle frame will be applied to the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\nComplementary Filter Orientation
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3904,7 +3904,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformQuaternion", /* .title = */ "Sensor to Vehicle Frame Transformation Quaternion", - /* .docs = */ "Set the sensor to vehicle frame transformation using unit length quaternion.nnNote: This is the transformation, the inverse of the rotation.nnThis quaternion describes the transformation of vectors from the sensor body frame to the vehicle frame of reference, and satisfies the following relationship:
nnEQSTART p^{veh} = q^{-1} p^{sen} q EQEND
nnWhere:
nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the transformation.
nEQSTART p^{sen} = (0, v^{sen}_x, v^{sen}_y, v^{sen}_z) EQEND and EQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
nEQSTART p^{veh} = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
nnThe transformation may be stored in the device as a matrix or a quaternion. When the quaternion is read back from the device, it may notnbe exactly equal to the quaternion used to set the transformation, but it is functionally equivalent.
n

nThis transformation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
n
nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .docs = */ "Set the sensor to vehicle frame transformation using unit length quaternion.\n\nNote: This is the transformation, the inverse of the rotation.\n\nThis quaternion describes the transformation of vectors from the sensor body frame to the vehicle frame of reference, and satisfies the following relationship:
\n\nEQSTART p^{veh} = q^{-1} p^{sen} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the transformation.
\nEQSTART p^{sen} = (0, v^{sen}_x, v^{sen}_y, v^{sen}_z) EQEND and EQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART p^{veh} = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
\n\nThe transformation may be stored in the device as a matrix or a quaternion. When the quaternion is read back from the device, it may not\nbe exactly equal to the quaternion used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3963,7 +3963,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformDcm", /* .title = */ "Sensor to Vehicle Frame Transformation Direction Cosine Matrix", - /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.nnThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
nnWhere:
nnEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
n
nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} end{bmatrix} EQENDnThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may notnbe exactly equal to array used to set the transformation, but it is functionally equivalent.
n

nThis transformation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
n
nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.\n\nThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
\nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
\n\nWhere:
\n\nEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND\nThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not\nbe exactly equal to array used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -4076,7 +4076,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ComplementaryFilter", /* .title = */ "Complementary filter settings", - /* .docs = */ "Configure the settings for the complementary filter which produces the following (0x80) descriptor set values: attitude matrix (0x80,09), quaternion (0x80,0A), and Euler angle (0x80,0C) outputs.nnThe filter can be configured to correct for pitch and roll using the accelerometer (with the assumption that linear acceleration is minimal),nand to correct for heading using the magnetometer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field).nPitch/roll and heading corrections each have their own configurable time constants, with a valid range of 1-1000 seconds. The default time constant is 10 seconds.", + /* .docs = */ "Configure the settings for the complementary filter which produces the following (0x80) descriptor set values: attitude matrix (0x80,09), quaternion (0x80,0A), and Euler angle (0x80,0C) outputs.\n\nThe filter can be configured to correct for pitch and roll using the accelerometer (with the assumption that linear acceleration is minimal),\nand to correct for heading using the magnetometer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field).\nPitch/roll and heading corrections each have their own configurable time constants, with a valid range of 1-1000 seconds. The default time constant is 10 seconds.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -4175,7 +4175,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::SensorRange", /* .title = */ "Sensor Range", - /* .docs = */ "Changes the IMU sensor gain.nnThis allows you to optimize the range to get the best accuracy and performancenwhile minimizing over-range events.nnUse the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determinenthe appropriate setting value for your application. Using values other thannthose specified may result in a NACK or inaccurate measurement data.", + /* .docs = */ "Changes the IMU sensor gain.\n\nThis allows you to optimize the range to get the best accuracy and performance\nwhile minimizing over-range events.\n\nUse the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine\nthe appropriate setting value for your application. Using values other than\nthose specified may result in a NACK or inaccurate measurement data.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -4285,7 +4285,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::CalibratedSensorRanges", /* .title = */ "Get Calibrated Sensor Ranges", - /* .docs = */ "Returns the supported sensor ranges which may be used with the 3DM Sensor Range (0x0C,0x52) command.nnThe response includes an array of (u8, float) pairs which map each allowed settingnto the corresponding maximum range in physical units. See SensorRangeType for units.", + /* .docs = */ "Returns the supported sensor ranges which may be used with the 3DM Sensor Range (0x0C,0x52) command.\n\nThe response includes an array of (u8, float) pairs which map each allowed setting\nto the corresponding maximum range in physical units. See SensorRangeType for units.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -4329,7 +4329,7 @@ struct MetadataFor }, { /* .name = */ "manual", - /* .docs = */ "If false, the frequency parameter is ignored and the filternwill track to half of the configured message format frequency.", + /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -4338,7 +4338,7 @@ struct MetadataFor }, { /* .name = */ "frequency", - /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequencynwhen read out in automatic mode.", + /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -4395,7 +4395,7 @@ struct MetadataFor }, { /* .name = */ "manual", - /* .docs = */ "If false, the frequency parameter is ignored and the filternwill track to half of the configured message format frequency.", + /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -4404,7 +4404,7 @@ struct MetadataFor }, { /* .name = */ "frequency", - /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequencynwhen read out in automatic mode.", + /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -4416,7 +4416,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::LowpassFilter", /* .title = */ "Low-pass anti-aliasing filter", - /* .docs = */ "This command controls the low-pass anti-aliasing filter supported data quantities.nnSee the device user manual for data quantities which support the anti-aliasing filter.nnIf set to automatic mode, the frequency will track half of the transmission ratenof the target descriptor according to the configured message format (0x0C,0x0F).nFor example, if scaled accel (0x80,0x04) is set to stream at 100 Hz, the filter wouldnbe set to 50 Hz. Changing the message format to 200 Hz would automatically adjust thenfilter to 100 Hz.nnFor WRITE, SAVE, LOAD, and DEFAULT function selectors, the descriptor set and/or field descriptornmay be 0x00 to set, save, load, or reset the setting for all supported descriptors. Thenfield descriptor must be 0x00 if the descriptor set is 0x00.n", + /* .docs = */ "This command controls the low-pass anti-aliasing filter supported data quantities.\n\nSee the device user manual for data quantities which support the anti-aliasing filter.\n\nIf set to automatic mode, the frequency will track half of the transmission rate\nof the target descriptor according to the configured message format (0x0C,0x0F).\nFor example, if scaled accel (0x80,0x04) is set to stream at 100 Hz, the filter would\nbe set to 50 Hz. Changing the message format to 200 Hz would automatically adjust the\nfilter to 100 Hz.\n\nFor WRITE, SAVE, LOAD, and DEFAULT function selectors, the descriptor set and/or field descriptor\nmay be 0x00 to set, save, load, or reset the setting for all supported descriptors. The\nfield descriptor must be 0x00 if the descriptor set is 0x00.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, diff --git a/src/cpp/mip/metadata/definitions/commands_aiding.hpp b/src/cpp/mip/metadata/definitions/commands_aiding.hpp index 81e106171..a0f98d3d1 100644 --- a/src/cpp/mip/metadata/definitions/commands_aiding.hpp +++ b/src/cpp/mip/metadata/definitions/commands_aiding.hpp @@ -185,7 +185,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_aiding::FrameConfig", /* .title = */ "Frame Configuration", - /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID.nThe frame ID used in this command should mirror the frame ID used in the aiding commandn(if that aiding measurement is measured in this reference frame).nnThis transform satisfies the following relationship:nnEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
nnWhere:
nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
nnRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth elementnin the rotation vector is ignored and should be set to 0.nnWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.nnExample: GNSS antenna lever armnnFrame ID: 1nFormat: 1 (Euler)nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)n", + /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID.\nThe frame ID used in this command should mirror the frame ID used in the aiding command\n(if that aiding measurement is measured in this reference frame).\n\nThis transform satisfies the following relationship:\n\nEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
\n\nWhere:
\nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

\nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
\nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
\n\nRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element\nin the rotation vector is ignored and should be set to 0.\n\nWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.\n\nExample: GNSS antenna lever arm\n\nFrame ID: 1\nFormat: 1 (Euler)\nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)\nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -515,7 +515,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_aiding::PosLlh", /* .title = */ "LLH Position", - /* .docs = */ "Geodetic position aiding command.nCoordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid.nUncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height.", + /* .docs = */ "Geodetic position aiding command.\nCoordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid.\nUncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index e3247bdba..658b31d9e 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -18,7 +18,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::Ping", /* .title = */ "Ping", - /* .docs = */ "Test Communications with a device.nnThe Device will respond with an ACK, if present and operating correctly.nnIf the device is not in a normal operating mode, it may NACK.", + /* .docs = */ "Test Communications with a device.\n\nThe Device will respond with an ACK, if present and operating correctly.\n\nIf the device is not in a normal operating mode, it may NACK.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -35,7 +35,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::SetIdle", /* .title = */ "Set to idle", - /* .docs = */ "Turn off all device data streams.nnThe Device will respond with an ACK, if present and operating correctly.nThis command will suspend streaming (if enabled) or wake the device from sleep (if sleeping) to allow it to respond to status and setup commands.nYou may restore the device mode by issuing the Resume command.", + /* .docs = */ "Turn off all device data streams.\n\nThe Device will respond with an ACK, if present and operating correctly.\nThis command will suspend streaming (if enabled) or wake the device from sleep (if sleeping) to allow it to respond to status and setup commands.\nYou may restore the device mode by issuing the Resume command.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -197,7 +197,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetDeviceDescriptors", /* .title = */ "Get device descriptors", - /* .docs = */ "Get the command and data descriptors supported by the device.nnReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", + /* .docs = */ "Get the command and data descriptors supported by the device.\n\nReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.\nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -243,7 +243,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::BuiltInTest", /* .title = */ "Built in test", - /* .docs = */ "Run the device Built-In Test (BIT).nnThe Built-In Test command always returns a 32 bit value.nA value of 0 means that all tests passed.nA non-zero value indicates that not all tests passed.nReference the device user manual to decode the result.", + /* .docs = */ "Run the device Built-In Test (BIT).\n\nThe Built-In Test command always returns a 32 bit value.\nA value of 0 means that all tests passed.\nA non-zero value indicates that not all tests passed.\nReference the device user manual to decode the result.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -260,7 +260,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::Resume", /* .title = */ "Resume", - /* .docs = */ "Take the device out of idle mode.nnThe device responds with ACK upon success.", + /* .docs = */ "Take the device out of idle mode.\n\nThe device responds with ACK upon success.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -306,7 +306,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetExtendedDescriptors", /* .title = */ "Get device descriptors (extended)", - /* .docs = */ "Get the command and data descriptors supported by the device.nnReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", + /* .docs = */ "Get the command and data descriptors supported by the device.\n\nReply has two fields: 'ACK/NACK' and 'Descriptors'. The 'Descriptors' field is an array of 16 bit values.\nThe MSB specifies the descriptor set and the LSB specifies the descriptor.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -323,7 +323,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "result", - /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.nBits are least-significant-byte first. For example, bit 0 isnlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],nbit 8 is located at bit 0 of result[1], and bit 127 is located at bitn7 of result[15].", + /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -352,7 +352,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::ContinuousBit", /* .title = */ "Continuous built-in test", - /* .docs = */ "Report result of continuous built-in test.nnThis test is non-disruptive but is not as thorough as the commanded BIT.", + /* .docs = */ "Report result of continuous built-in test.\n\nThis test is non-disruptive but is not as thorough as the commanded BIT.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -429,7 +429,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::CommSpeed", /* .title = */ "Comm Port Speed", - /* .docs = */ "Controls the baud rate of a specific port on the device.nnPlease see the device user manual for supported baud rates on each port.nnThe device will wait until all incoming and outgoing data has been sent, upnto a maximum of 250 ms, before applying any change.nnNo guarantee is provided as to what happens to commands issued during thisndelay period; They may or may not be processed and any responses aren'tnguaranteed to be at one rate or the other. The same applies to data packets.nnIt is highly recommended that the device be idle before issuing this commandnand that it be issued in its own packet. Users should wait 250 ms afternsending this command before further interaction.", + /* .docs = */ "Controls the baud rate of a specific port on the device.\n\nPlease see the device user manual for supported baud rates on each port.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -487,7 +487,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GpsTimeUpdate", /* .title = */ "GPS Time Update Command", - /* .docs = */ "Set device internal GPS timenWhen combined with a PPS input signal applied to the I/O connector, this command enables complete synchronization of data outputsnwith an external time base, such as GPS system time. Since the hardware PPS synchronization can only detect the fractional number of seconds when pulses arrive,ncomplete synchronization requires that the user provide the whole number of seconds via this command. After achieving PPS synchronization, this command should be sent twice: once to set the time-of-week and once to set the week number. PPS synchronization can be verified by monitoring the time sync status message (0xA0, 0x02) or the valid flags of any shared external timestamp (0x--, D7) data field.", + /* .docs = */ "Set device internal GPS time\nWhen combined with a PPS input signal applied to the I/O connector, this command enables complete synchronization of data outputs\nwith an external time base, such as GPS system time. Since the hardware PPS synchronization can only detect the fractional number of seconds when pulses arrive,\ncomplete synchronization requires that the user provide the whole number of seconds via this command. After achieving PPS synchronization, this command should be sent twice: once to set the time-of-week and once to set the week number. PPS synchronization can be verified by monitoring the time sync status message (0xA0, 0x02) or the valid flags of any shared external timestamp (0x--, D7) data field.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, false, false, false, false, true}, @@ -504,7 +504,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::SoftReset", /* .title = */ "Reset device", - /* .docs = */ "Resets the device.nnDevice responds with ACK and immediately resets.", + /* .docs = */ "Resets the device.\n\nDevice responds with ACK and immediately resets.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/commands_filter.hpp b/src/cpp/mip/metadata/definitions/commands_filter.hpp index 7674663b6..aec302139 100644 --- a/src/cpp/mip/metadata/definitions/commands_filter.hpp +++ b/src/cpp/mip/metadata/definitions/commands_filter.hpp @@ -18,7 +18,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::Reset", /* .title = */ "Reset Navigation Filter", - /* .docs = */ "Resets the filter to the initialization state.nnIf the auto-initialization feature is disabled, the initial attitude or heading must be set innorder to enter the run state after a reset.", + /* .docs = */ "Resets the filter to the initialization state.\n\nIf the auto-initialization feature is disabled, the initial attitude or heading must be set in\norder to enter the run state after a reset.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -65,7 +65,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SetInitialAttitude", /* .title = */ "Set Initial Attitude", - /* .docs = */ "Set the sensor initial attitude.nnThis command can only be issued in the 'Init' state and should be used with a goodnestimate of the vehicle attitude. The Euler angles are the sensor body frame with respectnto the NED frame.nnThe valid input ranges are as follows:nnRoll: [-pi, pi]nPitch: [-pi/2, pi/2]nHeading: [-pi, pi]n", + /* .docs = */ "Set the sensor initial attitude.\n\nThis command can only be issued in the 'Init' state and should be used with a good\nestimate of the vehicle attitude. The Euler angles are the sensor body frame with respect\nto the NED frame.\n\nThe valid input ranges are as follows:\n\nRoll: [-pi, pi]\nPitch: [-pi/2, pi/2]\nHeading: [-pi, pi]\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -148,7 +148,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::EstimationControl", /* .title = */ "Estimation Control Flags", - /* .docs = */ "Estimation Control FlagsnnControls which parameters are estimated by the Kalman Filter.nnDesired settings should be logically ORed together.nnExamples:nn0x0001 - Enable Gyro Bias Estimation Onlyn0x0063 - Enable Gyro Bias, Accel Bias, and Mag Auto Hard and Soft Iron Cal States Onlyn", + /* .docs = */ "Estimation Control Flags\n\nControls which parameters are estimated by the Kalman Filter.\n\nDesired settings should be logically ORed together.\n\nExamples:\n\n0x0001 - Enable Gyro Bias Estimation Only\n0x0063 - Enable Gyro Bias, Accel Bias, and Mag Auto Hard and Soft Iron Cal States Only\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -240,7 +240,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::ExternalGnssUpdate", /* .title = */ "External GNSS Update", - /* .docs = */ "Provide a filter measurement from an external GNSSnnThe GNSS source control must be set to 'external' for this command to succeed, otherwise it will be NACK'd.nPlease refer to your device user manual for information on the maximum rate of this message.n", + /* .docs = */ "Provide a filter measurement from an external GNSS\n\nThe GNSS source control must be set to 'external' for this command to succeed, otherwise it will be NACK'd.\nPlease refer to your device user manual for information on the maximum rate of this message.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -287,7 +287,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::ExternalHeadingUpdate", /* .title = */ "External Heading Update", - /* .docs = */ "Provide a filter measurement from an external heading sourcennThe heading must be the sensor frame with respect to the NED frame.nnThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.nHeading angle uncertainties of <= 0.0 will be NACK'dnnPlease refer to your device user manual for information on the maximum rate of this message.nnOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.nn", + /* .docs = */ "Provide a filter measurement from an external heading source\n\nThe heading must be the sensor frame with respect to the NED frame.\n\nThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.\nHeading angle uncertainties of <= 0.0 will be NACK'd\n\nPlease refer to your device user manual for information on the maximum rate of this message.\n\nOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.\nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.\n\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -352,7 +352,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::ExternalHeadingUpdateWithTime", /* .title = */ "External Heading Update With Time", - /* .docs = */ "Provide a filter measurement from an external heading source at a specific GPS timennThis is more accurate than the External Heading Update (0x0D, 0x17) and should be used in applicationsnwhere the rate of heading change will cause significant measurement error due to the sampling, transmission,nand processing time required. Accurate time stamping of the heading information is important.nnThe heading must be the sensor frame with respect to the NED frame.nnThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.nHeading angle uncertainties of <= 0.0 will be NACK'dnnPlease refer to your device user manual for information on the maximum rate of this message.nnOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.nn", + /* .docs = */ "Provide a filter measurement from an external heading source at a specific GPS time\n\nThis is more accurate than the External Heading Update (0x0D, 0x17) and should be used in applications\nwhere the rate of heading change will cause significant measurement error due to the sampling, transmission,\nand processing time required. Accurate time stamping of the heading information is important.\n\nThe heading must be the sensor frame with respect to the NED frame.\n\nThe heading update control must be set to external for this command to update the filter; otherwise it is NACK'd.\nHeading angle uncertainties of <= 0.0 will be NACK'd\n\nPlease refer to your device user manual for information on the maximum rate of this message.\n\nOn -25 models, if the declination source (0x0D, 0x43) is not valid, true heading updates will be NACK'd.\nOn -45 models, if the declination source is invalid, magnetic heading updates will be NACK'd.\n\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -431,7 +431,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::TareOrientation", /* .title = */ "Tare Sensor Orientation", - /* .docs = */ "Tare the device orientation.nnThis function uses the current device orientation relative to the NED frame as the current sensor to vehicle transformation.nThis command is provided as a convenient way to set the sensor to vehicle frame transformation.nThe filter must be initialized and have a valid attitude output. If the attitude is not valid, an error will be returned.", + /* .docs = */ "Tare the device orientation.\n\nThis function uses the current device orientation relative to the NED frame as the current sensor to vehicle transformation.\nThis command is provided as a convenient way to set the sensor to vehicle frame transformation.\nThe filter must be initialized and have a valid attitude output. If the attitude is not valid, an error will be returned.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -606,7 +606,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationEuler", /* .title = */ "Sensor to Vehicle Frame Rotation Euler", - /* .docs = */ "Set the sensor to vehicle frame rotation using Yaw, Pitch, Roll Euler angles.nnNote: This is the rotation, the inverse of the transformation.nThese angles define the rotation from the sensor body frame to the fixed vehicle frame.
nPlease reference the device Theory of Operation for more information.
nThe rotation is stored in the device as a quaternion. When Euler angles are read back from the device, they may notnbe equivalent in value to the Euler angles used to set the rotation, but they are functionally equivalent.
n

nThis rotation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using Yaw, Pitch, Roll Euler angles.\n\nNote: This is the rotation, the inverse of the transformation.\nThese angles define the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe rotation is stored in the device as a quaternion. When Euler angles are read back from the device, they may not\nbe equivalent in value to the Euler angles used to set the rotation, but they are functionally equivalent.
\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -665,7 +665,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationDcm", /* .title = */ "Sensor to Vehicle Frame Rotation DCM", - /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.nnNote: This is the rotation, the inverse of the transformation.nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
nPlease reference the device Theory of Operation for more information.
nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may notnbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
n
nMatrix element order:

nnEQSTART T_{SEN}^{VEH} = begin{bmatrix} 0 & 1 & 2 3 & 4 & 5 6 & 7 & 8 end{bmatrix} EQENDnn

nThis rotation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \\begin{bmatrix} 0 & 1 & 2\\\ 3 & 4 & 5\\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -724,7 +724,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationQuaternion", /* .title = */ "Sensor to Vehicle Frame Rotation Quaternion", - /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.nnNote: This is the rotation, the inverse of the transformation.nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
nPlease reference the device Theory of Operation for more information.
nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may notnbe equivalent in value to the quaternion used to set the rotation, due to normalization.
n
nQuaternion element definition:

n
nEQSTART Q_{SEN}^{VEH} = begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k end{bmatrix} EQENDn

nThis rotation affects the following output quantities:

nIMU:
nScaled Acceleration
nScaled Gyro
nScaled Magnetometer
nDelta Theta
nDelta Velocity
n

nEstimation Filter:
nEstimated Orientation, Quaternion
nEstimated Orientation, Matrix
nEstimated Orientation, Euler Angles
nEstimated Linear Acceleration
nEstimated Angular Rate
nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.\n\nNote: This is the rotation, the inverse of the transformation.\nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may not\nbe equivalent in value to the quaternion used to set the rotation, due to normalization.
\n
\nQuaternion element definition:

\n
\nEQSTART Q_{SEN}^{VEH} = \\begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \\end{bmatrix} EQEND\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -783,7 +783,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleOffset", /* .title = */ "Sensor to Vehicle Frame Offset", - /* .docs = */ "Set the sensor to vehicle frame offset, expressed in the sensor frame.nnThis is a simple offset, not a lever arm. It does not compensate for inertial effects experienced from being offset from the center of gravity/rotation of the vehicle.nIt simply adds the offset to the position output to express it in the origin of the user's vehicle frame.nnThis offset affects the following output quantities:nEstimated LLH PositionnnThe magnitude of the offset vector is limited to 10 meters", + /* .docs = */ "Set the sensor to vehicle frame offset, expressed in the sensor frame.\n\nThis is a simple offset, not a lever arm. It does not compensate for inertial effects experienced from being offset from the center of gravity/rotation of the vehicle.\nIt simply adds the offset to the position output to express it in the origin of the user's vehicle frame.\n\nThis offset affects the following output quantities:\nEstimated LLH Position\n\nThe magnitude of the offset vector is limited to 10 meters", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -842,7 +842,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AntennaOffset", /* .title = */ "GNSS Antenna Offset Control", - /* .docs = */ "Configure the GNSS antenna offset.nnFor 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.nnFor 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center.nnThis command should also be used for CV7 / GV7-INS NMEA Input over GPIO.nnThe magnitude of the offset vector is limited to 10 metersn", + /* .docs = */ "Configure the GNSS antenna offset.\n\nFor 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.\n\nFor 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center.\n\nThis command should also be used for CV7 / GV7-INS NMEA Input over GPIO.\n\nThe magnitude of the offset vector is limited to 10 meters\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -922,7 +922,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GnssSource", /* .title = */ "GNSS Aiding Source Control", - /* .docs = */ "Control the source of GNSS information used to update the Kalman Filter.nnChanging the GNSS source while the sensor is in the 'running' state may temporarily placenit back in the 'init' state until the new source of GNSS data is received.n", + /* .docs = */ "Control the source of GNSS information used to update the Kalman Filter.\n\nChanging the GNSS source while the sensor is in the 'running' state may temporarily place\nit back in the 'init' state until the new source of GNSS data is received.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1006,7 +1006,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::HeadingSource", /* .title = */ "Heading Aiding Source Control", - /* .docs = */ "Control the source of heading information used to update the Kalman Filter.nn1. To use internal GNSS velocity vector for heading updates, the target applicationnmust have minimal (preferably no) side-slip. This option is good for wheeled vehicles.nn2. On some devices, when using GNSS velocity vector for heading updates, the X-axis of the devicenmust align with the direction of travel. Please reference the user guide for your particular device tondetermine if this limitation is applicable.nn3. When none is selected, the heading estimate can still converge if GNSS is available and sufficient dynamic motionn(change in direction of travel and acceleration) is experienced. The heading may drift when: stationary, travelingnat a constant speed, or during a constant course over ground.", + /* .docs = */ "Control the source of heading information used to update the Kalman Filter.\n\n1. To use internal GNSS velocity vector for heading updates, the target application\nmust have minimal (preferably no) side-slip. This option is good for wheeled vehicles.\n\n2. On some devices, when using GNSS velocity vector for heading updates, the X-axis of the device\nmust align with the direction of travel. Please reference the user guide for your particular device to\ndetermine if this limitation is applicable.\n\n3. When none is selected, the heading estimate can still converge if GNSS is available and sufficient dynamic motion\n(change in direction of travel and acceleration) is experienced. The heading may drift when: stationary, traveling\nat a constant speed, or during a constant course over ground.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1065,7 +1065,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AutoInitControl", /* .title = */ "Auto-initialization Control", - /* .docs = */ "Filter Auto-initialization ControlnnEnable/Disable automatic initialization upon device startup.nnPossible enable values:nn0x00 - Disable auto-initializationn0x01 - Enable auto-initializationn", + /* .docs = */ "Filter Auto-initialization Control\n\nEnable/Disable automatic initialization upon device startup.\n\nPossible enable values:\n\n0x00 - Disable auto-initialization\n0x01 - Enable auto-initialization\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1124,7 +1124,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AccelNoise", /* .title = */ "Accelerometer Noise Standard Deviation", - /* .docs = */ "Accelerometer Noise Standard DeviationnnEach of the noise values must be greater than 0.0.nnThe noise value represents process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.nDefault values provide good performance for most laboratory conditions.", + /* .docs = */ "Accelerometer Noise Standard Deviation\n\nEach of the noise values must be greater than 0.0.\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.\nDefault values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1183,7 +1183,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GyroNoise", /* .title = */ "Gyroscope Noise Standard Deviation", - /* .docs = */ "Gyroscope Noise Standard DeviationnnEach of the noise values must be greater than 0.0nnThe noise value represents process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.nDefault values provide good performance for most laboratory conditions.", + /* .docs = */ "Gyroscope Noise Standard Deviation\n\nEach of the noise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.\nDefault values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1260,7 +1260,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AccelBiasModel", /* .title = */ "Accelerometer Bias Model Parameters", - /* .docs = */ "Accelerometer Bias Model ParametersnnNoise values must be greater than 0.0n", + /* .docs = */ "Accelerometer Bias Model Parameters\n\nNoise values must be greater than 0.0\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1337,7 +1337,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GyroBiasModel", /* .title = */ "Gyroscope Bias Model Parameters", - /* .docs = */ "Gyroscope Bias Model ParametersnnNoise values must be greater than 0.0n", + /* .docs = */ "Gyroscope Bias Model Parameters\n\nNoise values must be greater than 0.0\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1415,7 +1415,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AltitudeAiding", /* .title = */ "Altitude Aiding Control", - /* .docs = */ "Select altitude input for absolute altitude and/or vertical velocity. The primary altitude reading is always GNSS.nAiding inputs are used to improve GNSS altitude readings when GNSS is available and to backup GNSS during outages.nnPressure altitude is based on 'instant sea level pressure' which is dependent on location and weather conditions and can vary by more than 40 meters.n", + /* .docs = */ "Select altitude input for absolute altitude and/or vertical velocity. The primary altitude reading is always GNSS.\nAiding inputs are used to improve GNSS altitude readings when GNSS is available and to backup GNSS during outages.\n\nPressure altitude is based on 'instant sea level pressure' which is dependent on location and weather conditions and can vary by more than 40 meters.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1493,7 +1493,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::PitchRollAiding", /* .title = */ "Pitch/Roll Aiding Control", - /* .docs = */ "Select pitch/roll aiding input. Pitch/roll reading is always derived from GNSS corrected inertial solution.nAiding inputs are used to improve that solution during periods of low dynamics and GNSS outages.", + /* .docs = */ "Select pitch/roll aiding input. Pitch/roll reading is always derived from GNSS corrected inertial solution.\nAiding inputs are used to improve that solution during periods of low dynamics and GNSS outages.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1570,7 +1570,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AutoZupt", /* .title = */ "Zero Velocity Update Control", - /* .docs = */ "The ZUPT is triggered when the scalar magnitude of the GNSS reported velocity vector is equal-to or less than the threshold value.nThe device will NACK threshold values that are less than zero (i.e.negative.)", + /* .docs = */ "The ZUPT is triggered when the scalar magnitude of the GNSS reported velocity vector is equal-to or less than the threshold value.\nThe device will NACK threshold values that are less than zero (i.e.negative.)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1647,7 +1647,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AutoAngularZupt", /* .title = */ "Zero Angular Rate Update Control", - /* .docs = */ "Zero Angular Rate UpdatenThe ZUPT is triggered when the scalar magnitude of the angular rate vector is equal-to or less than the threshold value.nThe device will NACK threshold values that are less than zero (i.e.negative.)", + /* .docs = */ "Zero Angular Rate Update\nThe ZUPT is triggered when the scalar magnitude of the angular rate vector is equal-to or less than the threshold value.\nThe device will NACK threshold values that are less than zero (i.e.negative.)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1703,7 +1703,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagCaptureAutoCal", /* .title = */ "Magnetometer Capture Auto Calibration", - /* .docs = */ "This command captures the current value of the auto-calibration, applies it to the current fixed hard and soft iron calibration coefficients, and replaces the current fixed hard and soft iron calibration coefficients with the new values.nThis may be used in place of (or in addition to) a manual hard and soft iron calibration utility. This command also resets the auto-calibration coefficients.nFunction selector SAVE is the same as issuing the 0x0C, 0x3A and 0x0C, 0x3B commands with the SAVE function selector.", + /* .docs = */ "This command captures the current value of the auto-calibration, applies it to the current fixed hard and soft iron calibration coefficients, and replaces the current fixed hard and soft iron calibration coefficients with the new values.\nThis may be used in place of (or in addition to) a manual hard and soft iron calibration utility. This command also resets the auto-calibration coefficients.\nFunction selector SAVE is the same as issuing the 0x0C, 0x3A and 0x0C, 0x3B commands with the SAVE function selector.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, false, true, false, false, true}, @@ -1762,7 +1762,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GravityNoise", /* .title = */ "Gravity Noise Standard Deviation", - /* .docs = */ "Set the expected gravity noise 1-sigma values. This function can be used to tune the filter performance in the target application.nnNote: Noise values must be greater than 0.0nnThe noise value represents process noise in the Estimation Filter. Changing this value modifies how the filter responds to dynamic input and can be used to tune filter performance.nDefault values provide good performance for most laboratory conditions.", + /* .docs = */ "Set the expected gravity noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nNote: Noise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter. Changing this value modifies how the filter responds to dynamic input and can be used to tune filter performance.\nDefault values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1821,7 +1821,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::PressureAltitudeNoise", /* .title = */ "Pressure Altitude Noise Standard Deviation", - /* .docs = */ "Set the expected pressure altitude noise 1-sigma values. This function can be used to tune the filter performance in the target application.nnThe noise value must be greater than 0.0nnThis noise value represents pressure altitude model noise in the Estimation Filter.nA lower value will increase responsiveness of the sensor to pressure changes, however height estimates will be more susceptible to error from air pressure fluctuations not due to changes in altitude. Default values provide good performance for most laboratory conditions.", + /* .docs = */ "Set the expected pressure altitude noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nThe noise value must be greater than 0.0\n\nThis noise value represents pressure altitude model noise in the Estimation Filter.\nA lower value will increase responsiveness of the sensor to pressure changes, however height estimates will be more susceptible to error from air pressure fluctuations not due to changes in altitude. Default values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1880,7 +1880,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::HardIronOffsetNoise", /* .title = */ "Hard Iron Offset Process Noise", - /* .docs = */ "Set the expected hard iron offset noise 1-sigma values. This function can be used to tune the filter performance in the target application.nnThis function can be used to tune the filter performance in the target application.nnNoise values must be greater than 0.0nnThe noise values represent process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", + /* .docs = */ "Set the expected hard iron offset noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0\n\nThe noise values represent process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1939,7 +1939,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SoftIronMatrixNoise", /* .title = */ "Soft Iron Offset Process Noise", - /* .docs = */ "Set the expected soft iron matrix noise 1-sigma values.nThis function can be used to tune the filter performance in the target application.nnNoise values must be greater than 0.0nnThe noise value represents process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", + /* .docs = */ "Set the expected soft iron matrix noise 1-sigma values.\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -1998,7 +1998,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagNoise", /* .title = */ "Magnetometer Noise Standard Deviation", - /* .docs = */ "Set the expected magnetometer noise 1-sigma values.nThis function can be used to tune the filter performance in the target application.nnNoise values must be greater than 0.0 (gauss)nnThe noise value represents process noise in the Estimation Filter.nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions", + /* .docs = */ "Set the expected magnetometer noise 1-sigma values.\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0 (gauss)\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2095,7 +2095,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::InclinationSource", /* .title = */ "Inclination Source", - /* .docs = */ "Set/Get the local magnetic field inclination angle source.nnThis can be used to correct for the local value of inclination (dip angle) of the earthmagnetic field.nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.n", + /* .docs = */ "Set/Get the local magnetic field inclination angle source.\n\nThis can be used to correct for the local value of inclination (dip angle) of the earthmagnetic field.\nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2172,7 +2172,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagneticDeclinationSource", /* .title = */ "Magnetic Field Declination Source Control", - /* .docs = */ "Set/Get the local magnetic field declination angle source.nnThis can be used to correct for the local value of declination of the earthmagnetic field.nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.n", + /* .docs = */ "Set/Get the local magnetic field declination angle source.\n\nThis can be used to correct for the local value of declination of the earthmagnetic field.\nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2249,7 +2249,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagFieldMagnitudeSource", /* .title = */ "Magnetic Field Magnitude Source", - /* .docs = */ "Set/Get the local magnetic field magnitude source.nnThis is used to specify the local magnitude of the earth's magnetic field.nHaving a correct value for magnitude is important for best performance of the auto-mag calibration feature and for the magnetometer adaptive magnitude. If you do not have an accurate value for the local magnetic field magnitude, it is recommended that you leave the auto-mag calibration feature off.", + /* .docs = */ "Set/Get the local magnetic field magnitude source.\n\nThis is used to specify the local magnitude of the earth's magnetic field.\nHaving a correct value for magnitude is important for best performance of the auto-mag calibration feature and for the magnetometer adaptive magnitude. If you do not have an accurate value for the local magnetic field magnitude, it is recommended that you leave the auto-mag calibration feature off.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2362,7 +2362,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::ReferencePosition", /* .title = */ "Set Reference Position", - /* .docs = */ "Set the Lat/Long/Alt reference position for the sensor.nnThis position is used by the sensor to calculate the WGS84 gravity and WMM2015 magnetic field parameters.n", + /* .docs = */ "Set the Lat/Long/Alt reference position for the sensor.\n\nThis position is used by the sensor to calculate the WGS84 gravity and WMM2015 magnetic field parameters.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2549,7 +2549,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AccelMagnitudeErrorAdaptiveMeasurement", /* .title = */ "Gravity Magnitude Error Adaptive Measurement", - /* .docs = */ "Enable or disable the gravity magnitude error adaptive measurement.nThis function can be used to tune the filter performance in the target applicationnnPick values that give you the least occurrence of invalid EF attitude output.nThe default values are good for standard low dynamics applications.nIncrease values for higher dynamic conditions, lower values for lower dynamic.nToo low a value will result in excessive heading errors.nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.nnAdaptive measurements can be enabled/disabled without the need for providing the additional parameters.nIn this case, only the function selector and enable value are required; all other parameters will remain at their previous values.nWhen auto-adaptive is selected, the filter and limit parameters are ignored.nInstead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality.n", + /* .docs = */ "Enable or disable the gravity magnitude error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nAdaptive measurements can be enabled/disabled without the need for providing the additional parameters.\nIn this case, only the function selector and enable value are required; all other parameters will remain at their previous values.\nWhen auto-adaptive is selected, the filter and limit parameters are ignored.\nInstead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2716,7 +2716,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagMagnitudeErrorAdaptiveMeasurement", /* .title = */ "Magnetometer Magnitude Error Adaptive Measurement", - /* .docs = */ "Enable or disable the magnetometer magnitude error adaptive measurement.nThis feature will reject magnetometer readings that are out of range of the thresholds specified (fixed adaptive) or calculated internally (auto-adaptive).nnPick values that give you the least occurrence of invalid EF attitude output.nThe default values are good for standard low dynamics applications.nIncrease values for higher dynamic conditions, lower values for lower dynamic.nToo low a value will result in excessive heading errors.nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.n", + /* .docs = */ "Enable or disable the magnetometer magnitude error adaptive measurement.\nThis feature will reject magnetometer readings that are out of range of the thresholds specified (fixed adaptive) or calculated internally (auto-adaptive).\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2847,7 +2847,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagDipAngleErrorAdaptiveMeasurement", /* .title = */ "Magnetometer Dig Angle Error Adaptive Measurement", - /* .docs = */ "Enable or disable the magnetometer dip angle error adaptive measurement.nThis function can be used to tune the filter performance in the target applicationnnPick values that give you the least occurrence of invalid EF attitude output.nThe default values are good for standard low dynamics applications.nIncrease values for higher dynamic conditions, lower values for lower dynamic.nToo low a value will result in excessive heading errors.nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.nnThe magnetometer dip angle adaptive measurement is ignored if the auto-adaptive magnetometer magnitude or auto-adaptive accel magnitude options are selected.n", + /* .docs = */ "Enable or disable the magnetometer dip angle error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nThe magnetometer dip angle adaptive measurement is ignored if the auto-adaptive magnetometer magnitude or auto-adaptive accel magnitude options are selected.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2951,7 +2951,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AidingMeasurementEnable", /* .title = */ "Aiding Measurement Control", - /* .docs = */ "Enables / disables the specified aiding measurement source.nn", + /* .docs = */ "Enables / disables the specified aiding measurement source.\n\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2968,7 +2968,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::Run", /* .title = */ "Run Navigation Filter", - /* .docs = */ "Manual run command.nnIf the initialization configuration has the 'wait_for_run_command' option enabled, the filter will wait until it receives this command before commencing integration and enabling the Kalman filter. Prior to the receipt of this command, the filter will remain in the filter initialization mode.", + /* .docs = */ "Manual run command.\n\nIf the initialization configuration has the 'wait_for_run_command' option enabled, the filter will wait until it receives this command before commencing integration and enabling the Kalman filter. Prior to the receipt of this command, the filter will remain in the filter initialization mode.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2985,7 +2985,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "acceleration_constraint_selection", - /* .docs = */ "Acceleration constraint:
n0=None (default),
n1=Zero-acceleration.", + /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2994,7 +2994,7 @@ struct MetadataFor }, { /* .name = */ "velocity_constraint_selection", - /* .docs = */ "0=None (default),
n1=Zero-velocity,
n2=Wheeled-vehicle.
", + /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3003,7 +3003,7 @@ struct MetadataFor }, { /* .name = */ "angular_constraint_selection", - /* .docs = */ "0=None (default),n1=Zero-angular rate (ZUPT).", + /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3033,7 +3033,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "acceleration_constraint_selection", - /* .docs = */ "Acceleration constraint:
n0=None (default),
n1=Zero-acceleration.", + /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3042,7 +3042,7 @@ struct MetadataFor }, { /* .name = */ "velocity_constraint_selection", - /* .docs = */ "0=None (default),
n1=Zero-velocity,
n2=Wheeled-vehicle.
", + /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3051,7 +3051,7 @@ struct MetadataFor }, { /* .name = */ "angular_constraint_selection", - /* .docs = */ "0=None (default),n1=Zero-angular rate (ZUPT).", + /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3063,7 +3063,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::KinematicConstraint", /* .title = */ "Kinematic Constraint Control", - /* .docs = */ "Controls kinematic constraint model selection for the navigation filter.nnSee manual for explanation of how the kinematic constraints are applied.", + /* .docs = */ "Controls kinematic constraint model selection for the navigation filter.\n\nSee manual for explanation of how the kinematic constraints are applied.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3327,7 +3327,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::InitializationConfiguration", /* .title = */ "Navigation Filter Initialization", - /* .docs = */ "Controls the source and values used for initial conditions of the navigation solution.nnNotes: Initial conditions are the position, velocity, and attitude of the platform used when the filter starts running or is reset.nFor the user specified position array, the units are meters if the ECEF frame is selected, and degrees latitude, degrees longitude, and meters above ellipsoid if the latitude/longitude/height frame is selected.nFor the user specified velocity array, the units are meters per second, but the reference frame depends on the reference frame selector (ECEF or NED).", + /* .docs = */ "Controls the source and values used for initial conditions of the navigation solution.\n\nNotes: Initial conditions are the position, velocity, and attitude of the platform used when the filter starts running or is reset.\nFor the user specified position array, the units are meters if the ECEF frame is selected, and degrees latitude, degrees longitude, and meters above ellipsoid if the latitude/longitude/height frame is selected.\nFor the user specified velocity array, the units are meters per second, but the reference frame depends on the reference frame selector (ECEF or NED).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3344,7 +3344,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "level", - /* .docs = */ "Auto-adaptive operating level:
n0=Off,
n1=Conservative,
n2=Moderate (default),
n3=Aggressive.", + /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3383,7 +3383,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "level", - /* .docs = */ "Auto-adaptive operating level:
n0=Off,
n1=Conservative,
n2=Moderate (default),
n3=Aggressive.", + /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3481,7 +3481,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MultiAntennaOffset", /* .title = */ "GNSS Multi-Antenna Offset Control", - /* .docs = */ "Set the antenna lever arm.nnThis command works with devices that utilize multiple antennas.n

Offset Limit: 10 m magnitude (default)", + /* .docs = */ "Set the antenna lever arm.\n\nThis command works with devices that utilize multiple antennas.\n

Offset Limit: 10 m magnitude (default)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3671,7 +3671,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::RefPointLeverArm", /* .title = */ "Reference point lever arm", - /* .docs = */ "Lever arm offset with respect to the sensor for the indicated point of reference.nThis is used to change the location of the indicated point of reference, and will affect filter position and velocity outputs.nChanging this setting from default will result in a global position offset that depends on vehicle attitude,nand a velocity offset that depends on vehicle attitude and angular rate.n
The lever arm is defined by a 3-element vector that points from the sensor to the desired reference point, with (x,y,z) components given in the vehicle's reference frame.n

Note, if the reference point selector is set to VEH (1), this setting will affect the following data fields: (0x82, 0x01), (0x82, 0x02), (0x82, 0x40), (0x82, 0x41), and (0x82, 42)n

Offset Limitsn
Reference Point VEH (1): 10 m magnitude (default)", + /* .docs = */ "Lever arm offset with respect to the sensor for the indicated point of reference.\nThis is used to change the location of the indicated point of reference, and will affect filter position and velocity outputs.\nChanging this setting from default will result in a global position offset that depends on vehicle attitude,\nand a velocity offset that depends on vehicle attitude and angular rate.\n
The lever arm is defined by a 3-element vector that points from the sensor to the desired reference point, with (x,y,z) components given in the vehicle's reference frame.\n

Note, if the reference point selector is set to VEH (1), this setting will affect the following data fields: (0x82, 0x01), (0x82, 0x02), (0x82, 0x40), (0x82, 0x41), and (0x82, 42)\n

Offset Limits\n
Reference Point VEH (1): 10 m magnitude (default)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3727,7 +3727,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SpeedMeasurement", /* .title = */ "Input speed measurement", - /* .docs = */ "Speed aiding measurement, where speed is defined as rate of motion along the vehicle's x-axis direction.nCan be used by an external odometer/speedometer, for example.nThis command cannot be used if the internal odometer is configured.", + /* .docs = */ "Speed aiding measurement, where speed is defined as rate of motion along the vehicle's x-axis direction.\nCan be used by an external odometer/speedometer, for example.\nThis command cannot be used if the internal odometer is configured.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -3804,7 +3804,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SpeedLeverArm", /* .title = */ "Measurement speed lever arm", - /* .docs = */ "Lever arm offset for speed measurements.nThis is used to compensate for an off-center measurement pointnhaving a different speed due to rotation of the vehicle.nThe typical use case for this would be an odometer attached to a wheelnon a standard 4-wheeled vehicle. If the odometer is on the left wheel,nit will report higher speed on right turns and lower speed on left turns.nThis is because the outside edge of the curve is longer than the inside edge.", + /* .docs = */ "Lever arm offset for speed measurements.\nThis is used to compensate for an off-center measurement point\nhaving a different speed due to rotation of the vehicle.\nThe typical use case for this would be an odometer attached to a wheel\non a standard 4-wheeled vehicle. If the odometer is on the left wheel,\nit will report higher speed on right turns and lower speed on left turns.\nThis is because the outside edge of the curve is longer than the inside edge.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3863,7 +3863,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::WheeledVehicleConstraintControl", /* .title = */ "Wheeled Vehicle Constraint Control", - /* .docs = */ "Configure the wheeled vehicle kinematic constraint.nnWhen enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis.nBy convention, the primary vehicle axis is the vehicle X-axis (note: the sensor may be physically installed innany orientation on the vehicle if the appropriate mounting transformation has been specified).nThis constraint will typically improve heading estimates for vehicles where the assumption is valid, suchnas an automobile, particularly when GNSS coverage is intermittent.", + /* .docs = */ "Configure the wheeled vehicle kinematic constraint.\n\nWhen enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis.\nBy convention, the primary vehicle axis is the vehicle X-axis (note: the sensor may be physically installed in\nany orientation on the vehicle if the appropriate mounting transformation has been specified).\nThis constraint will typically improve heading estimates for vehicles where the assumption is valid, such\nas an automobile, particularly when GNSS coverage is intermittent.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3922,7 +3922,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::VerticalGyroConstraintControl", /* .title = */ "Vertical Gyro Constraint Control", - /* .docs = */ "Configure the vertical gyro kinematic constraint.nnWhen enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track pitchnand roll under the assumption that the sensor platform is not undergoing linear acceleration.nThis constraint is useful to maintain accurate pitch and roll during GNSS signal outages.", + /* .docs = */ "Configure the vertical gyro kinematic constraint.\n\nWhen enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track pitch\nand roll under the assumption that the sensor platform is not undergoing linear acceleration.\nThis constraint is useful to maintain accurate pitch and roll during GNSS signal outages.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3999,7 +3999,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GnssAntennaCalControl", /* .title = */ "GNSS Antenna Offset Calibration Control", - /* .docs = */ "Configure the GNSS antenna lever arm calibration.nnWhen enabled, the filter will enable lever arm error tracking, up to the maximum offset specified.", + /* .docs = */ "Configure the GNSS antenna lever arm calibration.\n\nWhen enabled, the filter will enable lever arm error tracking, up to the maximum offset specified.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -4028,7 +4028,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SetInitialHeading", /* .title = */ "Set Initial Heading Control", - /* .docs = */ "Set the initial heading angle.nnThe estimation filter will reset the heading estimate to provided value. If the product supports magnetometer aiding and this feature has been enabled, the headingnargument will be ignored and the filter will initialize using the inferred magnetic heading.", + /* .docs = */ "Set the initial heading angle.\n\nThe estimation filter will reset the heading estimate to provided value. If the product supports magnetometer aiding and this feature has been enabled, the heading\nargument will be ignored and the filter will initialize using the inferred magnetic heading.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/commands_gnss.hpp b/src/cpp/mip/metadata/definitions/commands_gnss.hpp index 2790fd045..dbfdecfba 100644 --- a/src/cpp/mip/metadata/definitions/commands_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/commands_gnss.hpp @@ -36,7 +36,7 @@ struct MetadataFor }, { /* .name = */ "description", - /* .docs = */ "Ascii description of receiver. Contains the following info (comma-delimited):
nModule name/model
nFirmware version info", + /* .docs = */ "Ascii description of receiver. Contains the following info (comma-delimited):
\nModule name/model
\nFirmware version info", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, /* .functions = */ NO_FUNCTIONS, @@ -99,7 +99,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::ReceiverInfo", /* .title = */ "None", - /* .docs = */ "Return information about the GNSS receivers in the device.n", + /* .docs = */ "Return information about the GNSS receivers in the device.\n", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -230,7 +230,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::SignalConfiguration", /* .title = */ "None", - /* .docs = */ "Configure the GNSS signals used by the device.n", + /* .docs = */ "Configure the GNSS signals used by the device.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -307,7 +307,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::RtkDongleConfiguration", /* .title = */ "None", - /* .docs = */ "Configure the communications with the RTK Dongle connected to the device.n", + /* .docs = */ "Configure the communications with the RTK Dongle connected to the device.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, diff --git a/src/cpp/mip/metadata/definitions/commands_rtk.hpp b/src/cpp/mip/metadata/definitions/commands_rtk.hpp index 21750f015..eddf293a5 100644 --- a/src/cpp/mip/metadata/definitions/commands_rtk.hpp +++ b/src/cpp/mip/metadata/definitions/commands_rtk.hpp @@ -638,7 +638,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::ProdEraseStorage", /* .title = */ "None", - /* .docs = */ "This command will erase the selected media to a raw and uninitialized state. ALL DATA WILL BE LOST.nThis command is only available in calibration mode.", + /* .docs = */ "This command will erase the selected media to a raw and uninitialized state. ALL DATA WILL BE LOST.\nThis command is only available in calibration mode.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -731,7 +731,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::ModemHardReset", /* .title = */ "None", - /* .docs = */ "This command will clear the modem flash. THIS MUST NOT BE DONE OFTEN AS IT CAN DAMAGE THE FLASH!nThis command is only available in calibration mode.", + /* .docs = */ "This command will clear the modem flash. THIS MUST NOT BE DONE OFTEN AS IT CAN DAMAGE THE FLASH!\nThis command is only available in calibration mode.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/commands_system.hpp b/src/cpp/mip/metadata/definitions/commands_system.hpp index 0154590a0..2a9f7adcf 100644 --- a/src/cpp/mip/metadata/definitions/commands_system.hpp +++ b/src/cpp/mip/metadata/definitions/commands_system.hpp @@ -60,7 +60,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_system::CommMode", /* .title = */ "None", - /* .docs = */ "Advanced specialized communication modes.nnThis command allows the user to communicate directly with various subsystems which may be present in MIP devices (i.e. IMU, GNSS, etc.)nPlease see the specific device's user manual for possible modes.nnThis command responds with an ACK/NACK just prior to switching to the new protocol.nFor all functions except 0x01 (use new settings), the new communications mode value is ignored.nn", + /* .docs = */ "Advanced specialized communication modes.\n\nThis command allows the user to communicate directly with various subsystems which may be present in MIP devices (i.e. IMU, GNSS, etc.)\nPlease see the specific device's user manual for possible modes.\n\nThis command responds with an ACK/NACK just prior to switching to the new protocol.\nFor all functions except 0x01 (use new settings), the new communications mode value is ignored.\n\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, false, false, true, true}, diff --git a/src/cpp/mip/metadata/definitions/data_filter.hpp b/src/cpp/mip/metadata/definitions/data_filter.hpp index d0156c156..f50c4e187 100644 --- a/src/cpp/mip/metadata/definitions/data_filter.hpp +++ b/src/cpp/mip/metadata/definitions/data_filter.hpp @@ -151,7 +151,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AttitudeQuaternion", /* .title = */ "None", - /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.nThis quaternion satisfies the following relationship:nnEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
nnWhere:
nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", + /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.\nThis quaternion satisfies the following relationship:\n\nEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
\nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -189,7 +189,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AttitudeDcm", /* .title = */ "None", - /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.nThis matrix satisfies the following relationship:nnEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
nnWhere:
nnEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
n
nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} end{bmatrix} EQEND", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -245,7 +245,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::EulerAngles", /* .title = */ "None", - /* .docs = */ "Filter reported Euler angles describing the orientation of the device with respect to the NED local-level frame.nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", + /* .docs = */ "Filter reported Euler angles describing the orientation of the device with respect to the NED local-level frame.\nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -489,7 +489,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::EulerAnglesUncertainty", /* .title = */ "None", - /* .docs = */ "Filter reported 1-sigma Euler angle uncertainties.nThe uncertainties are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", + /* .docs = */ "Filter reported 1-sigma Euler angle uncertainties.\nThe uncertainties are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -612,7 +612,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::Timestamp", /* .title = */ "None", - /* .docs = */ "GPS timestamp of the Filter datannShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.nnNote: this data field may be deprecated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead.", + /* .docs = */ "GPS timestamp of the Filter data\n\nShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.\nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.\nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.\n\nNote: this data field may be deprecated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -788,7 +788,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::LinearAccel", /* .title = */ "None", - /* .docs = */ "Filter-compensated linear acceleration expressed in the vehicle frame.nNote: The estimated gravity has been removed from this data leaving only linear acceleration.", + /* .docs = */ "Filter-compensated linear acceleration expressed in the vehicle frame.\nNote: The estimated gravity has been removed from this data leaving only linear acceleration.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1056,7 +1056,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::HeadingUpdateState", /* .title = */ "None", - /* .docs = */ "Filter reported heading update state.nnHeading updates can be applied from the sources listed below. Note, some of these sources may be combined.nThe heading value is always relative to true north.", + /* .docs = */ "Filter reported heading update state.\n\nHeading updates can be applied from the sources listed below. Note, some of these sources may be combined.\nThe heading value is always relative to true north.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1130,7 +1130,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagneticModel", /* .title = */ "None", - /* .docs = */ "The World Magnetic Model is used for this data. Please refer to the device user manual for the current version of the model.nA valid GNSS location is required for the model to be valid.", + /* .docs = */ "The World Magnetic Model is used for this data. Please refer to the device user manual for the current version of the model.\nA valid GNSS location is required for the model to be valid.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1432,7 +1432,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::StandardAtmosphere", /* .title = */ "None", - /* .docs = */ "Filter reported standard atmosphere parameters.nnThe US 1976 Standard Atmosphere Model is used. A valid GNSS location is required for the model to be valid.", + /* .docs = */ "Filter reported standard atmosphere parameters.\n\nThe US 1976 Standard Atmosphere Model is used. A valid GNSS location is required for the model to be valid.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1470,7 +1470,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::PressureAltitude", /* .title = */ "None", - /* .docs = */ "Filter reported pressure altitude.nnThe US 1976 Standard Atmosphere Model is used to calculate the pressure altitude in meters.nA valid pressure sensor reading is required for the pressure altitude to be valid.nThe minimum pressure reading supported by the model is 0.0037 mBar, corresponding to an altitude of 84,852 meters.", + /* .docs = */ "Filter reported pressure altitude.\n\nThe US 1976 Standard Atmosphere Model is used to calculate the pressure altitude in meters.\nA valid pressure sensor reading is required for the pressure altitude to be valid.\nThe minimum pressure reading supported by the model is 0.0037 mBar, corresponding to an altitude of 84,852 meters.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1546,7 +1546,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AntennaOffsetCorrection", /* .title = */ "None", - /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.nnThis offset added to any previously stored offset vector to compensate for errors in definition.", + /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.\n\nThis offset added to any previously stored offset vector to compensate for errors in definition.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1631,7 +1631,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MultiAntennaOffsetCorrection", /* .title = */ "None", - /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.nnThis offset added to any previously stored offset vector to compensate for errors in definition.", + /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.\n\nThis offset added to any previously stored offset vector to compensate for errors in definition.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1716,7 +1716,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerOffset", /* .title = */ "None", - /* .docs = */ "Filter reported magnetometer hard iron offset in sensor frame.nnThis offset added to any previously stored hard iron offset vector to compensate for magnetometer in-run bias errors.", + /* .docs = */ "Filter reported magnetometer hard iron offset in sensor frame.\n\nThis offset added to any previously stored hard iron offset vector to compensate for magnetometer in-run bias errors.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1754,7 +1754,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerMatrix", /* .title = */ "None", - /* .docs = */ "Filter reported magnetometer soft iron matrix in sensor frame.nnThis matrix is post multiplied to any previously stored soft iron matrix to compensate for magnetometer in-run errors.", + /* .docs = */ "Filter reported magnetometer soft iron matrix in sensor frame.\n\nThis matrix is post multiplied to any previously stored soft iron matrix to compensate for magnetometer in-run errors.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2758,7 +2758,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AidingFrameConfigError", /* .title = */ "Aiding Frame Configuration Error", - /* .docs = */ "Filter reported aiding source frame configuration errornnThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", + /* .docs = */ "Filter reported aiding source frame configuration error\n\nThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2805,7 +2805,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AidingFrameConfigErrorUncertainty", /* .title = */ "Aiding Frame Configuration Error Uncertainty", - /* .docs = */ "Filter reported aiding source frame configuration error uncertaintynnThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", + /* .docs = */ "Filter reported aiding source frame configuration error uncertainty\n\nThese estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/data_gnss.hpp b/src/cpp/mip/metadata/definitions/data_gnss.hpp index e977c3ed3..5b9d66848 100644 --- a/src/cpp/mip/metadata/definitions/data_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/data_gnss.hpp @@ -968,7 +968,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::SvInfo", /* .title = */ "None", - /* .docs = */ "GNSS reported space vehicle informationnnWhen enabled, these fields will arrive in separate MIP packets", + /* .docs = */ "GNSS reported space vehicle information\n\nWhen enabled, these fields will arrive in separate MIP packets", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1194,7 +1194,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::DgpsInfo", /* .title = */ "None", - /* .docs = */ "GNSS reported DGNSS statusnn
Possible Base Station Status Values:
n
  0 - UDRE Scale Factor = 1.0
n
  1 - UDRE Scale Factor = 0.75
n
  2 - UDRE Scale Factor = 0.5
n
  3 - UDRE Scale Factor = 0.3
n
  4 - UDRE Scale Factor = 0.2
n
  5 - UDRE Scale Factor = 0.1
n
  6 - Reference Station Transmission Not Monitored
n
  7 - Reference Station Not Working
nn(UDRE = User Differential Range Error)", + /* .docs = */ "GNSS reported DGNSS status\n\n
Possible Base Station Status Values:
\n
  0 - UDRE Scale Factor = 1.0
\n
  1 - UDRE Scale Factor = 0.75
\n
  2 - UDRE Scale Factor = 0.5
\n
  3 - UDRE Scale Factor = 0.3
\n
  4 - UDRE Scale Factor = 0.2
\n
  5 - UDRE Scale Factor = 0.1
\n
  6 - Reference Station Transmission Not Monitored
\n
  7 - Reference Station Not Working
\n\n(UDRE = User Differential Range Error)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1281,7 +1281,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::DgpsChannel", /* .title = */ "None", - /* .docs = */ "GNSS reported DGPS Channel Status statusnnWhen enabled, a separate field for each active space vehicle will be sent in the packet.", + /* .docs = */ "GNSS reported DGPS Channel Status status\n\nWhen enabled, a separate field for each active space vehicle will be sent in the packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1368,7 +1368,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::ClockInfo2", /* .title = */ "None", - /* .docs = */ "GNSS reported receiver clock parametersnnThis supersedes MIP_DATA_DESC_GNSS_CLOCK_INFO with additional information.", + /* .docs = */ "GNSS reported receiver clock parameters\n\nThis supersedes MIP_DATA_DESC_GNSS_CLOCK_INFO with additional information.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -1728,7 +1728,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::SbasCorrection", /* .title = */ "None", - /* .docs = */ "GNSS calculated SBAS CorrectionnnUDREI - the variance of a normal distribution associated with the user differential range errors for ansatellite after application of fast and long-term corrections, excluding atmospheric effectsnn
UDREI  Variance
n
-----------------------
n
0      0.0520 m^2
n
1      0.0924 m^2
n
2      0.1444 m^2
n
3      0.2830 m^2
n
4      0.4678 m^2
n
5      0.8315 m^2
n
6      1.2992 m^2
n
7      1.8709 m^2
n
8      2.5465 m^2
n
9      3.3260 m^2
n
10     5.1968 m^2
n
11     20.7870 m^2
n
12     230.9661 m^2
n
13     2078.695 m^2
n
14     'Not Monitored'
n
15     'Do Not Use'
", + /* .docs = */ "GNSS calculated SBAS Correction\n\nUDREI - the variance of a normal distribution associated with the user differential range errors for a\nsatellite after application of fast and long-term corrections, excluding atmospheric effects\n\n
UDREI  Variance
\n
-----------------------
\n
0      0.0520 m^2
\n
1      0.0924 m^2
\n
2      0.1444 m^2
\n
3      0.2830 m^2
\n
4      0.4678 m^2
\n
5      0.8315 m^2
\n
6      1.2992 m^2
\n
7      1.8709 m^2
\n
8      2.5465 m^2
\n
9      3.3260 m^2
\n
10     5.1968 m^2
\n
11     20.7870 m^2
\n
12     230.9661 m^2
\n
13     2078.695 m^2
\n
14     'Not Monitored'
\n
15     'Do Not Use'
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2010,7 +2010,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::BaseStationInfo", /* .title = */ "None", - /* .docs = */ "RTCM reported base station information (sourced from RTCM Message 1005 or 1006)nnValid Flag Mapping:", + /* .docs = */ "RTCM reported base station information (sourced from RTCM Message 1005 or 1006)\n\nValid Flag Mapping:", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2616,7 +2616,7 @@ struct MetadataFor }, { /* .name = */ "lock_time", - /* .docs = */ "DOCnMinimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver.", + /* .docs = */ "DOC\nMinimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -2728,7 +2728,7 @@ struct MetadataFor }, { /* .name = */ "iodc", - /* .docs = */ "Issue of Data Clock. This increments each time the data changes andnrolls over at 4. It is used to make sure various raw data elements fromndifferent sources line up correctly.", + /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -3074,7 +3074,7 @@ struct MetadataFor }, { /* .name = */ "iodc", - /* .docs = */ "Issue of Data Clock. This increments each time the data changes andnrolls over at 4. It is used to make sure various raw data elements fromndifferent sources line up correctly.", + /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index ec37446ac..727311874 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -30,7 +30,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawAccel", /* .title = */ "None", - /* .docs = */ "Three element vector representing the sensed acceleration.nThis quantity is temperature compensated and expressed in the sensor body frame.", + /* .docs = */ "Three element vector representing the sensed acceleration.\nThis quantity is temperature compensated and expressed in the sensor body frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -59,7 +59,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawGyro", /* .title = */ "None", - /* .docs = */ "Three element vector representing the sensed angular rate.nThis quantity is temperature compensated and expressed in the sensor body frame.", + /* .docs = */ "Three element vector representing the sensed angular rate.\nThis quantity is temperature compensated and expressed in the sensor body frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -88,7 +88,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawMag", /* .title = */ "None", - /* .docs = */ "Three element vector representing the sensed magnetic field.nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .docs = */ "Three element vector representing the sensed magnetic field.\nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -117,7 +117,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawPressure", /* .title = */ "None", - /* .docs = */ "Scalar value representing the sensed ambient pressure.nThis quantity is temperature compensated.", + /* .docs = */ "Scalar value representing the sensed ambient pressure.\nThis quantity is temperature compensated.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -146,7 +146,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledAccel", /* .title = */ "None", - /* .docs = */ "3-element vector representing the sensed acceleration.nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the sensed acceleration.\nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -175,7 +175,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledGyro", /* .title = */ "None", - /* .docs = */ "3-element vector representing the sensed angular rate.nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the sensed angular rate.\nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -204,7 +204,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledMag", /* .title = */ "None", - /* .docs = */ "3-element vector representing the sensed magnetic field.nThis quantity is temperature compensated and expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the sensed magnetic field.\nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -262,7 +262,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::DeltaTheta", /* .title = */ "None", - /* .docs = */ "3-element vector representing the time integral of angular rate.nThis quantity is the integral of sensed angular rate over the period set by the IMU message format. It is expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the time integral of angular rate.\nThis quantity is the integral of sensed angular rate over the period set by the IMU message format. It is expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -291,7 +291,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::DeltaVelocity", /* .title = */ "None", - /* .docs = */ "3-element vector representing the time integral of acceleration.nThis quantity is the integral of sensed acceleration over the period set by the IMU message format. It is expressed in the vehicle frame.", + /* .docs = */ "3-element vector representing the time integral of acceleration.\nThis quantity is the integral of sensed acceleration over the period set by the IMU message format. It is expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -320,7 +320,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::CompOrientationMatrix", /* .title = */ "Complementary Filter Orientation Matrix", - /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.nThis matrix satisfies the following relationship:nnEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
nnWhere:
nnEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
n
nThe matrix elements are stored is row-major order: EQSTART M = begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} end{bmatrix} EQEND", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -349,7 +349,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::CompQuaternion", /* .title = */ "Complementary Filter Quaternion", - /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.nThis quaternion satisfies the following relationship:nnEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
nnWhere:
nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", + /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.\nThis quaternion satisfies the following relationship:\n\nEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
\nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -396,7 +396,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::CompEulerAngles", /* .title = */ "Complementary Filter Euler Angles", - /* .docs = */ "Euler angles describing the orientation of the device with respect to the NED local-level frame.nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", + /* .docs = */ "Euler angles describing the orientation of the device with respect to the NED local-level frame.\nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -590,7 +590,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::GpsTimestamp", /* .title = */ "None", - /* .docs = */ "GPS timestamp of the SENSOR datannShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.nnNote: this data field may be deprecated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead.", + /* .docs = */ "GPS timestamp of the SENSOR data\n\nShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.\nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.\nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.\n\nNote: this data field may be deprecated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -637,7 +637,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::TemperatureAbs", /* .title = */ "Temperature Statistics", - /* .docs = */ "SENSOR reported temperature statisticsnnTemperature may originate from the MEMS sensors, or be calculated in combination with board temperature sensors.nAll quantities are calculated with respect to the last power on or reset, whichever is later.n", + /* .docs = */ "SENSOR reported temperature statistics\n\nTemperature may originate from the MEMS sensors, or be calculated in combination with board temperature sensors.\nAll quantities are calculated with respect to the last power on or reset, whichever is later.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -666,7 +666,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::UpVector", /* .title = */ "None", - /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimated vertical direction.nThis quantity is expressed in the vehicle frame.nnThis quantity is sensitive to non-gravitational accelerations, which may cause notable deviations from the true vertical direction.nnFor legacy reasons, this vector is the inverse of the gravity vector.n", + /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimated vertical direction.\nThis quantity is expressed in the vehicle frame.\n\nThis quantity is sensitive to non-gravitational accelerations, which may cause notable deviations from the true vertical direction.\n\nFor legacy reasons, this vector is the inverse of the gravity vector.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -695,7 +695,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::NorthVector", /* .title = */ "None", - /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimate of magnetic north.nThis quantity is expressed in the vehicle frame.nnThis quantity is sensitive to local magnetic field perturbations, which may cause notable deviations from true magnetic north.", + /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimate of magnetic north.\nThis quantity is expressed in the vehicle frame.\n\nThis quantity is sensitive to local magnetic field perturbations, which may cause notable deviations from true magnetic north.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/data_shared.hpp b/src/cpp/mip/metadata/definitions/data_shared.hpp index 3719eec0e..24409e893 100644 --- a/src/cpp/mip/metadata/definitions/data_shared.hpp +++ b/src/cpp/mip/metadata/definitions/data_shared.hpp @@ -18,7 +18,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "trigger_id", - /* .docs = */ "Trigger ID number. If 0, this message was emitted due to beingnscheduled in the 3DM Message Format Command (0x0C,0x0F).", + /* .docs = */ "Trigger ID number. If 0, this message was emitted due to being\nscheduled in the 3DM Message Format Command (0x0C,0x0F).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -30,7 +30,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::EventSource", /* .title = */ "None", - /* .docs = */ "Identifies which event trigger caused this packet to be emitted.nnGenerally this is used to determine whether a packet was emittedndue to scheduled streaming or due to an event.", + /* .docs = */ "Identifies which event trigger caused this packet to be emitted.\n\nGenerally this is used to determine whether a packet was emitted\ndue to scheduled streaming or due to an event.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -59,7 +59,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::Ticks", /* .title = */ "None", - /* .docs = */ "Time since powerup in multiples of the base rate.nnThe counter will wrap around to 0 after approximately 50 days.nOne tick is equivalent to one base period (reciprocal of the base rate).", + /* .docs = */ "Time since powerup in multiples of the base rate.\n\nThe counter will wrap around to 0 after approximately 50 days.\nOne tick is equivalent to one base period (reciprocal of the base rate).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -88,7 +88,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::DeltaTicks", /* .title = */ "None", - /* .docs = */ "Ticks since the last output of this field.nnThis field can be used to track the amount of time passed betweennevent occurrences.nOne tick is equivalent to one base period (reciprocal of the base rate).", + /* .docs = */ "Ticks since the last output of this field.\n\nThis field can be used to track the amount of time passed between\nevent occurrences.\nOne tick is equivalent to one base period (reciprocal of the base rate).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -155,7 +155,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::GpsTimestamp", /* .title = */ "None", - /* .docs = */ "Outputs the current GPS system time in time-of-week and week number format.nnFor events, this is the time of the event trigger.nIn order to be valid, a PPS signal needs to be present, and both a valid GPS time-of-week and week number command (0x0C, 0x72) need to be received after PPS sync has been achieved.", + /* .docs = */ "Outputs the current GPS system time in time-of-week and week number format.\n\nFor events, this is the time of the event trigger.\nIn order to be valid, a PPS signal needs to be present, and both a valid GPS time-of-week and week number command (0x0C, 0x72) need to be received after PPS sync has been achieved.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -184,7 +184,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::DeltaTime", /* .title = */ "None", - /* .docs = */ "Time in the synchronized clock domain since the last output of this field within the same descriptor set and event instance.nnThis can be used to track the amount of time passed betweennevent occurrences. See the manual page on delta time quantities.nnThis field contains the same value as the delta external time field, 0xD8,nbut is expressed in seconds. Transmission of either of these fieldsnrestarts a shared counter, so only one should be streamed at a time tonavoid confusion. The counter is not shared across descriptors sets ornbetween event instances.", + /* .docs = */ "Time in the synchronized clock domain since the last output of this field within the same descriptor set and event instance.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.\n\nThis field contains the same value as the delta external time field, 0xD8,\nbut is expressed in seconds. Transmission of either of these fields\nrestarts a shared counter, so only one should be streamed at a time to\navoid confusion. The counter is not shared across descriptors sets or\nbetween event instances.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -213,7 +213,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ReferenceTimestamp", /* .title = */ "None", - /* .docs = */ "Internal reference timestamp.nnThis timestamp represents the time at which the correspondingndata was sampled, according to the internal reference clock.nnThis is a monotonic clock which never jumps. The value is always valid.nnFor events, this is the time of the event trigger.", + /* .docs = */ "Internal reference timestamp.\n\nThis timestamp represents the time at which the corresponding\ndata was sampled, according to the internal reference clock.\n\nThis is a monotonic clock which never jumps. The value is always valid.\n\nFor events, this is the time of the event trigger.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -242,7 +242,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ReferenceTimeDelta", /* .title = */ "None", - /* .docs = */ "Delta time since the last packet.nnDifference between the time as reported by the shared reference time field, 0xD5,nand the previous output of this delta quantity within the same descriptor set and event instance.nnThe delta is based on the reference time which never jumps. The valuenis always valid.nnThis can be used to track the amount of time passed betweennevent occurrences. See the manual page on delta time quantities.", + /* .docs = */ "Delta time since the last packet.\n\nDifference between the time as reported by the shared reference time field, 0xD5,\nand the previous output of this delta quantity within the same descriptor set and event instance.\n\nThe delta is based on the reference time which never jumps. The value\nis always valid.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -298,7 +298,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ExternalTimestamp", /* .title = */ "None", - /* .docs = */ "External timestamp in nanoseconds.nnThis timestamp represents the time at which the correspondingndata was sampled in the external clock domain.nEquivalent to the GPS Timestamp but in nanoseconds.nnFor events, this is the time of the event trigger.nnTo be valid, external clock sync must be achieved using the PPS input.", + /* .docs = */ "External timestamp in nanoseconds.\n\nThis timestamp represents the time at which the corresponding\ndata was sampled in the external clock domain.\nEquivalent to the GPS Timestamp but in nanoseconds.\n\nFor events, this is the time of the event trigger.\n\nTo be valid, external clock sync must be achieved using the PPS input.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -354,7 +354,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ExternalTimeDelta", /* .title = */ "None", - /* .docs = */ "Delta time since the last packet containing delta external (0xFF,0xD4) or delta gps time (0xFF,0xD8).nnDifference between the time as reported by the shared external time field, 0xD7,nand the previous output of this delta quantity within the same descriptor set and event instance.nnThis can be used to track the amount of time passed betweennevent occurrences. See the manual page on delta time quantities.nnThis field contains the same value as the delta gps time field, 0xD4,nbut is expressed in nanoseconds. Transmission of either of these fieldsnrestarts a shared counter, so only one should be streamed at a time tonavoid confusion. The counter is not shared across descriptors sets ornbetween event instances.", + /* .docs = */ "Delta time since the last packet containing delta external (0xFF,0xD4) or delta gps time (0xFF,0xD8).\n\nDifference between the time as reported by the shared external time field, 0xD7,\nand the previous output of this delta quantity within the same descriptor set and event instance.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.\n\nThis field contains the same value as the delta gps time field, 0xD4,\nbut is expressed in nanoseconds. Transmission of either of these fields\nrestarts a shared counter, so only one should be streamed at a time to\navoid confusion. The counter is not shared across descriptors sets or\nbetween event instances.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, diff --git a/src/cpp/mip/metadata/definitions/data_system.hpp b/src/cpp/mip/metadata/definitions/data_system.hpp index a8660f42c..de699bd71 100644 --- a/src/cpp/mip/metadata/definitions/data_system.hpp +++ b/src/cpp/mip/metadata/definitions/data_system.hpp @@ -18,7 +18,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "result", - /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.nBits are least-significant-byte first. For example, bit 0 isnlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],nbit 8 is located at bit 0 of result[1], and bit 127 is located at bitn7 of result[15].", + /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -30,7 +30,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::BuiltInTest", /* .title = */ "None", - /* .docs = */ "Contains the continuous built-in-test (BIT) results.nnDue to the large size of this field, it is recommended to stream it atna low rate or poll it on demand.nnThese bits are 'sticky' until the next output message. If a fault occursnin between scheduled messages or while the device is idle, the nextnpacket with this field will have the corresponding flags set. The flagnis then cleared unless the fault persists.nnUnlike the commanded BIT, some bits may be 1 in certainnnon-fault situations, so simply checking if the result is all 0s isnnot very useful. For example, on devices with a built-in GNSS receiver,na 'solution fault' bit may be set before the receiver has obtainedna position fix. Consult the device manual to determine which bits arenof interest for your application.nnAll unspecified bits are reserved for future use and must be ignored.n", + /* .docs = */ "Contains the continuous built-in-test (BIT) results.\n\nDue to the large size of this field, it is recommended to stream it at\na low rate or poll it on demand.\n\nThese bits are 'sticky' until the next output message. If a fault occurs\nin between scheduled messages or while the device is idle, the next\npacket with this field will have the corresponding flags set. The flag\nis then cleared unless the fault persists.\n\nUnlike the commanded BIT, some bits may be 1 in certain\nnon-fault situations, so simply checking if the result is all 0s is\nnot very useful. For example, on devices with a built-in GNSS receiver,\na 'solution fault' bit may be set before the receiver has obtained\na position fix. Consult the device manual to determine which bits are\nof interest for your application.\n\nAll unspecified bits are reserved for future use and must be ignored.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -47,7 +47,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "time_sync", - /* .docs = */ "True if sync with the PPS signal is currently valid. False if PPSnfeature is disabled or a PPS signal is not detected.", + /* .docs = */ "True if sync with the PPS signal is currently valid. False if PPS\nfeature is disabled or a PPS signal is not detected.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -56,7 +56,7 @@ struct MetadataFor }, { /* .name = */ "last_pps_rcvd", - /* .docs = */ "Elapsed time in seconds since last PPS was received, with a maximumnvalue of 255.", + /* .docs = */ "Elapsed time in seconds since last PPS was received, with a maximum\nvalue of 255.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -85,7 +85,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "states", - /* .docs = */ "Bitfield containing the states for each GPIO pin.
nBit 0 (0x01): pin 1
nBit 1 (0x02): pin 2
nBit 2 (0x04): pin 3
nBit 3 (0x08): pin 4
nBits for pins that don't exist will read as 0.", + /* .docs = */ "Bitfield containing the states for each GPIO pin.
\nBit 0 (0x01): pin 1
\nBit 1 (0x02): pin 2
\nBit 2 (0x04): pin 3
\nBit 3 (0x08): pin 4
\nBits for pins that don't exist will read as 0.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -97,7 +97,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::GpioState", /* .title = */ "None", - /* .docs = */ "Indicates the state of all of the user GPIO pins.nnThis message can be used to correlate external signalsnwith the device time or other data quantities. It shouldngenerally be used with slow GPIO signals as brief pulsesnshorter than the scheduled data rate will be missed.nnTo synchronize with faster signals and pulses, or for more accurate timestamping,nutilize the event system and set the GPIO feature to TIMESTAMP in the 3DM GPIOnConfiguration command (0x0C,0x41).nnThese GPIO states are sampled within one base periodnof the system data descriptor set.nnTo obtain valid readings, the desired pin(s) must be configured to the GPIO featuren(either input or output behavior) using the 3DM GPIO Configuration commandn(0x0C,0x41). Other gpio features may work on some devices but this is not guaranteed.nConsult the factory before producing a design relying on reading pins configurednto other feature types.", + /* .docs = */ "Indicates the state of all of the user GPIO pins.\n\nThis message can be used to correlate external signals\nwith the device time or other data quantities. It should\ngenerally be used with slow GPIO signals as brief pulses\nshorter than the scheduled data rate will be missed.\n\nTo synchronize with faster signals and pulses, or for more accurate timestamping,\nutilize the event system and set the GPIO feature to TIMESTAMP in the 3DM GPIO\nConfiguration command (0x0C,0x41).\n\nThese GPIO states are sampled within one base period\nof the system data descriptor set.\n\nTo obtain valid readings, the desired pin(s) must be configured to the GPIO feature\n(either input or output behavior) using the 3DM GPIO Configuration command\n(0x0C,0x41). Other gpio features may work on some devices but this is not guaranteed.\nConsult the factory before producing a design relying on reading pins configured\nto other feature types.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -135,7 +135,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::GpioAnalogValue", /* .title = */ "None", - /* .docs = */ "Indicates the analog value of the given user GPIO.nThe pin must be configured for analog input.", + /* .docs = */ "Indicates the analog value of the given user GPIO.\nThe pin must be configured for analog input.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, From 426b434054d829fb4e770656341c7df50fb362df Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 25 Jul 2024 17:17:01 -0400 Subject: [PATCH 057/147] Attempt to fix strange MSVC compilation error. --- src/cpp/mip/mip_interface.hpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/src/cpp/mip/mip_interface.hpp b/src/cpp/mip/mip_interface.hpp index e8e985180..141ed6d40 100644 --- a/src/cpp/mip/mip_interface.hpp +++ b/src/cpp/mip/mip_interface.hpp @@ -443,7 +443,8 @@ void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t { auto callback = [](void* context, const C::mip_packet_view* packet, Timestamp timestamp) { - Callback(context, PacketView(*packet), timestamp); + PacketView packetView(*packet); + Callback(context, packetView, timestamp); }; registerPacketCallback(handler, descriptorSet, afterFields, callback, userData); @@ -485,8 +486,9 @@ void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t { auto callback = [](void* pointer, const mip::C::mip_packet_view* packet, Timestamp timestamp) { + PacketView packetView(*packet); Object* obj = static_cast(pointer); - (obj->*Callback)(PacketView(*packet), timestamp); + (obj->*Callback)(packetView, timestamp); }; registerPacketCallback(handler, descriptorSet, afterFields, callback, object); @@ -528,7 +530,8 @@ void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t { auto callback = [](void* context, const C::mip_field_view* field, Timestamp timestamp) { - Callback(context, FieldView(*field), timestamp); + FieldView fieldView(*field); + Callback(context, fieldView, timestamp); }; registerFieldCallback(handler, descriptorSet, fieldDescriptor, callback, userData); @@ -570,8 +573,9 @@ void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t { auto callback = [](void* pointer, const C::mip_field_view* field, Timestamp timestamp) { + FieldView fieldView(*field); Object* obj = static_cast(pointer); - (obj->*Callback)(FieldView(*field), timestamp); + (obj->*Callback)(fieldView, timestamp); }; registerFieldCallback(handler, descriptorSet, fieldDescriptor, callback, object); From 8179a146b17b95700efe63840655b8ed2b03f4c4 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Mon, 29 Jul 2024 13:12:52 -0400 Subject: [PATCH 058/147] Added comparison operator for CmdResult to CompositeResult::Entry --- src/cpp/microstrain/extras/composite_result.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/cpp/microstrain/extras/composite_result.hpp b/src/cpp/microstrain/extras/composite_result.hpp index 056761c64..819507fa3 100644 --- a/src/cpp/microstrain/extras/composite_result.hpp +++ b/src/cpp/microstrain/extras/composite_result.hpp @@ -27,6 +27,9 @@ namespace mip operator bool() const { return result; } bool operator!() const { return !result; } + bool operator==(mip::C::mip_cmd_result value) const { return result == value; } + bool operator!=(mip::C::mip_cmd_result value) const { return result != value; } + Entry(bool r, DescriptorId d={}) : result(r ? CmdResult::ACK_OK : CmdResult::STATUS_ERROR), descriptor(d) {} Entry(CmdResult r, DescriptorId d={}) : result(r), descriptor(d) {} Entry(C::mip_cmd_result r, DescriptorId d={}) : result(r), descriptor(d) {} From 0224c21d60c493e3c9f33e750c3289475096d307 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 31 Jul 2024 15:17:25 -0400 Subject: [PATCH 059/147] Fix Jenkinsfile to properly fail if subcommands fail on Windows. --- Jenkinsfile | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 5e83bdeba..0358a2320 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -42,9 +42,9 @@ pipeline { -T "v142" ` -DBUILD_DOCUMENTATION=ON ` -DBUILD_PACKAGE=ON - cmake --build . -j - cmake --build . --target package - cmake --build . --target package_docs + if(\$?) { cmake --build . } + if(\$?) { cmake --build . --target package } + if(\$?) { cmake --build . --target package_docs } """ archiveArtifacts artifacts: 'build_Win32/mipsdk_*' } @@ -61,8 +61,8 @@ pipeline { -A "x64" ` -T "v142" ` -DBUILD_PACKAGE=ON - cmake --build . -j - cmake --build . --target package + if(\$?) { cmake --build . } + if(\$?) { cmake --build . --target package } """ archiveArtifacts artifacts: 'build_x64/mipsdk_*' } From 081467976fd6a2d4c755c95a1eff42531b635c1e Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 31 Jul 2024 17:50:40 -0400 Subject: [PATCH 060/147] Organize mip 'extras', rename CMake/compiler options for consistency, and add check for metadata support. --- CMakeLists.txt | 85 +++++++++---------- README.md | 35 ++++---- cmake/check_metadata.cmake | 23 +++++ examples/CMakeLists.txt | 29 ++++--- examples/example_utils.cpp | 36 ++++---- examples/example_utils.hpp | 6 +- src/c/microstrain/common/CMakeLists.txt | 7 +- src/c/microstrain/common/embedded_time.h | 2 +- src/c/microstrain/common/logging.h | 20 ++--- src/c/microstrain/connections/CMakeLists.txt | 8 +- .../connections/serial/CMakeLists.txt | 1 + .../connections/tcp/CMakeLists.txt | 1 + src/c/mip/CMakeLists.txt | 8 +- src/c/mip/mip_types.h | 6 +- src/cpp/microstrain/common/CMakeLists.txt | 7 +- .../common/serialization/serializer.hpp | 2 + .../microstrain/connections/CMakeLists.txt | 6 +- src/cpp/microstrain/extras/CMakeLists.txt | 4 +- src/cpp/mip/CMakeLists.txt | 21 ++--- src/cpp/mip/extras/CMakeLists.txt | 10 +++ .../extras/composite_result.hpp | 2 +- .../common => mip/extras}/descriptor_id.hpp | 4 +- .../{microstrain => mip}/extras/version.cpp | 0 .../{microstrain => mip}/extras/version.hpp | 0 src/cpp/mip/metadata/CMakeLists.txt | 17 ++++ src/cpp/mip/metadata/definitions/common.hpp | 2 +- .../{utils.hpp => mip_meta_utils.hpp} | 2 +- src/cpp/mip/metadata/mip_metadata.hpp | 4 +- .../{structures.hpp => mip_structures.hpp} | 0 test/CMakeLists.txt | 2 +- 30 files changed, 199 insertions(+), 151 deletions(-) create mode 100644 cmake/check_metadata.cmake create mode 100644 src/cpp/mip/extras/CMakeLists.txt rename src/cpp/{microstrain => mip}/extras/composite_result.hpp (99%) rename src/cpp/{microstrain/common => mip/extras}/descriptor_id.hpp (96%) rename src/cpp/{microstrain => mip}/extras/version.cpp (100%) rename src/cpp/{microstrain => mip}/extras/version.hpp (100%) create mode 100644 src/cpp/mip/metadata/CMakeLists.txt rename src/cpp/mip/metadata/{utils.hpp => mip_meta_utils.hpp} (99%) rename src/cpp/mip/metadata/{structures.hpp => mip_structures.hpp} (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8782d011f..41ee1c91e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,10 +1,10 @@ cmake_minimum_required(VERSION 3.10) -set(CMAKE_CXX_STANDARD 20) -set(CMAKE_CXX_STANDARD_REQUIRED ON) -set(CMAKE_C_STANDARD 11) -set(CMAKE_C_STANDARD_REQUIRED ON) +#set(CMAKE_CXX_STANDARD 14) +#set(CMAKE_CXX_STANDARD_REQUIRED ON) +#set(CMAKE_C_STANDARD 11) +#set(CMAKE_C_STANDARD_REQUIRED ON) project( "MIP SDK" @@ -13,40 +13,49 @@ project( LANGUAGES C CXX ) +set(SRC_DIR "${CMAKE_CURRENT_LIST_DIR}/src") +set(MIP_CMAKE_DIR "${CMAKE_CURRENT_LIST_DIR}/cmake") +set(MIP_DIR "${SRC_DIR}/mip") + # # Build options # -option(MIP_USE_SERIAL "Build serial connection support into the library and examples" ON) -option(MIP_USE_TCP "Build TCP connection support into the library and exampels" ON) -option(MIP_USE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) +option(MICROSTRAIN_ENABLE_LOGGING "Build with logging functions enabled" ON) + +set(MICROSTRAIN_LOGGING_MAX_LEVEL "" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") +set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") + +option(MICROSTRAIN_ENABLE_SERIAL "Build serial connection support into the library and examples" ON) +option(MICROSTRAIN_ENABLE_TCP "Build TCP connection support into the library and exampels" ON) + +option(MICROSTRAIN_ENABLE_CPP "Enables the C++ API. Turn off to avoid compiling the C++ API." ON) +option(MICROSTRAIN_ENABLE_CPP_C_NAMESPACE "Wraps the C api in a C++ namespace to avoid global namespace pollution (e.g. microstrain::C::microstrain_serial_port)" ${MICROSTRAIN_ENABLE_CPP}) + +# MIP options +option(MIP_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) -option(MIP_ENABLE_LOGGING "Build with logging functions enabled" ON) + +if(NOT DEFINED MIP_ENABLE_METADATA) + include("${MIP_CMAKE_DIR}/check_metadata.cmake") +endif() +option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" MIP_COMPILER_SUPPORTS_METADATA) + +# Build options option(BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) option(BUILD_EXAMPLES "Builds the example programs." ON) # CTest defines this option to ON by default, so override it to OFF here. option(BUILD_TESTING "Build the testing tree." OFF) -option(MIP_DISABLE_CPP "Excludes all C++ files from the project." OFF) option(BUILD_DOCUMENTATION "Build the documentation." OFF) option(BUILD_DOCUMENTATION_FULL "Build the full (internal) documentation." OFF) option(BUILD_DOCUMENTATION_QUIET "Suppress doxygen standard output." ON) -set(MIP_LOGGING_MAX_LEVEL "" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") -set(MIP_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") - -set(SRC_DIR "${CMAKE_CURRENT_LIST_DIR}/src") -set(MIP_CMAKE_DIR "${CMAKE_CURRENT_LIST_DIR}/cmake") - -if(WITH_INTERNAL) - if(NOT DEFINED MIP_INTERNAL_DIR) - set(MIP_INTERNAL_DIR "int" CACHE PATH "") - endif() - file(REAL_PATH "${MIP_INTERNAL_DIR}" MIP_INTERNAL_DIR) - - add_subdirectory("${MIP_INTERNAL_DIR}" "${CMAKE_CURRENT_BINARY_DIR}/mip-internal") -endif() +option(MICROSTRAIN_CMAKE_DEBUG "If set, prints build system debug info such as source files and preprocessor definitions." ON) # TODO: off by default +mark_as_advanced(MICROSTRAIN_CMAKE_DEBUG) -set(MIP_DIR "${SRC_DIR}/mip") +# +# Version numbering +# # Use Git to find the version find_package(Git) @@ -89,28 +98,16 @@ else() endif() # Generate the version header file -set(VERSION_IN_FILE "${MIP_CMAKE_DIR}/mip_version.h.in") +set(VERSION_IN_FILE "${CMAKE_CURRENT_LIST_DIR}/cmake/mip_version.h.in") set(VERSION_OUT_FILE "${SRC_DIR}/c/mip/mip_version.h") configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) -# -# Build options -# - -option(MICROSTRAIN_CPP "Enables the C++ API. Turn off to avoid compiling the C++ API." ON) -option(MICROSTRAIN_CPP_C_NAMESPACE "Wraps the C api in a C++ namespace to avoid global namespace pollution (e.g. microstrain::C::microstrain_serial_port)" ${MICROSTRAIN_CPP}) -option(MICROSTRAIN_CMAKE_DEBUG "If set, prints build system debug info such as source files and preprocessor definitions." ON) # TODO: off by default - -option(MIP_USE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) - -option(BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) - # Suppress warnings due to adding files with target_sources. cmake_policy(SET CMP0076 NEW) include_directories(src/c) -if(MICROSTRAIN_CPP) +if(MICROSTRAIN_ENABLE_CPP) include_directories(src/cpp) endif() @@ -119,17 +116,17 @@ add_subdirectory(src/c/microstrain) add_subdirectory(src/c/mip) # Add all the C++ files (if C++ enabled) -if(MICROSTRAIN_CPP) +if(MICROSTRAIN_ENABLE_CPP) add_subdirectory(src/cpp/microstrain) add_subdirectory(src/cpp/mip) - #target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_CPP=1") - target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_CPP_C_NAMESPACE=${MICROSTRAIN_CPP_C_NAMESPACE}") + #target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_CPP=1") + target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_CPP_C_NAMESPACE=${MICROSTRAIN_ENABLE_CPP_C_NAMESPACE}") endif() -if(MIP_USE_EXTRAS) - list(APPEND MIP_DEFINES "MIP_USE_EXTRAS") +if(MIP_ENABLE_EXTRAS) + list(APPEND MIP_DEFINES "MIP_ENABLE_EXTRAS") set(MIP_EXTRAS_DIR "${MIP_DIR}/extras") set(MIP_EXTRA_SOURCES "${MIP_EXTRAS_DIR}/composite_result.hpp" @@ -203,7 +200,7 @@ if(BUILD_DOCUMENTATION) set(DOXYGEN_WARN_IF_UNDOCUMENTED NO) - if(NOT MIP_DISABLE_CPP) + if(MICROSTRAIN_ENABLE_CPP) set(DOXYGEN_PREDEFINED "__cplusplus") endif() diff --git a/README.md b/README.md index 1edc92919..1a33574f1 100644 --- a/README.md +++ b/README.md @@ -79,7 +79,7 @@ See the documentation page for [Command Results](https://lord-microstrain.github In order to implement command timeouts and provide time of arrival information, this library requires applications to provide the time of received data. The time must be provided as an unsigned integral value with a reasonable precision, typically milliseconds since program startup. By default the timestamp type is set to `uint64_t`, but some embedded -applications may which to change this to `uint32_t` via the `MIP_TIMESTAMP_TYPE` define. Note that wraparound is +applications may which to change this to `uint32_t` via the `MICROSTRAIN_TIMESTAMP_TYPE` define. Note that wraparound is permissible if the wraparound period is longer than twice the longest timeout used by the application. See the documentation page for [Timestamps](https://lord-microstrain.github.io/mip_sdk_documentation/latest/timestamps.html). @@ -96,7 +96,7 @@ A basic serial port interface is provided in C and C++ for Linux, Mac, and Windo The serial port connection will be used in most cases, when the MIP device is connected via a serial or USB cable (the USB connection acts like a virtual serial port). -[Enable it](#build-configuration) in the CMake configuration with `-DMIP_USE_SERIAL=1`. +[Enable it](#build-configuration) in the CMake configuration with `-DMICROSTRAIN_ENABLE_SERIAL=1`. ### TCP Client @@ -104,7 +104,7 @@ The TCP client connection allows you to connect to a MIP device remotely. The MI via the normal serial or USB cable to a computer system running a TCP server which forwards data between the serial port and TCP clients. -[Enable it](#build-configuration) in the CMake configuration with `-DMIP_USE_TCP=1`. +[Enable it](#build-configuration) in the CMake configuration with `-DMICROSTRAIN_ENABLE_TCP=1`. How to Build @@ -114,36 +114,37 @@ How to Build * A working C compiler * C11 or later required -* A working C++ compiler - * For C++ API only. Define `MIP_DISABLE_CPP=ON` if you don't want to use any C++. +* A working C++ compiler, if using any C++ features. + * Define `MICROSTRAIN_ENABLE_CPP=OFF` if you don't want to use any C++. Note that some features are only available in C++. * C++11 or later required for the mip library - * C++14 or later for the examples (currently CMakeLists.txt assumes C++14 is required regardless) + * C++14 or later for the examples + * C++20 or later for metadata and associated examples. * CMake version 3.10 or later (technically this is optional, see below) * Doxygen, if building documentation ### CMake Build Configuration The following options may be specified when configuring the build with CMake (e.g. `cmake .. -DOPTION=VALUE`): -* MIP_USE_SERIAL - Builds the included serial port library (default enabled). -* MIP_USE_TCP - Builds the included socket library (default enabled). -* MIP_USE_EXTRAS - Builds some higher level utility classes and functions that may use dynamic memory. -* MIP_ENABLE_LOGGING - Builds logging functionality into the library. The user is responsible for configuring a logging callback (default enabled) -* MIP_LOGGING_MAX_LEVEL - Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration. Useful if you want some logs, but do not want the overhead compiled into the code. +* MICROSTRAIN_ENABLE_SERIAL - Builds the included serial port library (default enabled). +* MICROSTRAIN_ENABLE_TCP - Builds the included socket library (default enabled). +* MICROSTRAIN_ENABLE_LOGGING - Builds logging functionality into the library. The user is responsible for configuring a logging callback (default enabled) +* MICROSTRAIN_LOGGING_MAX_LEVEL - Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration. Useful if you want some logs, but do not want the overhead compiled into the code. +* MICROSTRAIN_TIMESTAMP_TYPE - Overrides the default timestamp type. See the timestamps section in the documentation. +* MICROSTRAIN_ENABLE_CPP - Causes the src/cpp directory to be included in the build (default enabled). Disable to turn off the C++ api. +* MIP_ENABLE_EXTRAS - Builds some higher level utility classes and functions that may use dynamic memory. * MIP_ENABLE_DIAGNOSTICS - Adds some counters to various entities which can serve as a debugging aid. * BUILD_EXAMPLES - If enabled (`-DBUILD_EXAMPLES=ON`), the example projects will be built (default disabled). * BUILD_TESTING - If enabled (`-DBUILD_TESTING=ON`), the test programs in the /test directory will be compiled and linked. Run the tests with `ctest`. * BUILD_DOCUMENTATION - If enabled, the documentation will be built with doxygen. You must have doxygen installed. * BUILD_DOCUMENTATION_FULL - Builds internal documentation (default disabled). * BUILD_DOCUMENTATION_QUIET - Suppress standard doxygen output (default enabled). -* MIP_DISABLE_CPP - Ignores .hpp/.cpp files during the build and does not add them to the project. * BUILD_PACKAGE - Adds a `package` target to the project that will build a `.deb`, `.rpm`, or `.7z` file containing the library -* MIP_TIMESTAMP_TYPE - Overrides the default timestamp type. See the timestamps section in the documentation. ### Compilation 1. Create the build directory (e.g. `mkdir build`). 2. In the build directory, run `cmake .. ` - * Replace `` with your configuration options, such as `-DMIP_USE_SERIAL=1`. + * Replace `` with your configuration options, such as `-DMICROSTRAIN_ENABLE_SERIAL=1`. * You can use `cmake-gui ..` instead if you'd prefer to use the GUI tool (and have it installed). * An alternative generator may be used, such as ninja, code blocks, etc. by specifying `-G ` 3. Invoke `cmake --build .` in the build directory @@ -162,10 +163,10 @@ include all the necessary files and define a few options. #### Required #defines for building without CMake -Pass these to your compiler as appropriate, e.g. `arm-none-eabi-gcc -DMIP_TIMESTAMP_TYPE=uint32_t -DMIP_ENABLE_LOGGING=0` +Pass these to your compiler as appropriate, e.g. `arm-none-eabi-gcc -DMICROSTRAIN_TIMESTAMP_TYPE=uint32_t -DMICROSTRAIN_ENABLE_LOGGING=0` -* MIP_ENABLE_LOGGING (and MIP_LOGGING_MAX_LEVEL) - default is enabled -* MIP_TIMESTAMP_TYPE - defaults to uint64_t if not specified +* MICROSTRAIN_ENABLE_LOGGING (and MICROSTRAIN_LOGGING_MAX_LEVEL) - default is enabled +* MICROSTRAIN_TIMESTAMP_TYPE - defaults to uint64_t if not specified * MIP_ENABLE_DIAGNOSTICS - Supported on embedded platforms to aid debugging These options affect the compiled code interface and sizes of various structs. They diff --git a/cmake/check_metadata.cmake b/cmake/check_metadata.cmake new file mode 100644 index 000000000..fd02db1bf --- /dev/null +++ b/cmake/check_metadata.cmake @@ -0,0 +1,23 @@ + +include(CheckCXXSourceCompiles) + +check_cxx_source_compiles(" +#include + +struct Foo +{ + int i = 0; + const char* s = nullptr; +}; + +static inline constexpr Foo foo = {5, \"12345\"}; + +int main() +{ + static_assert(foo.i == 5 && foo.s != nullptr, \"foo has wrong value\"); + return 0; +} + +" MIP_COMPILER_SUPPORTS_METADATA) + +#set(MIP_COMPILER_SUPPORTS_METADATA ${COMPILER_SUPPORTS_METADATA} PARENT_SCOPE) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 83ec15ccd..2a24141f2 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -11,22 +11,22 @@ set(EXAMPLE_SOURCES set(EXAMPLE_LIBS ) -if(MIP_USE_SERIAL) - set(SERIAL_DEFS "MIP_USE_SERIAL") +if(MICROSTRAIN_ENABLE_SERIAL) + set(SERIAL_DEFS "MICROSTRAIN_ENABLE_SERIAL") list(APPEND EXAMPLE_LIBS microstrain_serial) endif() -if(MIP_USE_TCP) - set(TCP_DEFS "MIP_USE_TCP") +if(MICROSTRAIN_ENABLE_TCP) + set(TCP_DEFS "MICROSTRAIN_ENABLE_TCP") list(APPEND EXAMPLE_LIBS microstrain_socket) endif() -if(MIP_USE_SERIAL OR MIP_USE_TCP) +if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) list(APPEND EXAMPLE_LIBS microstrain_recording_connection) endif() -if(MIP_USE_EXTRAS) - set(EXTRAS_DEFS "MIP_USE_EXTRAS") +if(MIP_ENABLE_EXTRAS) + set(EXTRAS_DEFS "MIP_ENABLE_EXTRAS") endif() set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) @@ -35,23 +35,26 @@ macro(add_mip_example name sources) add_executable(${name} ${sources}) - target_link_libraries(${name} mip ${EXAMPLE_LIBS}) + target_compile_features(${name} PUBLIC c_std_11 cxx_std_14) + target_link_libraries(${name} PUBLIC mip ${EXAMPLE_LIBS}) target_compile_definitions(${name} PUBLIC ${MIP_EXAMPLE_DEFS}) target_include_directories(${name} PRIVATE ${SRC_DIR} ${EXAMPLE_DIR}) endmacro() # C++ examples need either serial or TCP support -if(MIP_USE_SERIAL OR MIP_USE_TCP) +if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) - if(NOT MIP_DISABLE_CPP) + if(NOT MICROSTRAIN_ENABLE_CPP) # Generic examples add_mip_example(DeviceInfo "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/device_info.cpp") add_mip_example(WatchImu "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.cpp") add_mip_example(Threads "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/threading.cpp") - add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") - target_compile_features(CsvExample PUBLIC cxx_std_20) + if(MIP_ENABLE_METADATA) + add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") + target_link_libraries(CsvExample PRIVATE mip_metadata) + endif() # Product-specific examples add_mip_example(GQ7_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") @@ -65,7 +68,7 @@ if(MIP_USE_SERIAL OR MIP_USE_TCP) endif() # C examples need serial support -if(MIP_USE_SERIAL) +if(MICROSTRAIN_ENABLE_SERIAL) add_mip_example(WatchImuC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.c") add_mip_example(GQ7_ExampleC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/GQ7/GQ7_example.c") diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index 9ac56d453..fb78fcb39 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -53,57 +53,57 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, if( !binary_file_path.empty() ) { -#ifdef MIP_USE_EXTRAS +#if defined MICROSTRAIN_ENABLE_SERIAL || defined MICROSTRAIN_ENABLE_TCP example_utils->recordedFile = std::make_unique(binary_file_path); if( !example_utils->recordedFile->is_open() ) throw std::runtime_error("Unable to open binary file"); -#else // MIP_USE_EXTRAS - throw std::runtime_error("The program was compiled without binary file recording support. Recompile with -DMIP_USE_EXTRAS=ON"); -#endif // MIP_USE_EXTRAS +#else // MIP_ENABLE_EXTRAS + throw std::runtime_error("The program was compiled without binary file recording support. Recompile with -DMIP_ENABLE_EXTRAS=ON"); +#endif // MIP_ENABLE_EXTRAS } if(port_or_hostname.find(PORT_KEY) == std::string::npos) // Not a serial port { -#ifdef MIP_USE_TCP +#ifdef MICROSTRAIN_ENABLE_TCP uint32_t port = std::strtoul(baud_or_port.c_str(), nullptr, 10); if( port < 1024 || port > 65535 ) throw std::runtime_error("Invalid TCP port (must be between 1024 and 65535."); -#ifdef MIP_USE_EXTRAS +#if defined MICROSTRAIN_ENABLE_SERIAL || defined MICROSTRAIN_ENABLE_TCP using RecordingTcpConnection = microstrain::connections::RecordingConnectionWrapper; example_utils->connection = std::make_unique(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, port); -#else // MIP_USE_EXTRAS +#else // MIP_ENABLE_EXTRAS using TcpConnection = microstrain::connections::TcpConnection; example_utils->connection = std::make_unique(port_or_hostname, port); -#endif // MIP_USE_EXTRAS +#endif // MIP_ENABLE_EXTRAS example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), 1000, 2000); -#else // MIP_USE_TCP - throw std::runtime_error("This program was compiled without socket support. Recompile with -DMIP_USE_TCP=1"); -#endif // MIP_USE_TCP +#else // MICROSTRAIN_ENABLE_TCP + throw std::runtime_error("This program was compiled without socket support. Recompile with -DMICROSTRAIN_ENABLE_TCP=1"); +#endif // MICROSTRAIN_ENABLE_TCP } else // Serial port { -#ifdef MIP_USE_SERIAL +#ifdef MICROSTRAIN_ENABLE_SERIAL uint32_t baud = std::strtoul(baud_or_port.c_str(), nullptr, 10); if( baud == 0 ) throw std::runtime_error("Serial baud rate must be a decimal integer greater than 0."); -#ifdef MIP_USE_EXTRAS +#if defined MICROSTRAIN_ENABLE_SERIAL || defined MICROSTRAIN_ENABLE_TCP using RecordingSerialConnection = microstrain::connections::RecordingConnectionWrapper; example_utils->connection = std::make_unique(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, baud); -#else // MIP_USE_EXTRAS +#else // MIP_ENABLE_EXTRAS using SerialConnection = microstrain::connections::SerialConnection; example_utils->connection = std::make_unique(port_or_hostname, baud); -#endif // MIP_USE_EXTRAS +#endif // MIP_ENABLE_EXTRAS example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), mip::C::mip_timeout_from_baudrate(baud), 500); -#else // MIP_USE_SERIAL - throw std::runtime_error("This program was compiled without serial support. Recompile with -DMIP_USE_SERIAL=1.\n"); -#endif //MIP_USE_SERIAL +#else // MICROSTRAIN_ENABLE_SERIAL + throw std::runtime_error("This program was compiled without serial support. Recompile with -DMICROSTRAIN_ENABLE_SERIAL=1.\n"); +#endif //MICROSTRAIN_ENABLE_SERIAL } if( !example_utils->connection->connect() ) diff --git a/examples/example_utils.hpp b/examples/example_utils.hpp index 2043e5a4f..0b8bb5c09 100644 --- a/examples/example_utils.hpp +++ b/examples/example_utils.hpp @@ -1,13 +1,13 @@ #pragma once -#ifdef MIP_USE_SERIAL +#ifdef MICROSTRAIN_ENABLE_SERIAL #include "microstrain/connections/serial/serial_connection.hpp" #endif -#ifdef MIP_USE_TCP +#ifdef MICROSTRAIN_ENABLE_TCP #include "microstrain/connections/tcp/tcp_connection.hpp" #endif -#ifdef MIP_USE_EXTRAS +#if defined MICROSTRAIN_ENABLE_SERIAL || defined MICROSTRAIN_ENABLE_TCP #include "microstrain/connections/recording/recording_connection.hpp" #endif diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index 2ca1c88b0..5b3b443c9 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -1,5 +1,5 @@ -option(MICROSTRAIN_ENABLE_LOGGING "Build with logging functions enabled" ON) +#option(MICROSTRAIN_ENABLE_LOGGING "Build with logging functions enabled" ON) set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any call to logging functions with a higher level than this will be compiled out.") set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") @@ -12,8 +12,9 @@ set(SOURCES ) add_library(microstrain_common ${SOURCES}) +target_compile_features(microstrain_common PUBLIC c_std_11) -target_compile_definitions(microstrain_common PUBLIC "MIP_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") # TODO rename +target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") # TODO rename # Logging is a little weird since we need to install the header no matter what if(MICROSTRAIN_ENABLE_LOGGING) @@ -22,7 +23,7 @@ if(MICROSTRAIN_ENABLE_LOGGING) endif() target_sources(microstrain_common PRIVATE "../../../c/microstrain/common/logging.c") message("MicroStrain logging is enabled. Max level = '${MICROSTRAIN_LOGGING_MAX_LEVEL}'") - target_compile_definitions(microstrain_common PUBLIC "MIP_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") # TODO rename + target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") # TODO rename endif() #target_include_directories(microstrain_common PUBLIC ${CMAKE_CURRENT_LIST_DIR}) diff --git a/src/c/microstrain/common/embedded_time.h b/src/c/microstrain/common/embedded_time.h index 2078dde63..d6ec2ca39 100644 --- a/src/c/microstrain/common/embedded_time.h +++ b/src/c/microstrain/common/embedded_time.h @@ -20,7 +20,7 @@ namespace C { /// this requirement may result in false timeouts or delays in getting parsed packets. /// #ifdef MICROSTRAIN_TIMESTAMP_TYPE -typedef MICROSTRAIN_TIMESTAMP_TYPE microstrain_timestamp; +typedef MICROSTRAIN_TIMESTAMP_TYPE microstrain_embedded_timestamp; static_assert( sizeof(microstrain_embedded_timestamp) >= 8 || microstrain_embedded_timestamp(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); #elif defined(MICROSTRAIN_PLATFORM_DESKTOP) diff --git a/src/c/microstrain/common/logging.h b/src/c/microstrain/common/logging.h index bcc05b85e..6c5fe097e 100644 --- a/src/c/microstrain/common/logging.h +++ b/src/c/microstrain/common/logging.h @@ -57,7 +57,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); ///@param level The level that the MIP SDK should log at ///@param user User data that will be passed to the callback every time it is excuted /// -#ifdef MIP_ENABLE_LOGGING +#ifdef MICROSTRAIN_ENABLE_LOGGING #define MIP_LOG_INIT(callback, level, user) microstrain_logging_init(callback, level, user) #else #define MIP_LOG_INIT(callback, level, user) (void)0 @@ -68,14 +68,14 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); /// log level functions like MIP_LOG_INFO, etc. when possible. ///@copydetails mip::C::microstrain_log_callback /// -#ifdef MIP_ENABLE_LOGGING +#ifdef MICROSTRAIN_ENABLE_LOGGING #define MIP_LOG_LOG(level, ...) microstrain_logging_log(level, __VA_ARGS__) #else #define MIP_LOG_LOG(level, ...) (void)0 #endif -#ifndef MIP_LOGGING_MAX_LEVEL -#define MIP_LOGGING_MAX_LEVEL MIP_LOG_LEVEL_WARN +#ifndef MICROSTRAIN_LOGGING_MAX_LEVEL +#define MICROSTRAIN_LOGGING_MAX_LEVEL MIP_LOG_LEVEL_WARN #endif //////////////////////////////////////////////////////////////////////////////// @@ -85,7 +85,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); ///@param fmt printf style format string ///@param ... Variadic args used to populate the fmt string /// -#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_FATAL +#if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_FATAL #define MIP_LOG_FATAL(...) MIP_LOG_LOG(MICROSTRAIN_LOG_LEVEL_FATAL, __VA_ARGS__) #else #define MIP_LOG_FATAL(...) (void)0 @@ -94,7 +94,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at error level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_ERROR +#if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_ERROR #define MIP_LOG_ERROR(...) MIP_LOG_LOG(MICROSTRAIN_LOG_LEVEL_ERROR, __VA_ARGS__) #else #define MIP_LOG_ERROR(...) (void)0 @@ -103,7 +103,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at warn level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_WARN +#if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_WARN #define MIP_LOG_WARN(...) MIP_LOG_LOG(MICROSTRAIN_LOG_LEVEL_WARN, __VA_ARGS__) #else #define MIP_LOG_WARN(...) (void)0 @@ -112,7 +112,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at info level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_INFO +#if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_INFO #define MIP_LOG_INFO(...) MIP_LOG_LOG(MIP_LOG_LEVEL_INFO, __VA_ARGS__) #else #define MIP_LOG_INFO(...) (void)0 @@ -121,7 +121,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at debug level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_DEBUG +#if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_DEBUG #define MIP_LOG_DEBUG(...) MIP_LOG_LOG(MIP_LOG_LEVEL_DEBUG, __VA_ARGS__) #else #define MIP_LOG_DEBUG(...) (void)0 @@ -130,7 +130,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MIP SDK at trace level ///@copydetails mip::C::MIP_LOG_FATAL -#if MIP_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_TRACE +#if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_TRACE #define MIP_LOG_TRACE(...) MIP_LOG_LOG(MIP_LOG_LEVEL_TRACE, __VA_ARGS__) #else #define MIP_LOG_TRACE(...) (void)0 diff --git a/src/c/microstrain/connections/CMakeLists.txt b/src/c/microstrain/connections/CMakeLists.txt index 48980b7f9..5a1143190 100644 --- a/src/c/microstrain/connections/CMakeLists.txt +++ b/src/c/microstrain/connections/CMakeLists.txt @@ -1,13 +1,13 @@ -option(MIP_USE_SERIAL "Build serial connection support into the library and examples" ON) -option(MIP_USE_TCP "Build TCP connection support into the library and exampels" ON) +#option(MICROSTRAIN_ENABLE_SERIAL "Build serial connection support into the library and examples" ON) +#option(MICROSTRAIN_ENABLE_TCP "Build TCP connection support into the library and exampels" ON) -if(MIP_USE_SERIAL) +if(MICROSTRAIN_ENABLE_SERIAL) add_subdirectory(serial) endif() -if(MIP_USE_TCP) +if(MICROSTRAIN_ENABLE_TCP) add_subdirectory(tcp) endif() diff --git a/src/c/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt index e20fec293..e3c35a932 100644 --- a/src/c/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -5,5 +5,6 @@ set(SOURCES ) add_library(microstrain_serial ${SOURCES}) +target_compile_features(microstrain_serial PUBLIC c_std_11) target_link_libraries(microstrain_serial PUBLIC microstrain_common) diff --git a/src/c/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt index 68a23f2d2..747eabc27 100644 --- a/src/c/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -5,6 +5,7 @@ set(SOURCES ) add_library(microstrain_socket ${SOURCES}) +target_compile_features(microstrain_socket PUBLIC c_std_11) target_link_libraries(microstrain_socket PUBLIC microstrain_common) diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index 6c43e3377..3be509929 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -1,6 +1,6 @@ -option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) +#option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) set(MIP_SOURCES @@ -34,7 +34,7 @@ set(MIP_SOURCES ) add_library(mip ${MIP_SOURCES}) - +target_compile_features(mip PUBLIC c_std_11) set(MIPDEFS commands_3dm @@ -91,8 +91,8 @@ if(${MIP_ENABLE_DIAGNOSTICS}) list(APPEND MIP_DEFINES "MIP_ENABLE_DIAGNOSTICS") endif() -if(${MIP_TIMESTAMP_TYPE}) - list(APPEND MIP_DEFINES "MIP_TIMESTAMP_TYPE=${MIP_TIMESTAMP_TYPE}") +if(${MICROSTRAIN_TIMESTAMP_TYPE}) + list(APPEND MIP_DEFINES "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") endif() target_compile_definitions(mip PUBLIC "${MIP_DEFINES}") diff --git a/src/c/mip/mip_types.h b/src/c/mip/mip_types.h index 2a8c7b4a8..8b6188b2c 100644 --- a/src/c/mip/mip_types.h +++ b/src/c/mip/mip_types.h @@ -23,9 +23,9 @@ extern "C" { /// days, so the parser should be invoked at least every 25 days. Failure to observe /// this requirement may result in false timeouts or delays in getting parsed packets. /// -#ifdef MIP_TIMESTAMP_TYPE - typedef MIP_TIMESTAMP_TYPE mip_timestamp; - static_assert( sizeof(mip_timestamp) >= 8 || (mip_timestamp)(-1) > 0, "MIP_TIMESTAMP_TYPE must be unsigned unless 64 bits."); +#ifdef MICROSTRAIN_TIMESTAMP_TYPE + typedef MICROSTRAIN_TIMESTAMP_TYPE mip_timestamp; + static_assert( sizeof(mip_timestamp) >= 8 || (mip_timestamp)(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); #else typedef uint64_t mip_timestamp; #endif diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index 443413ed1..00989ac67 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -1,12 +1,13 @@ # microstrain_common is defined by the C api. target_sources(microstrain_common PUBLIC - serialization.hpp - descriptor_id.hpp - index.hpp embedded_time.hpp + index.hpp logging.hpp platform.hpp + serialization.hpp + serialization/readwrite.hpp + serialization/serializer.hpp ) target_compile_features(microstrain_common PUBLIC cxx_std_11) diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index 95e6263c1..82f464cc7 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -2,6 +2,8 @@ #include "readwrite.hpp" +#include + #include #include diff --git a/src/cpp/microstrain/connections/CMakeLists.txt b/src/cpp/microstrain/connections/CMakeLists.txt index 662348b23..a7fe81fd8 100644 --- a/src/cpp/microstrain/connections/CMakeLists.txt +++ b/src/cpp/microstrain/connections/CMakeLists.txt @@ -1,13 +1,13 @@ -if(MIP_USE_SERIAL) +if(MICROSTRAIN_ENABLE_SERIAL) add_subdirectory(serial) endif() -if(MIP_USE_TCP) +if(MICROSTRAIN_ENABLE_TCP) add_subdirectory(tcp) endif() # Don't include recording connection if no connections are enabled. -if(MIP_USE_SERIAL OR MIP_USE_TCP) +if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) add_subdirectory(recording) endif() diff --git a/src/cpp/microstrain/extras/CMakeLists.txt b/src/cpp/microstrain/extras/CMakeLists.txt index 78bde7bcc..402dd515a 100644 --- a/src/cpp/microstrain/extras/CMakeLists.txt +++ b/src/cpp/microstrain/extras/CMakeLists.txt @@ -1,10 +1,8 @@ set(SOURCES - composite_result.hpp scope_helper.cpp scope_helper.hpp - version.cpp - version.hpp ) add_library(microstrain_extras ${SOURCES}) +target_compile_features(microstrain_extras PUBLIC cxx_std_11) diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index 4cf715271..53932d96d 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -28,17 +28,12 @@ if(MICROSTRAIN_CMAKE_DEBUG) message("C++ definitions = ${MIPDEF_SOURCES}") endif() -set(META_SOURCES - metadata/mip_all_definitions.hpp - metadata/mip_definitions.hpp - metadata/mip_definitions.cpp - metadata/mip_metadata.hpp - metadata/structures.hpp - metadata/utils.hpp - metadata/definitions/commands_base.hpp - metadata/definitions/commands_3dm.hpp - metadata/definitions/data_sensor.hpp - metadata/definitions/common.hpp -) +target_sources(mip PUBLIC ${MIPDEF_SOURCES}) + +if(MIP_ENABLE_METADATA) + add_subdirectory(metadata) +endif() -target_sources(mip PUBLIC ${MIPDEF_SOURCES} ${META_SOURCES}) +if(MIP_ENABLE_EXTRAS) + add_subdirectory(extras) +endif() diff --git a/src/cpp/mip/extras/CMakeLists.txt b/src/cpp/mip/extras/CMakeLists.txt new file mode 100644 index 000000000..903208018 --- /dev/null +++ b/src/cpp/mip/extras/CMakeLists.txt @@ -0,0 +1,10 @@ + +set(SOURCES + composite_result.hpp + descriptor_id.hpp + version.cpp + version.hpp +) + +add_library(mip_extras ${SOURCES}) +target_compile_features(mip_extras PUBLIC cxx_std_11) diff --git a/src/cpp/microstrain/extras/composite_result.hpp b/src/cpp/mip/extras/composite_result.hpp similarity index 99% rename from src/cpp/microstrain/extras/composite_result.hpp rename to src/cpp/mip/extras/composite_result.hpp index 056761c64..0ed409540 100644 --- a/src/cpp/microstrain/extras/composite_result.hpp +++ b/src/cpp/mip/extras/composite_result.hpp @@ -1,6 +1,6 @@ #pragma once -#include "microstrain/common/descriptor_id.hpp" +#include "descriptor_id.hpp" #include "mip/mip_interface.hpp" #include "mip/mip_result.h" diff --git a/src/cpp/microstrain/common/descriptor_id.hpp b/src/cpp/mip/extras/descriptor_id.hpp similarity index 96% rename from src/cpp/microstrain/common/descriptor_id.hpp rename to src/cpp/mip/extras/descriptor_id.hpp index 1fd1cac49..5762c404d 100644 --- a/src/cpp/microstrain/common/descriptor_id.hpp +++ b/src/cpp/mip/extras/descriptor_id.hpp @@ -1,8 +1,6 @@ #pragma once -#include "mip/mip_descriptors.h" - -#include +#include "../mip_descriptors.hpp" namespace mip diff --git a/src/cpp/microstrain/extras/version.cpp b/src/cpp/mip/extras/version.cpp similarity index 100% rename from src/cpp/microstrain/extras/version.cpp rename to src/cpp/mip/extras/version.cpp diff --git a/src/cpp/microstrain/extras/version.hpp b/src/cpp/mip/extras/version.hpp similarity index 100% rename from src/cpp/microstrain/extras/version.hpp rename to src/cpp/mip/extras/version.hpp diff --git a/src/cpp/mip/metadata/CMakeLists.txt b/src/cpp/mip/metadata/CMakeLists.txt new file mode 100644 index 000000000..d74b8d7b2 --- /dev/null +++ b/src/cpp/mip/metadata/CMakeLists.txt @@ -0,0 +1,17 @@ + + +set(META_SOURCES + mip_all_definitions.hpp + mip_definitions.hpp + mip_definitions.cpp + mip_metadata.hpp + mip_structures.hpp + mip_meta_utils.hpp + definitions/commands_base.hpp + definitions/commands_3dm.hpp + definitions/data_sensor.hpp + definitions/common.hpp +) + +add_library(mip_metadata ${META_SOURCES}) +target_compile_features(mip_metadata PUBLIC cxx_std_20) diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index 9f709d80a..e74bb224f 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -1,7 +1,7 @@ #pragma once #include -#include +#include #include diff --git a/src/cpp/mip/metadata/utils.hpp b/src/cpp/mip/metadata/mip_meta_utils.hpp similarity index 99% rename from src/cpp/mip/metadata/utils.hpp rename to src/cpp/mip/metadata/mip_meta_utils.hpp index 46e5a6f94..4d1b78ef2 100644 --- a/src/cpp/mip/metadata/utils.hpp +++ b/src/cpp/mip/metadata/mip_meta_utils.hpp @@ -1,6 +1,6 @@ #pragma once -#include "structures.hpp" +#include "mip_structures.hpp" namespace mip::metadata::utils diff --git a/src/cpp/mip/metadata/mip_metadata.hpp b/src/cpp/mip/metadata/mip_metadata.hpp index 7d7552737..03a1c6cd4 100644 --- a/src/cpp/mip/metadata/mip_metadata.hpp +++ b/src/cpp/mip/metadata/mip_metadata.hpp @@ -1,7 +1,7 @@ #pragma once -#include "structures.hpp" -#include "utils.hpp" +#include "mip_structures.hpp" +#include "mip_meta_utils.hpp" #include #include diff --git a/src/cpp/mip/metadata/structures.hpp b/src/cpp/mip/metadata/mip_structures.hpp similarity index 100% rename from src/cpp/mip/metadata/structures.hpp rename to src/cpp/mip/metadata/mip_structures.hpp diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 0029dd828..8ec25a0d1 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -23,7 +23,7 @@ add_mip_test(TestMipFields "${TEST_DIR}/mip/test_mip_fields.c" TestMipFi add_mip_test(TestMipCpp "${TEST_DIR}/mip/test_mip.cpp" TestMipCpp) add_mip_test(TestMipPerf "${TEST_DIR}/mip/mip_parser_performance.cpp" TestMipPerf) -#if(MIP_USE_SERIAL) +#if(MICROSTRAIN_ENABLE_SERIAL) # add_executable(TestSerial "${TEST_DIR}/test_serial.cpp") # target_include_directories(TestSerial PUBLIC "${SRC_DIR}") # target_link_libraries(TestSerial PUBLIC "serial") From 76a1ab371ab6125b0c409d6a479b19ff310430ac Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 1 Aug 2024 15:15:26 -0400 Subject: [PATCH 061/147] Fix build on MSVC. --- CMakeLists.txt | 3 ++- cmake/check_metadata.cmake | 2 -- src/c/microstrain/common/CMakeLists.txt | 2 +- .../microstrain/common/serialization/serializer.hpp | 12 ++++++------ src/cpp/mip/mip_interface.cpp | 2 +- 5 files changed, 10 insertions(+), 11 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 41ee1c91e..a34600603 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ set(MIP_DIR "${SRC_DIR}/mip") option(MICROSTRAIN_ENABLE_LOGGING "Build with logging functions enabled" ON) -set(MICROSTRAIN_LOGGING_MAX_LEVEL "" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") +set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_INFO" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") option(MICROSTRAIN_ENABLE_SERIAL "Build serial connection support into the library and examples" ON) @@ -38,6 +38,7 @@ option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip lib if(NOT DEFINED MIP_ENABLE_METADATA) include("${MIP_CMAKE_DIR}/check_metadata.cmake") + message("MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") endif() option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" MIP_COMPILER_SUPPORTS_METADATA) diff --git a/cmake/check_metadata.cmake b/cmake/check_metadata.cmake index fd02db1bf..621e73d7b 100644 --- a/cmake/check_metadata.cmake +++ b/cmake/check_metadata.cmake @@ -19,5 +19,3 @@ int main() } " MIP_COMPILER_SUPPORTS_METADATA) - -#set(MIP_COMPILER_SUPPORTS_METADATA ${COMPILER_SUPPORTS_METADATA} PARENT_SCOPE) diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index 5b3b443c9..52e7caf5e 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -19,7 +19,7 @@ target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE # Logging is a little weird since we need to install the header no matter what if(MICROSTRAIN_ENABLE_LOGGING) if(MICROSTRAIN_LOGGING_MAX_LEVEL STREQUAL "") - message(ERROR "MICROSTRAIN_LOGGING_MAX_LEVEL must be MICROSTRAIN_LOG_LEVEL_* or a number") + message(FATAL_ERROR "MICROSTRAIN_LOGGING_MAX_LEVEL must be MICROSTRAIN_LOG_LEVEL_* or a number") endif() target_sources(microstrain_common PRIVATE "../../../c/microstrain/common/logging.c") message("MicroStrain logging is enabled. Max level = '${MICROSTRAIN_LOGGING_MAX_LEVEL}'") diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index 82f464cc7..59717a07e 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -316,10 +316,10 @@ typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type return ( ... + insert(buffer, values) ); } #else -template -size_t insert(Serializer& serializer, T0 value0, Ts... values) +template +size_t insert(Serializer& serializer, const T0& value0, const T1& value1, Ts... values) { - return insert(serializer, value0) + insert(serializer, values...); + return insert(serializer, value0) + insert(serializer, value1, values...); } #endif @@ -346,10 +346,10 @@ typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type return ( ... + extract(buffer, values) ); } #else -template -size_t extract(Serializer& serializer, T0 value0, Ts... values) +template +size_t extract(Serializer& serializer, T0& value0, T1& value1, Ts&... values) { - return extract(serializer, value0) + extract(serializer, values...); + return extract(serializer, value0) + extract(serializer, value1, values...); } #endif diff --git a/src/cpp/mip/mip_interface.cpp b/src/cpp/mip/mip_interface.cpp index 02e14e7b8..cca500369 100644 --- a/src/cpp/mip/mip_interface.cpp +++ b/src/cpp/mip/mip_interface.cpp @@ -43,7 +43,7 @@ void connect_interface(mip::Interface& device, microstrain::Connection& conn) }; auto recv = [](C::mip_interface* device, uint8_t* buffer, size_t max_length, C::mip_timeout wait_time, size_t* length_out, C::mip_timestamp* timestamp_out)->bool { - return static_cast(C::mip_interface_user_pointer(device))->recvFromDevice(buffer, max_length, wait_time, length_out, timestamp_out); + return static_cast(C::mip_interface_user_pointer(device))->recvFromDevice(buffer, max_length, static_cast(wait_time), length_out, timestamp_out); }; C::mip_interface_set_user_pointer(&device, &conn); From b9103d26a9bbe38b338559fd7802fc19b55163e0 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 1 Aug 2024 16:03:59 -0400 Subject: [PATCH 062/147] Try to build examples with only C++11. --- examples/CMakeLists.txt | 5 ++++- examples/example_utils.cpp | 16 ++++++++-------- 2 files changed, 12 insertions(+), 9 deletions(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 2a24141f2..f87620d28 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -35,7 +35,10 @@ macro(add_mip_example name sources) add_executable(${name} ${sources}) - target_compile_features(${name} PUBLIC c_std_11 cxx_std_14) + target_compile_features(${name} PUBLIC c_std_11) + if(MICROSTRAIN_ENABLE_CPP) # Technically should only do this for C++ examples but this is simpler + target_compile_features(${name} PUBLIC cxx_std_11) + endif() target_link_libraries(${name} PUBLIC mip ${EXAMPLE_LIBS}) target_compile_definitions(${name} PUBLIC ${MIP_EXAMPLE_DEFS}) target_include_directories(${name} PRIVATE ${SRC_DIR} ${EXAMPLE_DIR}) diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index fb78fcb39..6d05ade7d 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -49,12 +49,12 @@ void customLog(void* user, microstrain_log_level level, const char* fmt, va_list std::unique_ptr openFromArgs(const std::string& port_or_hostname, const std::string& baud_or_port, const std::string& binary_file_path) { - auto example_utils = std::make_unique(); + std::unique_ptr example_utils(new ExampleUtils()); if( !binary_file_path.empty() ) { #if defined MICROSTRAIN_ENABLE_SERIAL || defined MICROSTRAIN_ENABLE_TCP - example_utils->recordedFile = std::make_unique(binary_file_path); + example_utils->recordedFile.reset(new std::ofstream(binary_file_path)); if( !example_utils->recordedFile->is_open() ) throw std::runtime_error("Unable to open binary file"); #else // MIP_ENABLE_EXTRAS @@ -72,13 +72,13 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, #if defined MICROSTRAIN_ENABLE_SERIAL || defined MICROSTRAIN_ENABLE_TCP using RecordingTcpConnection = microstrain::connections::RecordingConnectionWrapper; - example_utils->connection = std::make_unique(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, port); + example_utils->connection.reset(new RecordingTcpConnection(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, port)); #else // MIP_ENABLE_EXTRAS using TcpConnection = microstrain::connections::TcpConnection; - example_utils->connection = std::make_unique(port_or_hostname, port); + example_utils->connection.reset(new TcpConnection(port_or_hostname, port)); #endif // MIP_ENABLE_EXTRAS - example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), 1000, 2000); + example_utils->device.reset(new mip::Interface(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), 1000, 2000)); #else // MICROSTRAIN_ENABLE_TCP throw std::runtime_error("This program was compiled without socket support. Recompile with -DMICROSTRAIN_ENABLE_TCP=1"); #endif // MICROSTRAIN_ENABLE_TCP @@ -94,13 +94,13 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, #if defined MICROSTRAIN_ENABLE_SERIAL || defined MICROSTRAIN_ENABLE_TCP using RecordingSerialConnection = microstrain::connections::RecordingConnectionWrapper; - example_utils->connection = std::make_unique(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, baud); + example_utils->connection.reset(new RecordingSerialConnection(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, baud)); #else // MIP_ENABLE_EXTRAS using SerialConnection = microstrain::connections::SerialConnection; - example_utils->connection = std::make_unique(port_or_hostname, baud); + example_utils->connection.reset(new SerialConnection(port_or_hostname, baud)); #endif // MIP_ENABLE_EXTRAS - example_utils->device = std::make_unique(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), mip::C::mip_timeout_from_baudrate(baud), 500); + example_utils->device.reset(new mip::Interface(example_utils->connection.get(), example_utils->buffer, sizeof(example_utils->buffer), mip::C::mip_timeout_from_baudrate(baud), 500)); #else // MICROSTRAIN_ENABLE_SERIAL throw std::runtime_error("This program was compiled without serial support. Recompile with -DMICROSTRAIN_ENABLE_SERIAL=1.\n"); #endif //MICROSTRAIN_ENABLE_SERIAL From 839d46d98fa3a66450debcc775cb4b1c8488204f Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 2 Aug 2024 11:49:22 -0400 Subject: [PATCH 063/147] Fix metadata and cpp build detection. --- CMakeLists.txt | 9 +++++---- examples/CMakeLists.txt | 2 +- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a34600603..5335f212e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -36,11 +36,12 @@ option(MICROSTRAIN_ENABLE_CPP_C_NAMESPACE "Wraps the C api in a C++ namespace to option(MIP_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) -if(NOT DEFINED MIP_ENABLE_METADATA) - include("${MIP_CMAKE_DIR}/check_metadata.cmake") - message("MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") +if("cxx_std_20" IN_LIST CMAKE_CXX_COMPILE_FEATURES) + set(MIP_COMPILER_SUPPORTS_METADATA ON) +else() + set(MIP_COMPILER_SUPPORTS_METADATA OFF) endif() -option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" MIP_COMPILER_SUPPORTS_METADATA) +option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" ${MIP_COMPILER_SUPPORTS_METADATA}) # Build options option(BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index f87620d28..b70873dfe 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -48,7 +48,7 @@ endmacro() # C++ examples need either serial or TCP support if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) - if(NOT MICROSTRAIN_ENABLE_CPP) + if(MICROSTRAIN_ENABLE_CPP) # Generic examples add_mip_example(DeviceInfo "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/device_info.cpp") From 6abc9d69b87bfa6cd8e663ab793878db2c229ae6 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 2 Aug 2024 12:44:21 -0400 Subject: [PATCH 064/147] Undo changing metadata compiler test as it didn't work for g++-9.4. --- CMakeLists.txt | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5335f212e..27d0dfb30 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -36,10 +36,15 @@ option(MICROSTRAIN_ENABLE_CPP_C_NAMESPACE "Wraps the C api in a C++ namespace to option(MIP_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) -if("cxx_std_20" IN_LIST CMAKE_CXX_COMPILE_FEATURES) - set(MIP_COMPILER_SUPPORTS_METADATA ON) -else() - set(MIP_COMPILER_SUPPORTS_METADATA OFF) +# This fails with g++-9.4 as it can't find despite cmake claiming c++20 support. +#if("cxx_std_20" IN_LIST CMAKE_CXX_COMPILE_FEATURES) +# set(MIP_COMPILER_SUPPORTS_METADATA ON) +#else() +# set(MIP_COMPILER_SUPPORTS_METADATA OFF) +#endif() +if(NOT DEFINED MIP_ENABLE_METADATA) + include("${MIP_CMAKE_DIR}/check_metadata.cmake") + message("MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") endif() option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" ${MIP_COMPILER_SUPPORTS_METADATA}) From 321fc0a1b05a4abf2190a3b74739dbb16f8b8caa Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 2 Aug 2024 13:58:19 -0400 Subject: [PATCH 065/147] Try fixing pthreads linking error on g++-9.4. --- examples/CMakeLists.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index b70873dfe..ce9550e27 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -54,6 +54,9 @@ if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) add_mip_example(DeviceInfo "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/device_info.cpp") add_mip_example(WatchImu "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.cpp") add_mip_example(Threads "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/threading.cpp") + if(UNIX) + target_link_libraries(Threads PUBLIC pthread) + endif() if(MIP_ENABLE_METADATA) add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") target_link_libraries(CsvExample PRIVATE mip_metadata) From 238b240e3b91d1613ebe26d46e6accf5a2f205ad Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 5 Aug 2024 11:12:57 -0400 Subject: [PATCH 066/147] Fix CMake rebuilding all definition files for each example. --- src/c/mip/CMakeLists.txt | 2 +- src/cpp/microstrain/common/CMakeLists.txt | 2 +- src/cpp/microstrain/connections/serial/CMakeLists.txt | 1 - src/cpp/mip/CMakeLists.txt | 4 ++-- 4 files changed, 4 insertions(+), 5 deletions(-) diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index 3be509929..8b8c90d52 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -65,7 +65,7 @@ if(MICROSTRAIN_CMAKE_DEBUG) message("C definitions = ${MIPDEF_SOURCES}") endif() -target_sources(mip PUBLIC ${MIPDEF_SOURCES}) +target_sources(mip PRIVATE ${MIPDEF_SOURCES}) #string(REGEX REPLACE "\.h(;|$)" ".hpp\\1" MIPDEF_HPP_SOURCES "${MIPDEF_SOURCES}") #string(REGEX REPLACE "\.c(;|$)" ".cpp\\1" MIPDEF_CPP_SOURCES "${MIPDEF_HPP_SOURCES}") diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index 00989ac67..4f140bae5 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -1,6 +1,6 @@ # microstrain_common is defined by the C api. -target_sources(microstrain_common PUBLIC +target_sources(microstrain_common PRIVATE embedded_time.hpp index.hpp logging.hpp diff --git a/src/cpp/microstrain/connections/serial/CMakeLists.txt b/src/cpp/microstrain/connections/serial/CMakeLists.txt index 2a4aec372..c7b93850f 100644 --- a/src/cpp/microstrain/connections/serial/CMakeLists.txt +++ b/src/cpp/microstrain/connections/serial/CMakeLists.txt @@ -3,7 +3,6 @@ target_sources(microstrain_serial PRIVATE serial_connection.cpp - PUBLIC serial_connection.hpp ../connection.hpp ) diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index 53932d96d..24d37da62 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -1,5 +1,5 @@ -target_sources(mip PUBLIC +target_sources(mip PRIVATE mip.hpp mip_all.hpp mip_cmdqueue.hpp @@ -28,7 +28,7 @@ if(MICROSTRAIN_CMAKE_DEBUG) message("C++ definitions = ${MIPDEF_SOURCES}") endif() -target_sources(mip PUBLIC ${MIPDEF_SOURCES}) +target_sources(mip PRIVATE ${MIPDEF_SOURCES}) if(MIP_ENABLE_METADATA) add_subdirectory(metadata) From 141508d12c1b209936568359efda71e29eee3308 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 5 Aug 2024 11:29:18 -0400 Subject: [PATCH 067/147] Put example utils into a library. --- examples/CMakeLists.txt | 37 +++++++++++++++++++++---------------- 1 file changed, 21 insertions(+), 16 deletions(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index ce9550e27..63c9e786e 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -2,14 +2,14 @@ set(EXAMPLE_DIR "${CMAKE_CURRENT_LIST_DIR}") -set(EXAMPLE_SOURCES +add_library(example_utils "${EXAMPLE_DIR}/example_utils.c" "${EXAMPLE_DIR}/example_utils.h" "${EXAMPLE_DIR}/example_utils.cpp" "${EXAMPLE_DIR}/example_utils.hpp" ) -set(EXAMPLE_LIBS ) +set(EXAMPLE_LIBS example_utils) if(MICROSTRAIN_ENABLE_SERIAL) set(SERIAL_DEFS "MICROSTRAIN_ENABLE_SERIAL") @@ -31,6 +31,11 @@ endif() set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) + +target_compile_definitions(example_utils PUBLIC ${MIP_EXAMPLE_DEFS}) +target_include_directories(example_utils PRIVATE ${SRC_DIR}) + + macro(add_mip_example name sources) add_executable(${name} ${sources}) @@ -51,9 +56,9 @@ if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) if(MICROSTRAIN_ENABLE_CPP) # Generic examples - add_mip_example(DeviceInfo "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/device_info.cpp") - add_mip_example(WatchImu "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.cpp") - add_mip_example(Threads "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/threading.cpp") + add_mip_example(DeviceInfo "${EXAMPLE_DIR}/device_info.cpp") + add_mip_example(WatchImu "${EXAMPLE_DIR}/watch_imu.cpp") + add_mip_example(Threads "${EXAMPLE_DIR}/threading.cpp") if(UNIX) target_link_libraries(Threads PUBLIC pthread) endif() @@ -63,12 +68,12 @@ if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) endif() # Product-specific examples - add_mip_example(GQ7_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") - add_mip_example(CV7_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CV7/CV7_example.cpp") - add_mip_example(CV7_INS_Simple_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_example.cpp") - add_mip_example(CV7_INS_Simple_Ublox_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_ublox_example.cpp") - add_mip_example(CX5_GX5_45_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.cpp") - add_mip_example(CX5_GX5_CV5_15_25_Example "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp") + add_mip_example(GQ7_Example "${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") + add_mip_example(CV7_Example "${EXAMPLE_DIR}/CV7/CV7_example.cpp") + add_mip_example(CV7_INS_Simple_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_example.cpp") + add_mip_example(CV7_INS_Simple_Ublox_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_ublox_example.cpp") + add_mip_example(CX5_GX5_45_Example "${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.cpp") + add_mip_example(CX5_GX5_CV5_15_25_Example "${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp") endif() endif() @@ -76,10 +81,10 @@ endif() # C examples need serial support if(MICROSTRAIN_ENABLE_SERIAL) - add_mip_example(WatchImuC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/watch_imu.c") - add_mip_example(GQ7_ExampleC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/GQ7/GQ7_example.c") - add_mip_example(CV7_ExampleC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CV7/CV7_example.c") - add_mip_example(CX5_GX5_45_ExampleC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.c") - add_mip_example(CX5_GX5_CV5_15_25_ExampleC "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c") + add_mip_example(WatchImuC "${EXAMPLE_DIR}/watch_imu.c") + add_mip_example(GQ7_ExampleC "${EXAMPLE_DIR}/GQ7/GQ7_example.c") + add_mip_example(CV7_ExampleC "${EXAMPLE_DIR}/CV7/CV7_example.c") + add_mip_example(CX5_GX5_45_ExampleC "${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.c") + add_mip_example(CX5_GX5_CV5_15_25_ExampleC "${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c") endif() From 8c3e7652cdaf19cb3e20eb55636551a40db9c899 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 5 Aug 2024 11:40:32 -0400 Subject: [PATCH 068/147] Put example utils into a library (take 2). --- examples/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 63c9e786e..b4207a495 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -34,6 +34,7 @@ set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) target_compile_definitions(example_utils PUBLIC ${MIP_EXAMPLE_DEFS}) target_include_directories(example_utils PRIVATE ${SRC_DIR}) +target_link_libraries(example_utils PUBLIC mip ${EXAMPLE_LIBS}) macro(add_mip_example name sources) From 3f5420fe689d049c7e71780cf3a2ee2e62346afa Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 5 Aug 2024 11:43:09 -0400 Subject: [PATCH 069/147] Put example utils into a library (take 3). --- examples/CMakeLists.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index b4207a495..993472570 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -9,7 +9,7 @@ add_library(example_utils "${EXAMPLE_DIR}/example_utils.hpp" ) -set(EXAMPLE_LIBS example_utils) +set(EXAMPLE_LIBS) if(MICROSTRAIN_ENABLE_SERIAL) set(SERIAL_DEFS "MICROSTRAIN_ENABLE_SERIAL") @@ -36,6 +36,7 @@ target_compile_definitions(example_utils PUBLIC ${MIP_EXAMPLE_DEFS}) target_include_directories(example_utils PRIVATE ${SRC_DIR}) target_link_libraries(example_utils PUBLIC mip ${EXAMPLE_LIBS}) +list(APPEND EXAMPLE_LIBS example_utils) macro(add_mip_example name sources) From 5808a29d9e54f7a75447a574a1e4bfcfdc4327e5 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 16 Aug 2024 18:07:28 -0400 Subject: [PATCH 070/147] Set target_include_directories on each library. --- CMakeLists.txt | 9 ++--- examples/CMakeLists.txt | 4 +-- src/c/microstrain/CMakeLists.txt | 2 ++ src/c/microstrain/common/CMakeLists.txt | 2 +- .../connections/serial/CMakeLists.txt | 2 ++ .../connections/tcp/CMakeLists.txt | 2 ++ src/c/mip/CMakeLists.txt | 22 ++---------- src/cpp/microstrain/CMakeLists.txt | 2 ++ src/cpp/microstrain/common/CMakeLists.txt | 2 ++ .../connections/recording/CMakeLists.txt | 2 ++ .../connections/serial/CMakeLists.txt | 2 ++ .../connections/tcp/CMakeLists.txt | 2 ++ src/cpp/microstrain/extras/CMakeLists.txt | 2 ++ src/cpp/mip/CMakeLists.txt | 4 +++ src/cpp/mip/extras/CMakeLists.txt | 2 ++ src/cpp/mip/metadata/CMakeLists.txt | 34 +++++++++++++------ 16 files changed, 58 insertions(+), 37 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 27d0dfb30..f32a7fe14 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -113,10 +113,10 @@ configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) # Suppress warnings due to adding files with target_sources. cmake_policy(SET CMP0076 NEW) -include_directories(src/c) -if(MICROSTRAIN_ENABLE_CPP) - include_directories(src/cpp) -endif() +#include_directories(src/c) +#if(MICROSTRAIN_ENABLE_CPP) +# include_directories(src/cpp) +#endif() # Add all the C files (required even for C++ API) add_subdirectory(src/c/microstrain) @@ -132,6 +132,7 @@ if(MICROSTRAIN_ENABLE_CPP) endif() + if(MIP_ENABLE_EXTRAS) list(APPEND MIP_DEFINES "MIP_ENABLE_EXTRAS") set(MIP_EXTRAS_DIR "${MIP_DIR}/extras") diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 993472570..a403e3ea5 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -33,7 +33,7 @@ set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) target_compile_definitions(example_utils PUBLIC ${MIP_EXAMPLE_DEFS}) -target_include_directories(example_utils PRIVATE ${SRC_DIR}) +#target_include_directories(example_utils PRIVATE ${SRC_DIR}) target_link_libraries(example_utils PUBLIC mip ${EXAMPLE_LIBS}) list(APPEND EXAMPLE_LIBS example_utils) @@ -48,7 +48,7 @@ macro(add_mip_example name sources) endif() target_link_libraries(${name} PUBLIC mip ${EXAMPLE_LIBS}) target_compile_definitions(${name} PUBLIC ${MIP_EXAMPLE_DEFS}) - target_include_directories(${name} PRIVATE ${SRC_DIR} ${EXAMPLE_DIR}) + target_include_directories(${name} PRIVATE ${EXAMPLE_DIR}) endmacro() diff --git a/src/c/microstrain/CMakeLists.txt b/src/c/microstrain/CMakeLists.txt index e501bfb7a..8fc14a7be 100644 --- a/src/c/microstrain/CMakeLists.txt +++ b/src/c/microstrain/CMakeLists.txt @@ -1,3 +1,5 @@ +set(MICROSTRAIN_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") + add_subdirectory(common) add_subdirectory(connections) diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index 52e7caf5e..cfa8901b6 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -26,4 +26,4 @@ if(MICROSTRAIN_ENABLE_LOGGING) target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") # TODO rename endif() -#target_include_directories(microstrain_common PUBLIC ${CMAKE_CURRENT_LIST_DIR}) +target_include_directories(microstrain_common INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) diff --git a/src/c/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt index e3c35a932..cb2926e35 100644 --- a/src/c/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -7,4 +7,6 @@ set(SOURCES add_library(microstrain_serial ${SOURCES}) target_compile_features(microstrain_serial PUBLIC c_std_11) +target_include_directories(microstrain_serial INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) + target_link_libraries(microstrain_serial PUBLIC microstrain_common) diff --git a/src/c/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt index 747eabc27..b9721f3da 100644 --- a/src/c/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -7,6 +7,8 @@ set(SOURCES add_library(microstrain_socket ${SOURCES}) target_compile_features(microstrain_socket PUBLIC c_std_11) +target_include_directories(microstrain_socket INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) + target_link_libraries(microstrain_socket PUBLIC microstrain_common) if(WIN32) diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index 8b8c90d52..54774a823 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -2,6 +2,7 @@ #option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) +set(MIP_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") set(MIP_SOURCES "${VERSION_OUT_FILE}" @@ -35,6 +36,7 @@ set(MIP_SOURCES add_library(mip ${MIP_SOURCES}) target_compile_features(mip PUBLIC c_std_11) +target_include_directories(mip INTERFACE ${MIP_INCLUDE_DIR}) set(MIPDEFS commands_3dm @@ -49,9 +51,9 @@ set(MIPDEFS data_sensor data_shared data_system -# ${INTDEF_SOURCES} # Todo ) +# Set this list as a target property so the C++ version can access it. set_target_properties(mip PROPERTIES definitions "${MIPDEFS}") set(MIPDEF_HEADERS ${MIPDEFS}) @@ -67,24 +69,6 @@ endif() target_sources(mip PRIVATE ${MIPDEF_SOURCES}) -#string(REGEX REPLACE "\.h(;|$)" ".hpp\\1" MIPDEF_HPP_SOURCES "${MIPDEF_SOURCES}") -#string(REGEX REPLACE "\.c(;|$)" ".cpp\\1" MIPDEF_CPP_SOURCES "${MIPDEF_HPP_SOURCES}") -# -#set(ALL_MIP_SOURCES -# ${MIPDEF_SOURCES} -# ${MIPDEF_CPP_SOURCES} -# ${MIP_SOURCES_C} -# ${MIP_SOURCES_CPP} -# ${UTILS_SOURCES} -# ${MIP_CPP_HEADERS} -# ${MIP_INTERFACE_SOURCES} -# ${MIP_EXTRA_SOURCES} -#) -# -#if(MIP_DISABLE_CPP) -# list(FILTER ALL_MIP_SOURCES EXCLUDE REGEX "[c|h]pp$") -#endif() -# if(${MIP_ENABLE_DIAGNOSTICS}) diff --git a/src/cpp/microstrain/CMakeLists.txt b/src/cpp/microstrain/CMakeLists.txt index 8b19364e5..837c329eb 100644 --- a/src/cpp/microstrain/CMakeLists.txt +++ b/src/cpp/microstrain/CMakeLists.txt @@ -1,4 +1,6 @@ +set(MICROSTRAIN_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") + add_subdirectory(common) add_subdirectory(connections) add_subdirectory(extras) diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index 4f140bae5..72ce5bde6 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -11,3 +11,5 @@ target_sources(microstrain_common PRIVATE ) target_compile_features(microstrain_common PUBLIC cxx_std_11) +target_include_directories(microstrain_common INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) + diff --git a/src/cpp/microstrain/connections/recording/CMakeLists.txt b/src/cpp/microstrain/connections/recording/CMakeLists.txt index 006fa7a77..78edfccc3 100644 --- a/src/cpp/microstrain/connections/recording/CMakeLists.txt +++ b/src/cpp/microstrain/connections/recording/CMakeLists.txt @@ -9,3 +9,5 @@ add_library(microstrain_recording_connection target_link_libraries(microstrain_recording_connection PUBLIC microstrain_common) target_compile_features(microstrain_recording_connection PUBLIC cxx_std_11) +target_include_directories(microstrain_recording_connection INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) + diff --git a/src/cpp/microstrain/connections/serial/CMakeLists.txt b/src/cpp/microstrain/connections/serial/CMakeLists.txt index c7b93850f..94dca37c2 100644 --- a/src/cpp/microstrain/connections/serial/CMakeLists.txt +++ b/src/cpp/microstrain/connections/serial/CMakeLists.txt @@ -8,3 +8,5 @@ target_sources(microstrain_serial ) target_compile_features(microstrain_serial PUBLIC cxx_std_11) +target_include_directories(microstrain_serial INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) + diff --git a/src/cpp/microstrain/connections/tcp/CMakeLists.txt b/src/cpp/microstrain/connections/tcp/CMakeLists.txt index d4b8c64c5..8f37ddf0c 100644 --- a/src/cpp/microstrain/connections/tcp/CMakeLists.txt +++ b/src/cpp/microstrain/connections/tcp/CMakeLists.txt @@ -9,3 +9,5 @@ target_sources(microstrain_socket ) target_compile_features(microstrain_socket PUBLIC cxx_std_11) +target_include_directories(microstrain_socket INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) + diff --git a/src/cpp/microstrain/extras/CMakeLists.txt b/src/cpp/microstrain/extras/CMakeLists.txt index 402dd515a..2e2fce7b0 100644 --- a/src/cpp/microstrain/extras/CMakeLists.txt +++ b/src/cpp/microstrain/extras/CMakeLists.txt @@ -6,3 +6,5 @@ set(SOURCES add_library(microstrain_extras ${SOURCES}) target_compile_features(microstrain_extras PUBLIC cxx_std_11) +target_include_directories(microstrain_extras INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) + diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index 24d37da62..a711bef3a 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -1,4 +1,6 @@ +set(MIP_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") + target_sources(mip PRIVATE mip.hpp mip_all.hpp @@ -14,7 +16,9 @@ target_sources(mip PRIVATE ) target_compile_features(mip PUBLIC cxx_std_11) +target_include_directories(mip INTERFACE ${MIP_INCLUDE_DIR}) +# Get the mipdef list from the C version get_target_property(MIPDEFS mip definitions) set(MIPDEF_HEADERS ${MIPDEFS}) diff --git a/src/cpp/mip/extras/CMakeLists.txt b/src/cpp/mip/extras/CMakeLists.txt index 903208018..1e43049ca 100644 --- a/src/cpp/mip/extras/CMakeLists.txt +++ b/src/cpp/mip/extras/CMakeLists.txt @@ -8,3 +8,5 @@ set(SOURCES add_library(mip_extras ${SOURCES}) target_compile_features(mip_extras PUBLIC cxx_std_11) +target_include_directories(mip_extras INTERFACE ${MIP_INCLUDE_DIR}) + diff --git a/src/cpp/mip/metadata/CMakeLists.txt b/src/cpp/mip/metadata/CMakeLists.txt index d74b8d7b2..59941d7e8 100644 --- a/src/cpp/mip/metadata/CMakeLists.txt +++ b/src/cpp/mip/metadata/CMakeLists.txt @@ -1,17 +1,29 @@ set(META_SOURCES - mip_all_definitions.hpp - mip_definitions.hpp - mip_definitions.cpp - mip_metadata.hpp - mip_structures.hpp - mip_meta_utils.hpp - definitions/commands_base.hpp - definitions/commands_3dm.hpp - definitions/data_sensor.hpp - definitions/common.hpp + "mip_all_definitions.hpp" + "mip_definitions.hpp" + "mip_definitions.cpp" + "mip_metadata.hpp" + "mip_structures.hpp" + "mip_meta_utils.hpp" ) -add_library(mip_metadata ${META_SOURCES}) +# Get the mipdef list from the C version +get_target_property(MIPDEFS mip definitions) + +set(MIPDEF_HEADERS ${MIPDEFS}) +list(TRANSFORM MIPDEF_HEADERS APPEND ".hpp") +list(TRANSFORM MIPDEF_HEADERS PREPEND "definitions/") + +if(MICROSTRAIN_CMAKE_DEBUG) + message("C++ metadata definitions = ${MIPDEF_HEADERS}") +endif() + +add_library(mip_metadata ${META_SOURCES} ${MIPDEF_HEADERS}) + target_compile_features(mip_metadata PUBLIC cxx_std_20) + +target_include_directories(mip_metadata INTERFACE ${MIP_INCLUDE_DIR}) + +target_link_libraries(mip_metadata PUBLIC mip) From ffa12a6334cd7ab576a175c0496f057ddb09154c Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 10:00:00 -0400 Subject: [PATCH 071/147] Add missing definitions for response serialization. --- src/c/mip/definitions/commands_3dm.c | 682 ++++++++++++++++++++ src/c/mip/definitions/commands_3dm.h | 6 +- src/c/mip/definitions/commands_aiding.c | 152 +++-- src/c/mip/definitions/commands_aiding.h | 277 ++++---- src/c/mip/definitions/commands_base.c | 15 + src/c/mip/definitions/commands_base.h | 2 +- src/c/mip/definitions/commands_filter.c | 646 ++++++++++++++++++ src/c/mip/definitions/commands_filter.h | 14 +- src/c/mip/definitions/commands_gnss.c | 46 ++ src/c/mip/definitions/commands_gnss.h | 2 +- src/c/mip/definitions/commands_rtk.c | 34 + src/c/mip/definitions/commands_rtk.h | 2 +- src/c/mip/definitions/commands_system.c | 11 + src/c/mip/definitions/commands_system.h | 2 +- src/c/mip/definitions/data_filter.h | 29 +- src/c/mip/definitions/data_gnss.h | 2 +- src/c/mip/definitions/data_sensor.h | 2 +- src/c/mip/definitions/data_shared.h | 2 +- src/c/mip/definitions/data_system.h | 2 +- src/cpp/mip/definitions/commands_3dm.cpp | 682 ++++++++++++++++++++ src/cpp/mip/definitions/commands_3dm.hpp | 26 +- src/cpp/mip/definitions/commands_aiding.cpp | 62 +- src/cpp/mip/definitions/commands_aiding.hpp | 183 +++--- src/cpp/mip/definitions/commands_base.cpp | 284 +------- src/cpp/mip/definitions/commands_base.hpp | 56 +- src/cpp/mip/definitions/commands_filter.hpp | 42 +- src/cpp/mip/definitions/commands_gnss.hpp | 2 +- src/cpp/mip/definitions/commands_rtk.hpp | 54 +- src/cpp/mip/definitions/commands_system.hpp | 2 +- src/cpp/mip/definitions/data_filter.hpp | 135 +--- src/cpp/mip/definitions/data_gnss.hpp | 338 +--------- src/cpp/mip/definitions/data_sensor.hpp | 32 +- src/cpp/mip/definitions/data_shared.hpp | 12 +- src/cpp/mip/definitions/data_system.hpp | 2 +- 34 files changed, 2529 insertions(+), 1311 deletions(-) diff --git a/src/c/mip/definitions/commands_3dm.c b/src/c/mip/definitions/commands_3dm.c index cf7b15ce1..a9cc6d9a5 100644 --- a/src/c/mip/definitions/commands_3dm.c +++ b/src/c/mip/definitions/commands_3dm.c @@ -194,6 +194,25 @@ void extract_mip_3dm_imu_message_format_command(microstrain_serializer* serializ } } +void insert_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, const mip_3dm_imu_message_format_response* self) +{ + microstrain_insert_u8(serializer, self->num_descriptors); + + + for(unsigned int i=0; i < self->num_descriptors; i++) + insert_mip_descriptor_rate(serializer, &self->descriptors[i]); + +} +void extract_mip_3dm_imu_message_format_response(microstrain_serializer* serializer, mip_3dm_imu_message_format_response* self) +{ + assert(self->num_descriptors); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + + for(unsigned int i=0; i < self->num_descriptors; i++) + extract_mip_descriptor_rate(serializer, &self->descriptors[i]); + +} + mip_cmd_result mip_3dm_write_imu_message_format(mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; @@ -307,6 +326,25 @@ void extract_mip_3dm_gps_message_format_command(microstrain_serializer* serializ } } +void insert_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, const mip_3dm_gps_message_format_response* self) +{ + microstrain_insert_u8(serializer, self->num_descriptors); + + + for(unsigned int i=0; i < self->num_descriptors; i++) + insert_mip_descriptor_rate(serializer, &self->descriptors[i]); + +} +void extract_mip_3dm_gps_message_format_response(microstrain_serializer* serializer, mip_3dm_gps_message_format_response* self) +{ + assert(self->num_descriptors); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + + for(unsigned int i=0; i < self->num_descriptors; i++) + extract_mip_descriptor_rate(serializer, &self->descriptors[i]); + +} + mip_cmd_result mip_3dm_write_gps_message_format(mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; @@ -420,6 +458,25 @@ void extract_mip_3dm_filter_message_format_command(microstrain_serializer* seria } } +void insert_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, const mip_3dm_filter_message_format_response* self) +{ + microstrain_insert_u8(serializer, self->num_descriptors); + + + for(unsigned int i=0; i < self->num_descriptors; i++) + insert_mip_descriptor_rate(serializer, &self->descriptors[i]); + +} +void extract_mip_3dm_filter_message_format_response(microstrain_serializer* serializer, mip_3dm_filter_message_format_response* self) +{ + assert(self->num_descriptors); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + + for(unsigned int i=0; i < self->num_descriptors; i++) + extract_mip_descriptor_rate(serializer, &self->descriptors[i]); + +} + mip_cmd_result mip_3dm_write_filter_message_format(mip_interface* device, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; @@ -622,6 +679,21 @@ void extract_mip_3dm_get_base_rate_command(microstrain_serializer* serializer, m } +void insert_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, const mip_3dm_get_base_rate_response* self) +{ + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u16(serializer, self->rate); + +} +void extract_mip_3dm_get_base_rate_response(microstrain_serializer* serializer, mip_3dm_get_base_rate_response* self) +{ + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_u16(serializer, &self->rate); + +} + mip_cmd_result mip_3dm_get_base_rate(mip_interface* device, uint8_t desc_set, uint16_t* rate_out) { microstrain_serializer serializer; @@ -683,6 +755,29 @@ void extract_mip_3dm_message_format_command(microstrain_serializer* serializer, } } +void insert_mip_3dm_message_format_response(microstrain_serializer* serializer, const mip_3dm_message_format_response* self) +{ + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u8(serializer, self->num_descriptors); + + + for(unsigned int i=0; i < self->num_descriptors; i++) + insert_mip_descriptor_rate(serializer, &self->descriptors[i]); + +} +void extract_mip_3dm_message_format_response(microstrain_serializer* serializer, mip_3dm_message_format_response* self) +{ + microstrain_extract_u8(serializer, &self->desc_set); + + assert(self->num_descriptors); + microstrain_extract_count(serializer, &self->num_descriptors, sizeof(self->descriptors)/sizeof(self->descriptors[0])); + + for(unsigned int i=0; i < self->num_descriptors; i++) + extract_mip_descriptor_rate(serializer, &self->descriptors[i]); + +} + mip_cmd_result mip_3dm_write_message_format(mip_interface* device, uint8_t desc_set, uint8_t num_descriptors, const mip_descriptor_rate* descriptors) { microstrain_serializer serializer; @@ -849,6 +944,25 @@ void extract_mip_3dm_nmea_message_format_command(microstrain_serializer* seriali } } +void insert_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, const mip_3dm_nmea_message_format_response* self) +{ + microstrain_insert_u8(serializer, self->count); + + + for(unsigned int i=0; i < self->count; i++) + insert_mip_nmea_message(serializer, &self->format_entries[i]); + +} +void extract_mip_3dm_nmea_message_format_response(microstrain_serializer* serializer, mip_3dm_nmea_message_format_response* self) +{ + assert(self->count); + microstrain_extract_count(serializer, &self->count, sizeof(self->format_entries)/sizeof(self->format_entries[0])); + + for(unsigned int i=0; i < self->count; i++) + extract_mip_nmea_message(serializer, &self->format_entries[i]); + +} + mip_cmd_result mip_3dm_write_nmea_message_format(mip_interface* device, uint8_t count, const mip_nmea_message* format_entries) { microstrain_serializer serializer; @@ -1001,6 +1115,17 @@ void extract_mip_3dm_uart_baudrate_command(microstrain_serializer* serializer, m } } +void insert_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, const mip_3dm_uart_baudrate_response* self) +{ + microstrain_insert_u32(serializer, self->baud); + +} +void extract_mip_3dm_uart_baudrate_response(microstrain_serializer* serializer, mip_3dm_uart_baudrate_response* self) +{ + microstrain_extract_u32(serializer, &self->baud); + +} + mip_cmd_result mip_3dm_write_uart_baudrate(mip_interface* device, uint32_t baud) { microstrain_serializer serializer; @@ -1131,6 +1256,21 @@ void extract_mip_3dm_datastream_control_command(microstrain_serializer* serializ } } +void insert_mip_3dm_datastream_control_response(microstrain_serializer* serializer, const mip_3dm_datastream_control_response* self) +{ + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_bool(serializer, self->enabled); + +} +void extract_mip_3dm_datastream_control_response(microstrain_serializer* serializer, mip_3dm_datastream_control_response* self) +{ + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_bool(serializer, &self->enabled); + +} + mip_cmd_result mip_3dm_write_datastream_control(mip_interface* device, uint8_t desc_set, bool enable) { microstrain_serializer serializer; @@ -1279,6 +1419,33 @@ void extract_mip_3dm_constellation_settings_command(microstrain_serializer* seri } } +void insert_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, const mip_3dm_constellation_settings_response* self) +{ + microstrain_insert_u16(serializer, self->max_channels_available); + + microstrain_insert_u16(serializer, self->max_channels_use); + + microstrain_insert_u8(serializer, self->config_count); + + + for(unsigned int i=0; i < self->config_count; i++) + insert_mip_3dm_constellation_settings_command_settings(serializer, &self->settings[i]); + +} +void extract_mip_3dm_constellation_settings_response(microstrain_serializer* serializer, mip_3dm_constellation_settings_response* self) +{ + microstrain_extract_u16(serializer, &self->max_channels_available); + + microstrain_extract_u16(serializer, &self->max_channels_use); + + assert(self->config_count); + microstrain_extract_count(serializer, &self->config_count, sizeof(self->settings)/sizeof(self->settings[0])); + + for(unsigned int i=0; i < self->config_count; i++) + extract_mip_3dm_constellation_settings_command_settings(serializer, &self->settings[i]); + +} + mip_cmd_result mip_3dm_write_constellation_settings(mip_interface* device, uint16_t max_channels, uint8_t config_count, const mip_3dm_constellation_settings_command_settings* settings) { microstrain_serializer serializer; @@ -1408,6 +1575,33 @@ void extract_mip_3dm_gnss_sbas_settings_command(microstrain_serializer* serializ } } +void insert_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, const mip_3dm_gnss_sbas_settings_response* self) +{ + microstrain_insert_u8(serializer, self->enable_sbas); + + insert_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, self->sbas_options); + + microstrain_insert_u8(serializer, self->num_included_prns); + + + for(unsigned int i=0; i < self->num_included_prns; i++) + microstrain_insert_u16(serializer, self->included_prns[i]); + +} +void extract_mip_3dm_gnss_sbas_settings_response(microstrain_serializer* serializer, mip_3dm_gnss_sbas_settings_response* self) +{ + microstrain_extract_u8(serializer, &self->enable_sbas); + + extract_mip_3dm_gnss_sbas_settings_command_sbasoptions(serializer, &self->sbas_options); + + assert(self->num_included_prns); + microstrain_extract_count(serializer, &self->num_included_prns, sizeof(self->included_prns)/sizeof(self->included_prns[0])); + + for(unsigned int i=0; i < self->num_included_prns; i++) + microstrain_extract_u16(serializer, &self->included_prns[i]); + +} + mip_cmd_result mip_3dm_write_gnss_sbas_settings(mip_interface* device, uint8_t enable_sbas, mip_3dm_gnss_sbas_settings_command_sbasoptions sbas_options, uint8_t num_included_prns, const uint16_t* included_prns) { microstrain_serializer serializer; @@ -1527,6 +1721,21 @@ void extract_mip_3dm_gnss_assisted_fix_command(microstrain_serializer* serialize } } +void insert_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, const mip_3dm_gnss_assisted_fix_response* self) +{ + insert_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, self->option); + + microstrain_insert_u8(serializer, self->flags); + +} +void extract_mip_3dm_gnss_assisted_fix_response(microstrain_serializer* serializer, mip_3dm_gnss_assisted_fix_response* self) +{ + extract_mip_3dm_gnss_assisted_fix_command_assisted_fix_option(serializer, &self->option); + + microstrain_extract_u8(serializer, &self->flags); + +} + mip_cmd_result mip_3dm_write_gnss_assisted_fix(mip_interface* device, mip_3dm_gnss_assisted_fix_command_assisted_fix_option option, uint8_t flags) { microstrain_serializer serializer; @@ -1637,6 +1846,25 @@ void extract_mip_3dm_gnss_time_assistance_command(microstrain_serializer* serial } } +void insert_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, const mip_3dm_gnss_time_assistance_response* self) +{ + microstrain_insert_double(serializer, self->tow); + + microstrain_insert_u16(serializer, self->week_number); + + microstrain_insert_float(serializer, self->accuracy); + +} +void extract_mip_3dm_gnss_time_assistance_response(microstrain_serializer* serializer, mip_3dm_gnss_time_assistance_response* self) +{ + microstrain_extract_double(serializer, &self->tow); + + microstrain_extract_u16(serializer, &self->week_number); + + microstrain_extract_float(serializer, &self->accuracy); + +} + mip_cmd_result mip_3dm_write_gnss_time_assistance(mip_interface* device, double tow, uint16_t week_number, float accuracy) { microstrain_serializer serializer; @@ -1724,6 +1952,33 @@ void extract_mip_3dm_imu_lowpass_filter_command(microstrain_serializer* serializ } } +void insert_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_imu_lowpass_filter_response* self) +{ + microstrain_insert_u8(serializer, self->target_descriptor); + + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_bool(serializer, self->manual); + + microstrain_insert_u16(serializer, self->frequency); + + microstrain_insert_u8(serializer, self->reserved); + +} +void extract_mip_3dm_imu_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_imu_lowpass_filter_response* self) +{ + microstrain_extract_u8(serializer, &self->target_descriptor); + + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_bool(serializer, &self->manual); + + microstrain_extract_u16(serializer, &self->frequency); + + microstrain_extract_u8(serializer, &self->reserved); + +} + mip_cmd_result mip_3dm_write_imu_lowpass_filter(mip_interface* device, uint8_t target_descriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { microstrain_serializer serializer; @@ -1848,6 +2103,17 @@ void extract_mip_3dm_pps_source_command(microstrain_serializer* serializer, mip_ } } +void insert_mip_3dm_pps_source_response(microstrain_serializer* serializer, const mip_3dm_pps_source_response* self) +{ + insert_mip_3dm_pps_source_command_source(serializer, self->source); + +} +void extract_mip_3dm_pps_source_response(microstrain_serializer* serializer, mip_3dm_pps_source_response* self) +{ + extract_mip_3dm_pps_source_command_source(serializer, &self->source); + +} + mip_cmd_result mip_3dm_write_pps_source(mip_interface* device, mip_3dm_pps_source_command_source source) { microstrain_serializer serializer; @@ -1957,6 +2223,29 @@ void extract_mip_3dm_gpio_config_command(microstrain_serializer* serializer, mip } } +void insert_mip_3dm_gpio_config_response(microstrain_serializer* serializer, const mip_3dm_gpio_config_response* self) +{ + microstrain_insert_u8(serializer, self->pin); + + insert_mip_3dm_gpio_config_command_feature(serializer, self->feature); + + insert_mip_3dm_gpio_config_command_behavior(serializer, self->behavior); + + insert_mip_3dm_gpio_config_command_pin_mode(serializer, self->pin_mode); + +} +void extract_mip_3dm_gpio_config_response(microstrain_serializer* serializer, mip_3dm_gpio_config_response* self) +{ + microstrain_extract_u8(serializer, &self->pin); + + extract_mip_3dm_gpio_config_command_feature(serializer, &self->feature); + + extract_mip_3dm_gpio_config_command_behavior(serializer, &self->behavior); + + extract_mip_3dm_gpio_config_command_pin_mode(serializer, &self->pin_mode); + +} + mip_cmd_result mip_3dm_write_gpio_config(mip_interface* device, uint8_t pin, mip_3dm_gpio_config_command_feature feature, mip_3dm_gpio_config_command_behavior behavior, mip_3dm_gpio_config_command_pin_mode pin_mode) { microstrain_serializer serializer; @@ -2086,6 +2375,21 @@ void extract_mip_3dm_gpio_state_command(microstrain_serializer* serializer, mip_ } } +void insert_mip_3dm_gpio_state_response(microstrain_serializer* serializer, const mip_3dm_gpio_state_response* self) +{ + microstrain_insert_u8(serializer, self->pin); + + microstrain_insert_bool(serializer, self->state); + +} +void extract_mip_3dm_gpio_state_response(microstrain_serializer* serializer, mip_3dm_gpio_state_response* self) +{ + microstrain_extract_u8(serializer, &self->pin); + + microstrain_extract_bool(serializer, &self->state); + +} + mip_cmd_result mip_3dm_write_gpio_state(mip_interface* device, uint8_t pin, bool state) { microstrain_serializer serializer; @@ -2161,6 +2465,25 @@ void extract_mip_3dm_odometer_command(microstrain_serializer* serializer, mip_3d } } +void insert_mip_3dm_odometer_response(microstrain_serializer* serializer, const mip_3dm_odometer_response* self) +{ + insert_mip_3dm_odometer_command_mode(serializer, self->mode); + + microstrain_insert_float(serializer, self->scaling); + + microstrain_insert_float(serializer, self->uncertainty); + +} +void extract_mip_3dm_odometer_response(microstrain_serializer* serializer, mip_3dm_odometer_response* self) +{ + extract_mip_3dm_odometer_command_mode(serializer, &self->mode); + + microstrain_extract_float(serializer, &self->scaling); + + microstrain_extract_float(serializer, &self->uncertainty); + +} + mip_cmd_result mip_3dm_write_odometer(mip_interface* device, mip_3dm_odometer_command_mode mode, float scaling, float uncertainty) { microstrain_serializer serializer; @@ -2273,6 +2596,33 @@ void extract_mip_3dm_get_event_support_command(microstrain_serializer* serialize } +void insert_mip_3dm_get_event_support_response(microstrain_serializer* serializer, const mip_3dm_get_event_support_response* self) +{ + insert_mip_3dm_get_event_support_command_query(serializer, self->query); + + microstrain_insert_u8(serializer, self->max_instances); + + microstrain_insert_u8(serializer, self->num_entries); + + + for(unsigned int i=0; i < self->num_entries; i++) + insert_mip_3dm_get_event_support_command_info(serializer, &self->entries[i]); + +} +void extract_mip_3dm_get_event_support_response(microstrain_serializer* serializer, mip_3dm_get_event_support_response* self) +{ + extract_mip_3dm_get_event_support_command_query(serializer, &self->query); + + microstrain_extract_u8(serializer, &self->max_instances); + + assert(self->num_entries); + microstrain_extract_count(serializer, &self->num_entries, sizeof(self->entries)/sizeof(self->entries[0])); + + for(unsigned int i=0; i < self->num_entries; i++) + extract_mip_3dm_get_event_support_command_info(serializer, &self->entries[i]); + +} + mip_cmd_result mip_3dm_get_event_support(mip_interface* device, mip_3dm_get_event_support_command_query query, uint8_t* max_instances_out, uint8_t* num_entries_out, uint8_t num_entries_out_max, mip_3dm_get_event_support_command_info* entries_out) { microstrain_serializer serializer; @@ -2333,6 +2683,21 @@ void extract_mip_3dm_event_control_command(microstrain_serializer* serializer, m } } +void insert_mip_3dm_event_control_response(microstrain_serializer* serializer, const mip_3dm_event_control_response* self) +{ + microstrain_insert_u8(serializer, self->instance); + + insert_mip_3dm_event_control_command_mode(serializer, self->mode); + +} +void extract_mip_3dm_event_control_response(microstrain_serializer* serializer, mip_3dm_event_control_response* self) +{ + microstrain_extract_u8(serializer, &self->instance); + + extract_mip_3dm_event_control_command_mode(serializer, &self->mode); + +} + mip_cmd_result mip_3dm_write_event_control(mip_interface* device, uint8_t instance, mip_3dm_event_control_command_mode mode) { microstrain_serializer serializer; @@ -2455,6 +2820,25 @@ void extract_mip_3dm_get_event_trigger_status_command(microstrain_serializer* se } +void insert_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_trigger_status_response* self) +{ + microstrain_insert_u8(serializer, self->count); + + + for(unsigned int i=0; i < self->count; i++) + insert_mip_3dm_get_event_trigger_status_command_entry(serializer, &self->triggers[i]); + +} +void extract_mip_3dm_get_event_trigger_status_response(microstrain_serializer* serializer, mip_3dm_get_event_trigger_status_response* self) +{ + assert(self->count); + microstrain_extract_count(serializer, &self->count, sizeof(self->triggers)/sizeof(self->triggers[0])); + + for(unsigned int i=0; i < self->count; i++) + extract_mip_3dm_get_event_trigger_status_command_entry(serializer, &self->triggers[i]); + +} + mip_cmd_result mip_3dm_get_event_trigger_status(mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_trigger_status_command_entry* triggers_out) { microstrain_serializer serializer; @@ -2523,6 +2907,25 @@ void extract_mip_3dm_get_event_action_status_command(microstrain_serializer* ser } +void insert_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, const mip_3dm_get_event_action_status_response* self) +{ + microstrain_insert_u8(serializer, self->count); + + + for(unsigned int i=0; i < self->count; i++) + insert_mip_3dm_get_event_action_status_command_entry(serializer, &self->actions[i]); + +} +void extract_mip_3dm_get_event_action_status_response(microstrain_serializer* serializer, mip_3dm_get_event_action_status_response* self) +{ + assert(self->count); + microstrain_extract_count(serializer, &self->count, sizeof(self->actions)/sizeof(self->actions[0])); + + for(unsigned int i=0; i < self->count; i++) + extract_mip_3dm_get_event_action_status_command_entry(serializer, &self->actions[i]); + +} + mip_cmd_result mip_3dm_get_event_action_status(mip_interface* device, uint8_t requested_count, const uint8_t* requested_instances, uint8_t* count_out, uint8_t count_out_max, mip_3dm_get_event_action_status_command_entry* actions_out) { microstrain_serializer serializer; @@ -2707,6 +3110,51 @@ void extract_mip_3dm_event_trigger_command(microstrain_serializer* serializer, m } } +void insert_mip_3dm_event_trigger_response(microstrain_serializer* serializer, const mip_3dm_event_trigger_response* self) +{ + microstrain_insert_u8(serializer, self->instance); + + insert_mip_3dm_event_trigger_command_type(serializer, self->type); + + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_GPIO ) + { + insert_mip_3dm_event_trigger_command_gpio_params(serializer, &self->parameters.gpio); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_THRESHOLD ) + { + insert_mip_3dm_event_trigger_command_threshold_params(serializer, &self->parameters.threshold); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_COMBINATION ) + { + insert_mip_3dm_event_trigger_command_combination_params(serializer, &self->parameters.combination); + + } +} +void extract_mip_3dm_event_trigger_response(microstrain_serializer* serializer, mip_3dm_event_trigger_response* self) +{ + microstrain_extract_u8(serializer, &self->instance); + + extract_mip_3dm_event_trigger_command_type(serializer, &self->type); + + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_GPIO ) + { + extract_mip_3dm_event_trigger_command_gpio_params(serializer, &self->parameters.gpio); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_THRESHOLD ) + { + extract_mip_3dm_event_trigger_command_threshold_params(serializer, &self->parameters.threshold); + + } + if( self->type == MIP_3DM_EVENT_TRIGGER_COMMAND_TYPE_COMBINATION ) + { + extract_mip_3dm_event_trigger_command_combination_params(serializer, &self->parameters.combination); + + } +} + mip_cmd_result mip_3dm_write_event_trigger(mip_interface* device, uint8_t instance, mip_3dm_event_trigger_command_type type, const mip_3dm_event_trigger_command_parameters* parameters) { microstrain_serializer serializer; @@ -2916,6 +3364,45 @@ void extract_mip_3dm_event_action_command(microstrain_serializer* serializer, mi } } +void insert_mip_3dm_event_action_response(microstrain_serializer* serializer, const mip_3dm_event_action_response* self) +{ + microstrain_insert_u8(serializer, self->instance); + + microstrain_insert_u8(serializer, self->trigger); + + insert_mip_3dm_event_action_command_type(serializer, self->type); + + if( self->type == MIP_3DM_EVENT_ACTION_COMMAND_TYPE_GPIO ) + { + insert_mip_3dm_event_action_command_gpio_params(serializer, &self->parameters.gpio); + + } + if( self->type == MIP_3DM_EVENT_ACTION_COMMAND_TYPE_MESSAGE ) + { + insert_mip_3dm_event_action_command_message_params(serializer, &self->parameters.message); + + } +} +void extract_mip_3dm_event_action_response(microstrain_serializer* serializer, mip_3dm_event_action_response* self) +{ + microstrain_extract_u8(serializer, &self->instance); + + microstrain_extract_u8(serializer, &self->trigger); + + extract_mip_3dm_event_action_command_type(serializer, &self->type); + + if( self->type == MIP_3DM_EVENT_ACTION_COMMAND_TYPE_GPIO ) + { + extract_mip_3dm_event_action_command_gpio_params(serializer, &self->parameters.gpio); + + } + if( self->type == MIP_3DM_EVENT_ACTION_COMMAND_TYPE_MESSAGE ) + { + extract_mip_3dm_event_action_command_message_params(serializer, &self->parameters.message); + + } +} + mip_cmd_result mip_3dm_write_event_action(mip_interface* device, uint8_t instance, uint8_t trigger, mip_3dm_event_action_command_type type, const mip_3dm_event_action_command_parameters* parameters) { microstrain_serializer serializer; @@ -3050,6 +3537,17 @@ void extract_mip_3dm_accel_bias_command(microstrain_serializer* serializer, mip_ } } +void insert_mip_3dm_accel_bias_response(microstrain_serializer* serializer, const mip_3dm_accel_bias_response* self) +{ + insert_mip_vector3f(serializer, self->bias); + +} +void extract_mip_3dm_accel_bias_response(microstrain_serializer* serializer, mip_3dm_accel_bias_response* self) +{ + extract_mip_vector3f(serializer, self->bias); + +} + mip_cmd_result mip_3dm_write_accel_bias(mip_interface* device, const float* bias) { microstrain_serializer serializer; @@ -3150,6 +3648,17 @@ void extract_mip_3dm_gyro_bias_command(microstrain_serializer* serializer, mip_3 } } +void insert_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_gyro_bias_response* self) +{ + insert_mip_vector3f(serializer, self->bias); + +} +void extract_mip_3dm_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_gyro_bias_response* self) +{ + extract_mip_vector3f(serializer, self->bias); + +} + mip_cmd_result mip_3dm_write_gyro_bias(mip_interface* device, const float* bias) { microstrain_serializer serializer; @@ -3240,6 +3749,17 @@ void extract_mip_3dm_capture_gyro_bias_command(microstrain_serializer* serialize } +void insert_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, const mip_3dm_capture_gyro_bias_response* self) +{ + insert_mip_vector3f(serializer, self->bias); + +} +void extract_mip_3dm_capture_gyro_bias_response(microstrain_serializer* serializer, mip_3dm_capture_gyro_bias_response* self) +{ + extract_mip_vector3f(serializer, self->bias); + +} + mip_cmd_result mip_3dm_capture_gyro_bias(mip_interface* device, uint16_t averaging_time_ms, float* bias_out) { microstrain_serializer serializer; @@ -3288,6 +3808,17 @@ void extract_mip_3dm_mag_hard_iron_offset_command(microstrain_serializer* serial } } +void insert_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, const mip_3dm_mag_hard_iron_offset_response* self) +{ + insert_mip_vector3f(serializer, self->offset); + +} +void extract_mip_3dm_mag_hard_iron_offset_response(microstrain_serializer* serializer, mip_3dm_mag_hard_iron_offset_response* self) +{ + extract_mip_vector3f(serializer, self->offset); + +} + mip_cmd_result mip_3dm_write_mag_hard_iron_offset(mip_interface* device, const float* offset) { microstrain_serializer serializer; @@ -3388,6 +3919,17 @@ void extract_mip_3dm_mag_soft_iron_matrix_command(microstrain_serializer* serial } } +void insert_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, const mip_3dm_mag_soft_iron_matrix_response* self) +{ + insert_mip_matrix3f(serializer, self->offset); + +} +void extract_mip_3dm_mag_soft_iron_matrix_response(microstrain_serializer* serializer, mip_3dm_mag_soft_iron_matrix_response* self) +{ + extract_mip_matrix3f(serializer, self->offset); + +} + mip_cmd_result mip_3dm_write_mag_soft_iron_matrix(mip_interface* device, const float* offset) { microstrain_serializer serializer; @@ -3488,6 +4030,17 @@ void extract_mip_3dm_coning_sculling_enable_command(microstrain_serializer* seri } } +void insert_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, const mip_3dm_coning_sculling_enable_response* self) +{ + microstrain_insert_bool(serializer, self->enable); + +} +void extract_mip_3dm_coning_sculling_enable_response(microstrain_serializer* serializer, mip_3dm_coning_sculling_enable_response* self) +{ + microstrain_extract_bool(serializer, &self->enable); + +} + mip_cmd_result mip_3dm_write_coning_sculling_enable(mip_interface* device, bool enable) { microstrain_serializer serializer; @@ -3593,6 +4146,25 @@ void extract_mip_3dm_sensor_2_vehicle_transform_euler_command(microstrain_serial } } +void insert_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_euler_response* self) +{ + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->yaw); + +} +void extract_mip_3dm_sensor_2_vehicle_transform_euler_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_euler_response* self) +{ + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->yaw); + +} + mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_euler(mip_interface* device, float roll, float pitch, float yaw) { microstrain_serializer serializer; @@ -3700,6 +4272,17 @@ void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_command(microstrain_s } } +void insert_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) +{ + insert_mip_quatf(serializer, self->q); + +} +void extract_mip_3dm_sensor_2_vehicle_transform_quaternion_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_quaternion_response* self) +{ + extract_mip_quatf(serializer, self->q); + +} + mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_quaternion(mip_interface* device, const float* q) { microstrain_serializer serializer; @@ -3800,6 +4383,17 @@ void extract_mip_3dm_sensor_2_vehicle_transform_dcm_command(microstrain_serializ } } +void insert_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, const mip_3dm_sensor_2_vehicle_transform_dcm_response* self) +{ + insert_mip_matrix3f(serializer, self->dcm); + +} +void extract_mip_3dm_sensor_2_vehicle_transform_dcm_response(microstrain_serializer* serializer, mip_3dm_sensor_2_vehicle_transform_dcm_response* self) +{ + extract_mip_matrix3f(serializer, self->dcm); + +} + mip_cmd_result mip_3dm_write_sensor_2_vehicle_transform_dcm(mip_interface* device, const float* dcm) { microstrain_serializer serializer; @@ -3912,6 +4506,29 @@ void extract_mip_3dm_complementary_filter_command(microstrain_serializer* serial } } +void insert_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, const mip_3dm_complementary_filter_response* self) +{ + microstrain_insert_bool(serializer, self->pitch_roll_enable); + + microstrain_insert_bool(serializer, self->heading_enable); + + microstrain_insert_float(serializer, self->pitch_roll_time_constant); + + microstrain_insert_float(serializer, self->heading_time_constant); + +} +void extract_mip_3dm_complementary_filter_response(microstrain_serializer* serializer, mip_3dm_complementary_filter_response* self) +{ + microstrain_extract_bool(serializer, &self->pitch_roll_enable); + + microstrain_extract_bool(serializer, &self->heading_enable); + + microstrain_extract_float(serializer, &self->pitch_roll_time_constant); + + microstrain_extract_float(serializer, &self->heading_time_constant); + +} + mip_cmd_result mip_3dm_write_complementary_filter(mip_interface* device, bool pitch_roll_enable, bool heading_enable, float pitch_roll_time_constant, float heading_time_constant) { microstrain_serializer serializer; @@ -4028,6 +4645,21 @@ void extract_mip_3dm_sensor_range_command(microstrain_serializer* serializer, mi } } +void insert_mip_3dm_sensor_range_response(microstrain_serializer* serializer, const mip_3dm_sensor_range_response* self) +{ + insert_mip_sensor_range_type(serializer, self->sensor); + + microstrain_insert_u8(serializer, self->setting); + +} +void extract_mip_3dm_sensor_range_response(microstrain_serializer* serializer, mip_3dm_sensor_range_response* self) +{ + extract_mip_sensor_range_type(serializer, &self->sensor); + + microstrain_extract_u8(serializer, &self->setting); + +} + mip_cmd_result mip_3dm_write_sensor_range(mip_interface* device, mip_sensor_range_type sensor, uint8_t setting) { microstrain_serializer serializer; @@ -4142,6 +4774,29 @@ void extract_mip_3dm_calibrated_sensor_ranges_command(microstrain_serializer* se } +void insert_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, const mip_3dm_calibrated_sensor_ranges_response* self) +{ + insert_mip_sensor_range_type(serializer, self->sensor); + + microstrain_insert_u8(serializer, self->num_ranges); + + + for(unsigned int i=0; i < self->num_ranges; i++) + insert_mip_3dm_calibrated_sensor_ranges_command_entry(serializer, &self->ranges[i]); + +} +void extract_mip_3dm_calibrated_sensor_ranges_response(microstrain_serializer* serializer, mip_3dm_calibrated_sensor_ranges_response* self) +{ + extract_mip_sensor_range_type(serializer, &self->sensor); + + assert(self->num_ranges); + microstrain_extract_count(serializer, &self->num_ranges, sizeof(self->ranges)/sizeof(self->ranges[0])); + + for(unsigned int i=0; i < self->num_ranges; i++) + extract_mip_3dm_calibrated_sensor_ranges_command_entry(serializer, &self->ranges[i]); + +} + mip_cmd_result mip_3dm_calibrated_sensor_ranges(mip_interface* device, mip_sensor_range_type sensor, uint8_t* num_ranges_out, uint8_t num_ranges_out_max, mip_3dm_calibrated_sensor_ranges_command_entry* ranges_out) { microstrain_serializer serializer; @@ -4211,6 +4866,33 @@ void extract_mip_3dm_lowpass_filter_command(microstrain_serializer* serializer, } } +void insert_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, const mip_3dm_lowpass_filter_response* self) +{ + microstrain_insert_u8(serializer, self->desc_set); + + microstrain_insert_u8(serializer, self->field_desc); + + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_bool(serializer, self->manual); + + microstrain_insert_float(serializer, self->frequency); + +} +void extract_mip_3dm_lowpass_filter_response(microstrain_serializer* serializer, mip_3dm_lowpass_filter_response* self) +{ + microstrain_extract_u8(serializer, &self->desc_set); + + microstrain_extract_u8(serializer, &self->field_desc); + + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_bool(serializer, &self->manual); + + microstrain_extract_float(serializer, &self->frequency); + +} + mip_cmd_result mip_3dm_write_lowpass_filter(mip_interface* device, uint8_t desc_set, uint8_t field_desc, bool enable, bool manual, float frequency) { microstrain_serializer serializer; diff --git a/src/c/mip/definitions/commands_3dm.h b/src/c/mip/definitions/commands_3dm.h index f13d5e29b..bb94c738a 100644 --- a/src/c/mip/definitions/commands_3dm.h +++ b/src/c/mip/definitions/commands_3dm.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include @@ -152,8 +152,8 @@ enum mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_VTG = 5, ///< Course over Ground. Source can be the Filter or GNSS1/2 datasets. MIP_NMEA_MESSAGE_MESSAGE_ID_HDT = 6, ///< Heading, True. Source can be the Filter or GNSS1/2 datasets. MIP_NMEA_MESSAGE_MESSAGE_ID_ZDA = 7, ///< Time & Date. Source must be the GNSS1 or GNSS2 datasets. - MIP_NMEA_MESSAGE_MESSAGE_ID_MSRA = 129, ///< MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. - MIP_NMEA_MESSAGE_MESSAGE_ID_MSRR = 130, ///< MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. + MIP_NMEA_MESSAGE_MESSAGE_ID_PKRA = 129, ///< Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. + MIP_NMEA_MESSAGE_MESSAGE_ID_PKRR = 130, ///< Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. }; typedef enum mip_nmea_message_message_id mip_nmea_message_message_id; diff --git a/src/c/mip/definitions/commands_aiding.c b/src/c/mip/definitions/commands_aiding.c index 7b787179f..4f1039c83 100644 --- a/src/c/mip/definitions/commands_aiding.c +++ b/src/c/mip/definitions/commands_aiding.c @@ -97,6 +97,49 @@ void extract_mip_aiding_frame_config_command(microstrain_serializer* serializer, } } +void insert_mip_aiding_frame_config_response(microstrain_serializer* serializer, const mip_aiding_frame_config_response* self) +{ + microstrain_insert_u8(serializer, self->frame_id); + + insert_mip_aiding_frame_config_command_format(serializer, self->format); + + microstrain_insert_bool(serializer, self->tracking_enabled); + + insert_mip_vector3f(serializer, self->translation); + + if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) + { + insert_mip_vector3f(serializer, self->rotation.euler); + + } + if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_QUATERNION ) + { + insert_mip_quatf(serializer, self->rotation.quaternion); + + } +} +void extract_mip_aiding_frame_config_response(microstrain_serializer* serializer, mip_aiding_frame_config_response* self) +{ + microstrain_extract_u8(serializer, &self->frame_id); + + extract_mip_aiding_frame_config_command_format(serializer, &self->format); + + microstrain_extract_bool(serializer, &self->tracking_enabled); + + extract_mip_vector3f(serializer, self->translation); + + if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER ) + { + extract_mip_vector3f(serializer, self->rotation.euler); + + } + if( self->format == MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_QUATERNION ) + { + extract_mip_quatf(serializer, self->rotation.quaternion); + + } +} + mip_cmd_result mip_aiding_write_frame_config(mip_interface* device, uint8_t frame_id, mip_aiding_frame_config_command_format format, bool tracking_enabled, const float* translation, const mip_aiding_frame_config_command_rotation* rotation) { microstrain_serializer serializer; @@ -219,28 +262,39 @@ mip_cmd_result mip_aiding_default_frame_config(mip_interface* device, uint8_t fr return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_echo_control_command* self) +void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self) { insert_mip_function_selector(serializer, self->function); if( self->function == MIP_FUNCTION_WRITE ) { - insert_mip_aiding_echo_control_command_mode(serializer, self->mode); + insert_mip_aiding_aiding_echo_control_command_mode(serializer, self->mode); } } -void extract_mip_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_echo_control_command* self) +void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self) { extract_mip_function_selector(serializer, &self->function); if( self->function == MIP_FUNCTION_WRITE ) { - extract_mip_aiding_echo_control_command_mode(serializer, &self->mode); + extract_mip_aiding_aiding_echo_control_command_mode(serializer, &self->mode); } } -mip_cmd_result mip_aiding_write_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode mode) +void insert_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self) +{ + insert_mip_aiding_aiding_echo_control_command_mode(serializer, self->mode); + +} +void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self) +{ + extract_mip_aiding_aiding_echo_control_command_mode(serializer, &self->mode); + +} + +mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -248,13 +302,13 @@ mip_cmd_result mip_aiding_write_echo_control(mip_interface* device, mip_aiding_e insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - insert_mip_aiding_echo_control_command_mode(&serializer, mode); + insert_mip_aiding_aiding_echo_control_command_mode(&serializer, mode); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_read_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode* mode_out) +mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -273,14 +327,14 @@ mip_cmd_result mip_aiding_read_echo_control(mip_interface* device, mip_aiding_ec microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(mode_out); - extract_mip_aiding_echo_control_command_mode(&deserializer, mode_out); + extract_mip_aiding_aiding_echo_control_command_mode(&deserializer, mode_out); if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_aiding_save_echo_control(mip_interface* device) +mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -292,7 +346,7 @@ mip_cmd_result mip_aiding_save_echo_control(mip_interface* device) return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_load_echo_control(mip_interface* device) +mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -304,7 +358,7 @@ mip_cmd_result mip_aiding_load_echo_control(mip_interface* device) return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_default_echo_control(mip_interface* device) +mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -316,7 +370,7 @@ mip_cmd_result mip_aiding_default_echo_control(mip_interface* device) return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, const mip_aiding_pos_ecef_command* self) +void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self) { insert_mip_time(serializer, &self->time); @@ -326,10 +380,10 @@ void insert_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, cons insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_pos_ecef_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_ecef_pos_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, mip_aiding_pos_ecef_command* self) +void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self) { extract_mip_time(serializer, &self->time); @@ -339,11 +393,11 @@ void extract_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, mip extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_pos_ecef_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_ecef_pos_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_pos_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_pos_ecef_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -362,13 +416,13 @@ mip_cmd_result mip_aiding_pos_ecef(mip_interface* device, const mip_time* time, for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_pos_ecef_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_ecef_pos_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_pos_llh_command(microstrain_serializer* serializer, const mip_aiding_pos_llh_command* self) +void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self) { insert_mip_time(serializer, &self->time); @@ -382,10 +436,10 @@ void insert_mip_aiding_pos_llh_command(microstrain_serializer* serializer, const insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_pos_llh_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_llh_pos_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_pos_llh_command(microstrain_serializer* serializer, mip_aiding_pos_llh_command* self) +void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self) { extract_mip_time(serializer, &self->time); @@ -399,11 +453,11 @@ void extract_mip_aiding_pos_llh_command(microstrain_serializer* serializer, mip_ extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_pos_llh_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_llh_pos_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_pos_llh(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_pos_llh_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -424,13 +478,13 @@ mip_cmd_result mip_aiding_pos_llh(mip_interface* device, const mip_time* time, u for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_pos_llh_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_llh_pos_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, const mip_aiding_height_above_ellipsoid_command* self) +void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self) { insert_mip_time(serializer, &self->time); @@ -443,7 +497,7 @@ void insert_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* se microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, mip_aiding_height_above_ellipsoid_command* self) +void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self) { extract_mip_time(serializer, &self->time); @@ -457,7 +511,7 @@ void extract_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* s } -mip_cmd_result mip_aiding_height_above_ellipsoid(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) +mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -476,9 +530,9 @@ mip_cmd_result mip_aiding_height_above_ellipsoid(mip_interface* device, const mi assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABOVE_ELLIPSOID, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, const mip_aiding_vel_ecef_command* self) +void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self) { insert_mip_time(serializer, &self->time); @@ -488,10 +542,10 @@ void insert_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, cons insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_vel_ecef_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_ecef_vel_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, mip_aiding_vel_ecef_command* self) +void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self) { extract_mip_time(serializer, &self->time); @@ -501,11 +555,11 @@ void extract_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, mip extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_vel_ecef_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_ecef_vel_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_vel_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ecef_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -524,13 +578,13 @@ mip_cmd_result mip_aiding_vel_ecef(mip_interface* device, const mip_time* time, for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_vel_ecef_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_ecef_vel_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_vel_ned_command(microstrain_serializer* serializer, const mip_aiding_vel_ned_command* self) +void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self) { insert_mip_time(serializer, &self->time); @@ -540,10 +594,10 @@ void insert_mip_aiding_vel_ned_command(microstrain_serializer* serializer, const insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_vel_ned_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_ned_vel_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_vel_ned_command(microstrain_serializer* serializer, mip_aiding_vel_ned_command* self) +void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self) { extract_mip_time(serializer, &self->time); @@ -553,11 +607,11 @@ void extract_mip_aiding_vel_ned_command(microstrain_serializer* serializer, mip_ extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_vel_ned_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_ned_vel_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_vel_ned(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ned_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -576,13 +630,13 @@ mip_cmd_result mip_aiding_vel_ned(mip_interface* device, const mip_time* time, u for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_vel_ned_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_ned_vel_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, const mip_aiding_vel_body_frame_command* self) +void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self) { insert_mip_time(serializer, &self->time); @@ -592,10 +646,10 @@ void insert_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_vel_body_frame_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, mip_aiding_vel_body_frame_command* self) +void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self) { extract_mip_time(serializer, &self->time); @@ -605,11 +659,11 @@ void extract_mip_aiding_vel_body_frame_command(microstrain_serializer* serialize extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_vel_body_frame_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_vel_body_frame(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_body_frame_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -628,13 +682,13 @@ mip_cmd_result mip_aiding_vel_body_frame(mip_interface* device, const mip_time* for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_vel_body_frame_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_BODY_FRAME, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ODOM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_heading_true_command(microstrain_serializer* serializer, const mip_aiding_heading_true_command* self) +void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self) { insert_mip_time(serializer, &self->time); @@ -647,7 +701,7 @@ void insert_mip_aiding_heading_true_command(microstrain_serializer* serializer, microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_aiding_heading_true_command(microstrain_serializer* serializer, mip_aiding_heading_true_command* self) +void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self) { extract_mip_time(serializer, &self->time); @@ -661,7 +715,7 @@ void extract_mip_aiding_heading_true_command(microstrain_serializer* serializer, } -mip_cmd_result mip_aiding_heading_true(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) +mip_cmd_result mip_aiding_true_heading(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/c/mip/definitions/commands_aiding.h b/src/c/mip/definitions/commands_aiding.h index 9245a8711..8fde01071 100644 --- a/src/c/mip/definitions/commands_aiding.h +++ b/src/c/mip/definitions/commands_aiding.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include @@ -29,29 +29,29 @@ extern "C" { enum { - MIP_AIDING_CMD_DESC_SET = 0x13, + MIP_AIDING_CMD_DESC_SET = 0x13, - MIP_CMD_DESC_AIDING_FRAME_CONFIG = 0x01, - MIP_CMD_DESC_AIDING_LOCAL_FRAME = 0x03, - MIP_CMD_DESC_AIDING_ECHO_CONTROL = 0x1F, - MIP_CMD_DESC_AIDING_POS_LOCAL = 0x20, - MIP_CMD_DESC_AIDING_POS_ECEF = 0x21, - MIP_CMD_DESC_AIDING_POS_LLH = 0x22, - MIP_CMD_DESC_AIDING_HEIGHT_ABOVE_ELLIPSOID = 0x23, - MIP_CMD_DESC_AIDING_HEIGHT_REL = 0x24, - MIP_CMD_DESC_AIDING_VEL_ECEF = 0x28, - MIP_CMD_DESC_AIDING_VEL_NED = 0x29, - MIP_CMD_DESC_AIDING_VEL_BODY_FRAME = 0x2A, - MIP_CMD_DESC_AIDING_WHEELSPEED = 0x2B, - MIP_CMD_DESC_AIDING_HEADING_TRUE = 0x31, - MIP_CMD_DESC_AIDING_MAGNETIC_FIELD = 0x32, - MIP_CMD_DESC_AIDING_PRESSURE = 0x33, - MIP_CMD_DESC_AIDING_DELTA_POSITION = 0x38, - MIP_CMD_DESC_AIDING_DELTA_ATTITUDE = 0x39, - MIP_CMD_DESC_AIDING_ANGULAR_RATE_LOCAL = 0x3A, + MIP_CMD_DESC_AIDING_FRAME_CONFIG = 0x01, + MIP_CMD_DESC_AIDING_LOCAL_FRAME = 0x03, + MIP_CMD_DESC_AIDING_ECHO_CONTROL = 0x1F, + MIP_CMD_DESC_AIDING_POS_LOCAL = 0x20, + MIP_CMD_DESC_AIDING_POS_ECEF = 0x21, + MIP_CMD_DESC_AIDING_POS_LLH = 0x22, + MIP_CMD_DESC_AIDING_HEIGHT_ABS = 0x23, + MIP_CMD_DESC_AIDING_HEIGHT_REL = 0x24, + MIP_CMD_DESC_AIDING_VEL_ECEF = 0x28, + MIP_CMD_DESC_AIDING_VEL_NED = 0x29, + MIP_CMD_DESC_AIDING_VEL_ODOM = 0x2A, + MIP_CMD_DESC_AIDING_WHEELSPEED = 0x2B, + MIP_CMD_DESC_AIDING_HEADING_TRUE = 0x31, + MIP_CMD_DESC_AIDING_MAGNETIC_FIELD = 0x32, + MIP_CMD_DESC_AIDING_PRESSURE = 0x33, + MIP_CMD_DESC_AIDING_DELTA_POSITION = 0x38, + MIP_CMD_DESC_AIDING_DELTA_ATTITUDE = 0x39, + MIP_CMD_DESC_AIDING_LOCAL_ANGULAR_RATE = 0x3A, - MIP_REPLY_DESC_AIDING_FRAME_CONFIG = 0x81, - MIP_REPLY_DESC_AIDING_ECHO_CONTROL = 0x9F, + MIP_REPLY_DESC_AIDING_FRAME_CONFIG = 0x81, + MIP_REPLY_DESC_AIDING_ECHO_CONTROL = 0x9F, }; //////////////////////////////////////////////////////////////////////////////// @@ -96,9 +96,8 @@ void extract_mip_time(microstrain_serializer* serializer, mip_time* self); //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_aiding_frame_config (0x13,0x01) Frame Config [C] -/// Defines an aiding frame associated with a specific sensor frame ID. -/// The frame ID used in this command should mirror the frame ID used in the aiding command -/// (if that aiding measurement is measured in this reference frame). +/// Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command +/// should mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame) /// /// This transform satisfies the following relationship: /// @@ -185,24 +184,24 @@ mip_cmd_result mip_aiding_default_frame_config(mip_interface* device, uint8_t fr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_echo_control (0x13,0x1F) Echo Control [C] +///@defgroup c_aiding_aiding_echo_control (0x13,0x1F) Aiding Echo Control [C] /// Controls command response behavior to external aiding commands /// ///@{ -enum mip_aiding_echo_control_command_mode +enum mip_aiding_aiding_echo_control_command_mode { - MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_SUPPRESS_ACK = 0, ///< Suppresses the usual command ack field for aiding messages. - MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_STANDARD = 1, ///< Normal ack/nack behavior. - MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_RESPONSE = 2, ///< Echo the data back as a response. + MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_SUPPRESS_ACK = 0, ///< Suppresses the usual command ack field for aiding messages. + MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_STANDARD = 1, ///< Normal ack/nack behavior. + MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_RESPONSE = 2, ///< Echo the data back as a response. }; -typedef enum mip_aiding_echo_control_command_mode mip_aiding_echo_control_command_mode; +typedef enum mip_aiding_aiding_echo_control_command_mode mip_aiding_aiding_echo_control_command_mode; -static inline void insert_mip_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_echo_control_command_mode self) +static inline void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -static inline void extract_mip_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_echo_control_command_mode* self) +static inline void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -210,50 +209,50 @@ static inline void extract_mip_aiding_echo_control_command_mode(microstrain_seri } -struct mip_aiding_echo_control_command +struct mip_aiding_aiding_echo_control_command { mip_function_selector function; - mip_aiding_echo_control_command_mode mode; ///< Controls data echoing. + mip_aiding_aiding_echo_control_command_mode mode; ///< Controls data echoing. }; -typedef struct mip_aiding_echo_control_command mip_aiding_echo_control_command; +typedef struct mip_aiding_aiding_echo_control_command mip_aiding_aiding_echo_control_command; -void insert_mip_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_echo_control_command* self); -void extract_mip_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_echo_control_command* self); +void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self); +void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self); -struct mip_aiding_echo_control_response +struct mip_aiding_aiding_echo_control_response { - mip_aiding_echo_control_command_mode mode; ///< Controls data echoing. + mip_aiding_aiding_echo_control_command_mode mode; ///< Controls data echoing. }; -typedef struct mip_aiding_echo_control_response mip_aiding_echo_control_response; +typedef struct mip_aiding_aiding_echo_control_response mip_aiding_aiding_echo_control_response; -void insert_mip_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_echo_control_response* self); -void extract_mip_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_echo_control_response* self); +void insert_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self); +void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self); -mip_cmd_result mip_aiding_write_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode mode); -mip_cmd_result mip_aiding_read_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode* mode_out); -mip_cmd_result mip_aiding_save_echo_control(mip_interface* device); -mip_cmd_result mip_aiding_load_echo_control(mip_interface* device); -mip_cmd_result mip_aiding_default_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode); +mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out); +mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_pos_ecef (0x13,0x21) Pos Ecef [C] +///@defgroup c_aiding_ecef_pos (0x13,0x21) Ecef Pos [C] /// Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system. /// ///@{ -typedef uint16_t mip_aiding_pos_ecef_command_valid_flags; -static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_pos_ecef_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_pos_ecef_command_valid_flags self) +typedef uint16_t mip_aiding_ecef_pos_command_valid_flags; +static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_pos_ecef_command_valid_flags(microstrain_serializer* serializer, mip_aiding_pos_ecef_command_valid_flags* self) +static inline void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -261,42 +260,41 @@ static inline void extract_mip_aiding_pos_ecef_command_valid_flags(microstrain_s } -struct mip_aiding_pos_ecef_command +struct mip_aiding_ecef_pos_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3d position; ///< ECEF position [m]. mip_vector3f uncertainty; ///< ECEF position uncertainty [m]. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_pos_ecef_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_ecef_pos_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_pos_ecef_command mip_aiding_pos_ecef_command; +typedef struct mip_aiding_ecef_pos_command mip_aiding_ecef_pos_command; -void insert_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, const mip_aiding_pos_ecef_command* self); -void extract_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, mip_aiding_pos_ecef_command* self); +void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self); +void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self); -mip_cmd_result mip_aiding_pos_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_pos_ecef_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_pos_llh (0x13,0x22) Pos Llh [C] -/// Geodetic position aiding command. -/// Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. +///@defgroup c_aiding_llh_pos (0x13,0x22) Llh Pos [C] +/// Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. /// Uncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height. /// ///@{ -typedef uint16_t mip_aiding_pos_llh_command_valid_flags; -static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_LATITUDE = 0x0001; ///< -static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_LONGITUDE = 0x0002; ///< -static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_HEIGHT = 0x0004; ///< -static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_pos_llh_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_pos_llh_command_valid_flags self) +typedef uint16_t mip_aiding_llh_pos_command_valid_flags; +static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_LATITUDE = 0x0001; ///< +static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_LONGITUDE = 0x0002; ///< +static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_HEIGHT = 0x0004; ///< +static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_pos_llh_command_valid_flags(microstrain_serializer* serializer, mip_aiding_pos_llh_command_valid_flags* self) +static inline void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -304,7 +302,7 @@ static inline void extract_mip_aiding_pos_llh_command_valid_flags(microstrain_se } -struct mip_aiding_pos_llh_command +struct mip_aiding_llh_pos_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). @@ -312,24 +310,24 @@ struct mip_aiding_pos_llh_command double longitude; ///< [deg] double height; ///< [m] mip_vector3f uncertainty; ///< NED position uncertainty. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_pos_llh_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_llh_pos_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_pos_llh_command mip_aiding_pos_llh_command; +typedef struct mip_aiding_llh_pos_command mip_aiding_llh_pos_command; -void insert_mip_aiding_pos_llh_command(microstrain_serializer* serializer, const mip_aiding_pos_llh_command* self); -void extract_mip_aiding_pos_llh_command(microstrain_serializer* serializer, mip_aiding_pos_llh_command* self); +void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self); +void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self); -mip_cmd_result mip_aiding_pos_llh(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_pos_llh_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_height_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [C] -/// Estimated value of the height above ellipsoid. +///@defgroup c_aiding_height (0x13,0x23) Height [C] +/// Estimated value of height. /// ///@{ -struct mip_aiding_height_above_ellipsoid_command +struct mip_aiding_height_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). @@ -337,32 +335,32 @@ struct mip_aiding_height_above_ellipsoid_command float uncertainty; ///< [m] uint16_t valid_flags; }; -typedef struct mip_aiding_height_above_ellipsoid_command mip_aiding_height_above_ellipsoid_command; +typedef struct mip_aiding_height_command mip_aiding_height_command; -void insert_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, const mip_aiding_height_above_ellipsoid_command* self); -void extract_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, mip_aiding_height_above_ellipsoid_command* self); +void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self); +void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self); -mip_cmd_result mip_aiding_height_above_ellipsoid(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); +mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_vel_ecef (0x13,0x28) Vel Ecef [C] +///@defgroup c_aiding_ecef_vel (0x13,0x28) Ecef Vel [C] /// ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame. /// ///@{ -typedef uint16_t mip_aiding_vel_ecef_command_valid_flags; -static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_vel_ecef_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vel_ecef_command_valid_flags self) +typedef uint16_t mip_aiding_ecef_vel_command_valid_flags; +static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_vel_ecef_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vel_ecef_command_valid_flags* self) +static inline void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -370,40 +368,40 @@ static inline void extract_mip_aiding_vel_ecef_command_valid_flags(microstrain_s } -struct mip_aiding_vel_ecef_command +struct mip_aiding_ecef_vel_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3f velocity; ///< ECEF velocity [m/s]. mip_vector3f uncertainty; ///< ECEF velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_vel_ecef_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_ecef_vel_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_vel_ecef_command mip_aiding_vel_ecef_command; +typedef struct mip_aiding_ecef_vel_command mip_aiding_ecef_vel_command; -void insert_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, const mip_aiding_vel_ecef_command* self); -void extract_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, mip_aiding_vel_ecef_command* self); +void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self); +void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self); -mip_cmd_result mip_aiding_vel_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ecef_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_vel_ned (0x13,0x29) Vel Ned [C] +///@defgroup c_aiding_ned_vel (0x13,0x29) Ned Vel [C] /// NED velocity aiding command. Coordinates are given in the local North-East-Down frame. /// ///@{ -typedef uint16_t mip_aiding_vel_ned_command_valid_flags; -static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_vel_ned_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vel_ned_command_valid_flags self) +typedef uint16_t mip_aiding_ned_vel_command_valid_flags; +static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_vel_ned_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vel_ned_command_valid_flags* self) +static inline void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -411,40 +409,41 @@ static inline void extract_mip_aiding_vel_ned_command_valid_flags(microstrain_se } -struct mip_aiding_vel_ned_command +struct mip_aiding_ned_vel_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3f velocity; ///< NED velocity [m/s]. mip_vector3f uncertainty; ///< NED velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_vel_ned_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_ned_vel_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_vel_ned_command mip_aiding_vel_ned_command; +typedef struct mip_aiding_ned_vel_command mip_aiding_ned_vel_command; -void insert_mip_aiding_vel_ned_command(microstrain_serializer* serializer, const mip_aiding_vel_ned_command* self); -void extract_mip_aiding_vel_ned_command(microstrain_serializer* serializer, mip_aiding_vel_ned_command* self); +void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self); +void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self); -mip_cmd_result mip_aiding_vel_ned(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ned_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_vel_body_frame (0x13,0x2A) Vel Body Frame [C] -/// Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame. +///@defgroup c_aiding_vehicle_fixed_frame_velocity (0x13,0x2A) Vehicle Fixed Frame Velocity [C] +/// Estimate of velocity of the vehicle in the frame associated +/// with the given sensor ID. /// ///@{ -typedef uint16_t mip_aiding_vel_body_frame_command_valid_flags; -static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_vel_body_frame_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vel_body_frame_command_valid_flags self) +typedef uint16_t mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags; +static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_vel_body_frame_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vel_body_frame_command_valid_flags* self) +static inline void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -452,29 +451,29 @@ static inline void extract_mip_aiding_vel_body_frame_command_valid_flags(microst } -struct mip_aiding_vel_body_frame_command +struct mip_aiding_vehicle_fixed_frame_velocity_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3f velocity; ///< [m/s] mip_vector3f uncertainty; ///< [m/s] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_vel_body_frame_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_vel_body_frame_command mip_aiding_vel_body_frame_command; +typedef struct mip_aiding_vehicle_fixed_frame_velocity_command mip_aiding_vehicle_fixed_frame_velocity_command; -void insert_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, const mip_aiding_vel_body_frame_command* self); -void extract_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, mip_aiding_vel_body_frame_command* self); +void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self); +void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self); -mip_cmd_result mip_aiding_vel_body_frame(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_body_frame_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_heading_true (0x13,0x31) Heading True [C] +///@defgroup c_aiding_true_heading (0x13,0x31) True Heading [C] /// ///@{ -struct mip_aiding_heading_true_command +struct mip_aiding_true_heading_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). @@ -482,12 +481,12 @@ struct mip_aiding_heading_true_command float uncertainty; ///< Cannot be 0 unless the valid flags are 0. uint16_t valid_flags; }; -typedef struct mip_aiding_heading_true_command mip_aiding_heading_true_command; +typedef struct mip_aiding_true_heading_command mip_aiding_true_heading_command; -void insert_mip_aiding_heading_true_command(microstrain_serializer* serializer, const mip_aiding_heading_true_command* self); -void extract_mip_aiding_heading_true_command(microstrain_serializer* serializer, mip_aiding_heading_true_command* self); +void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self); +void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self); -mip_cmd_result mip_aiding_heading_true(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); +mip_cmd_result mip_aiding_true_heading(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); ///@} /// diff --git a/src/c/mip/definitions/commands_base.c b/src/c/mip/definitions/commands_base.c index 82b99f96a..198c536f5 100644 --- a/src/c/mip/definitions/commands_base.c +++ b/src/c/mip/definitions/commands_base.c @@ -198,6 +198,21 @@ void extract_mip_base_comm_speed_command(microstrain_serializer* serializer, mip } } +void insert_mip_base_comm_speed_response(microstrain_serializer* serializer, const mip_base_comm_speed_response* self) +{ + microstrain_insert_u8(serializer, self->port); + + microstrain_insert_u32(serializer, self->baud); + +} +void extract_mip_base_comm_speed_response(microstrain_serializer* serializer, mip_base_comm_speed_response* self) +{ + microstrain_extract_u8(serializer, &self->port); + + microstrain_extract_u32(serializer, &self->baud); + +} + mip_cmd_result mip_base_write_comm_speed(mip_interface* device, uint8_t port, uint32_t baud) { microstrain_serializer serializer; diff --git a/src/c/mip/definitions/commands_base.h b/src/c/mip/definitions/commands_base.h index c36ce3c8c..529714bc0 100644 --- a/src/c/mip/definitions/commands_base.h +++ b/src/c/mip/definitions/commands_base.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include diff --git a/src/c/mip/definitions/commands_filter.c b/src/c/mip/definitions/commands_filter.c index 8f42326d5..4385fdcd5 100644 --- a/src/c/mip/definitions/commands_filter.c +++ b/src/c/mip/definitions/commands_filter.c @@ -79,6 +79,17 @@ void extract_mip_filter_estimation_control_command(microstrain_serializer* seria } } +void insert_mip_filter_estimation_control_response(microstrain_serializer* serializer, const mip_filter_estimation_control_response* self) +{ + insert_mip_filter_estimation_control_command_enable_flags(serializer, self->enable); + +} +void extract_mip_filter_estimation_control_response(microstrain_serializer* serializer, mip_filter_estimation_control_response* self) +{ + extract_mip_filter_estimation_control_command_enable_flags(serializer, &self->enable); + +} + mip_cmd_result mip_filter_write_estimation_control(mip_interface* device, mip_filter_estimation_control_command_enable_flags enable) { microstrain_serializer serializer; @@ -329,6 +340,17 @@ void extract_mip_filter_tare_orientation_command(microstrain_serializer* seriali } } +void insert_mip_filter_tare_orientation_response(microstrain_serializer* serializer, const mip_filter_tare_orientation_response* self) +{ + insert_mip_filter_tare_orientation_command_mip_tare_axes(serializer, self->axes); + +} +void extract_mip_filter_tare_orientation_response(microstrain_serializer* serializer, mip_filter_tare_orientation_response* self) +{ + extract_mip_filter_tare_orientation_command_mip_tare_axes(serializer, &self->axes); + +} + mip_cmd_result mip_filter_write_tare_orientation(mip_interface* device, mip_filter_tare_orientation_command_mip_tare_axes axes) { microstrain_serializer serializer; @@ -426,6 +448,17 @@ void extract_mip_filter_vehicle_dynamics_mode_command(microstrain_serializer* se } } +void insert_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, const mip_filter_vehicle_dynamics_mode_response* self) +{ + insert_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(serializer, self->mode); + +} +void extract_mip_filter_vehicle_dynamics_mode_response(microstrain_serializer* serializer, mip_filter_vehicle_dynamics_mode_response* self) +{ + extract_mip_filter_vehicle_dynamics_mode_command_dynamics_mode(serializer, &self->mode); + +} + mip_cmd_result mip_filter_write_vehicle_dynamics_mode(mip_interface* device, mip_filter_vehicle_dynamics_mode_command_dynamics_mode mode) { microstrain_serializer serializer; @@ -531,6 +564,25 @@ void extract_mip_filter_sensor_to_vehicle_rotation_euler_command(microstrain_ser } } +void insert_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_euler_response* self) +{ + microstrain_insert_float(serializer, self->roll); + + microstrain_insert_float(serializer, self->pitch); + + microstrain_insert_float(serializer, self->yaw); + +} +void extract_mip_filter_sensor_to_vehicle_rotation_euler_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_euler_response* self) +{ + microstrain_extract_float(serializer, &self->roll); + + microstrain_extract_float(serializer, &self->pitch); + + microstrain_extract_float(serializer, &self->yaw); + +} + mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_euler(mip_interface* device, float roll, float pitch, float yaw) { microstrain_serializer serializer; @@ -638,6 +690,17 @@ void extract_mip_filter_sensor_to_vehicle_rotation_dcm_command(microstrain_seria } } +void insert_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_dcm_response* self) +{ + insert_mip_matrix3f(serializer, self->dcm); + +} +void extract_mip_filter_sensor_to_vehicle_rotation_dcm_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_dcm_response* self) +{ + extract_mip_matrix3f(serializer, self->dcm); + +} + mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_dcm(mip_interface* device, const float* dcm) { microstrain_serializer serializer; @@ -738,6 +801,17 @@ void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_command(microstrai } } +void insert_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) +{ + insert_mip_quatf(serializer, self->quat); + +} +void extract_mip_filter_sensor_to_vehicle_rotation_quaternion_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_rotation_quaternion_response* self) +{ + extract_mip_quatf(serializer, self->quat); + +} + mip_cmd_result mip_filter_write_sensor_to_vehicle_rotation_quaternion(mip_interface* device, const float* quat) { microstrain_serializer serializer; @@ -838,6 +912,17 @@ void extract_mip_filter_sensor_to_vehicle_offset_command(microstrain_serializer* } } +void insert_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, const mip_filter_sensor_to_vehicle_offset_response* self) +{ + insert_mip_vector3f(serializer, self->offset); + +} +void extract_mip_filter_sensor_to_vehicle_offset_response(microstrain_serializer* serializer, mip_filter_sensor_to_vehicle_offset_response* self) +{ + extract_mip_vector3f(serializer, self->offset); + +} + mip_cmd_result mip_filter_write_sensor_to_vehicle_offset(mip_interface* device, const float* offset) { microstrain_serializer serializer; @@ -938,6 +1023,17 @@ void extract_mip_filter_antenna_offset_command(microstrain_serializer* serialize } } +void insert_mip_filter_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_antenna_offset_response* self) +{ + insert_mip_vector3f(serializer, self->offset); + +} +void extract_mip_filter_antenna_offset_response(microstrain_serializer* serializer, mip_filter_antenna_offset_response* self) +{ + extract_mip_vector3f(serializer, self->offset); + +} + mip_cmd_result mip_filter_write_antenna_offset(mip_interface* device, const float* offset) { microstrain_serializer serializer; @@ -1038,6 +1134,17 @@ void extract_mip_filter_gnss_source_command(microstrain_serializer* serializer, } } +void insert_mip_filter_gnss_source_response(microstrain_serializer* serializer, const mip_filter_gnss_source_response* self) +{ + insert_mip_filter_gnss_source_command_source(serializer, self->source); + +} +void extract_mip_filter_gnss_source_response(microstrain_serializer* serializer, mip_filter_gnss_source_response* self) +{ + extract_mip_filter_gnss_source_command_source(serializer, &self->source); + +} + mip_cmd_result mip_filter_write_gnss_source(mip_interface* device, mip_filter_gnss_source_command_source source) { microstrain_serializer serializer; @@ -1135,6 +1242,17 @@ void extract_mip_filter_heading_source_command(microstrain_serializer* serialize } } +void insert_mip_filter_heading_source_response(microstrain_serializer* serializer, const mip_filter_heading_source_response* self) +{ + insert_mip_filter_heading_source_command_source(serializer, self->source); + +} +void extract_mip_filter_heading_source_response(microstrain_serializer* serializer, mip_filter_heading_source_response* self) +{ + extract_mip_filter_heading_source_command_source(serializer, &self->source); + +} + mip_cmd_result mip_filter_write_heading_source(mip_interface* device, mip_filter_heading_source_command_source source) { microstrain_serializer serializer; @@ -1232,6 +1350,17 @@ void extract_mip_filter_auto_init_control_command(microstrain_serializer* serial } } +void insert_mip_filter_auto_init_control_response(microstrain_serializer* serializer, const mip_filter_auto_init_control_response* self) +{ + microstrain_insert_u8(serializer, self->enable); + +} +void extract_mip_filter_auto_init_control_response(microstrain_serializer* serializer, mip_filter_auto_init_control_response* self) +{ + microstrain_extract_u8(serializer, &self->enable); + +} + mip_cmd_result mip_filter_write_auto_init_control(mip_interface* device, uint8_t enable) { microstrain_serializer serializer; @@ -1329,6 +1458,17 @@ void extract_mip_filter_accel_noise_command(microstrain_serializer* serializer, } } +void insert_mip_filter_accel_noise_response(microstrain_serializer* serializer, const mip_filter_accel_noise_response* self) +{ + insert_mip_vector3f(serializer, self->noise); + +} +void extract_mip_filter_accel_noise_response(microstrain_serializer* serializer, mip_filter_accel_noise_response* self) +{ + extract_mip_vector3f(serializer, self->noise); + +} + mip_cmd_result mip_filter_write_accel_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; @@ -1429,6 +1569,17 @@ void extract_mip_filter_gyro_noise_command(microstrain_serializer* serializer, m } } +void insert_mip_filter_gyro_noise_response(microstrain_serializer* serializer, const mip_filter_gyro_noise_response* self) +{ + insert_mip_vector3f(serializer, self->noise); + +} +void extract_mip_filter_gyro_noise_response(microstrain_serializer* serializer, mip_filter_gyro_noise_response* self) +{ + extract_mip_vector3f(serializer, self->noise); + +} + mip_cmd_result mip_filter_write_gyro_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; @@ -1533,6 +1684,21 @@ void extract_mip_filter_accel_bias_model_command(microstrain_serializer* seriali } } +void insert_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, const mip_filter_accel_bias_model_response* self) +{ + insert_mip_vector3f(serializer, self->beta); + + insert_mip_vector3f(serializer, self->noise); + +} +void extract_mip_filter_accel_bias_model_response(microstrain_serializer* serializer, mip_filter_accel_bias_model_response* self) +{ + extract_mip_vector3f(serializer, self->beta); + + extract_mip_vector3f(serializer, self->noise); + +} + mip_cmd_result mip_filter_write_accel_bias_model(mip_interface* device, const float* beta, const float* noise) { microstrain_serializer serializer; @@ -1645,6 +1811,21 @@ void extract_mip_filter_gyro_bias_model_command(microstrain_serializer* serializ } } +void insert_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, const mip_filter_gyro_bias_model_response* self) +{ + insert_mip_vector3f(serializer, self->beta); + + insert_mip_vector3f(serializer, self->noise); + +} +void extract_mip_filter_gyro_bias_model_response(microstrain_serializer* serializer, mip_filter_gyro_bias_model_response* self) +{ + extract_mip_vector3f(serializer, self->beta); + + extract_mip_vector3f(serializer, self->noise); + +} + mip_cmd_result mip_filter_write_gyro_bias_model(mip_interface* device, const float* beta, const float* noise) { microstrain_serializer serializer; @@ -1753,6 +1934,17 @@ void extract_mip_filter_altitude_aiding_command(microstrain_serializer* serializ } } +void insert_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, const mip_filter_altitude_aiding_response* self) +{ + insert_mip_filter_altitude_aiding_command_aiding_selector(serializer, self->selector); + +} +void extract_mip_filter_altitude_aiding_response(microstrain_serializer* serializer, mip_filter_altitude_aiding_response* self) +{ + extract_mip_filter_altitude_aiding_command_aiding_selector(serializer, &self->selector); + +} + mip_cmd_result mip_filter_write_altitude_aiding(mip_interface* device, mip_filter_altitude_aiding_command_aiding_selector selector) { microstrain_serializer serializer; @@ -1850,6 +2042,17 @@ void extract_mip_filter_pitch_roll_aiding_command(microstrain_serializer* serial } } +void insert_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, const mip_filter_pitch_roll_aiding_response* self) +{ + insert_mip_filter_pitch_roll_aiding_command_aiding_source(serializer, self->source); + +} +void extract_mip_filter_pitch_roll_aiding_response(microstrain_serializer* serializer, mip_filter_pitch_roll_aiding_response* self) +{ + extract_mip_filter_pitch_roll_aiding_command_aiding_source(serializer, &self->source); + +} + mip_cmd_result mip_filter_write_pitch_roll_aiding(mip_interface* device, mip_filter_pitch_roll_aiding_command_aiding_source source) { microstrain_serializer serializer; @@ -1951,6 +2154,21 @@ void extract_mip_filter_auto_zupt_command(microstrain_serializer* serializer, mi } } +void insert_mip_filter_auto_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_zupt_response* self) +{ + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_float(serializer, self->threshold); + +} +void extract_mip_filter_auto_zupt_response(microstrain_serializer* serializer, mip_filter_auto_zupt_response* self) +{ + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->threshold); + +} + mip_cmd_result mip_filter_write_auto_zupt(mip_interface* device, uint8_t enable, float threshold) { microstrain_serializer serializer; @@ -2057,6 +2275,21 @@ void extract_mip_filter_auto_angular_zupt_command(microstrain_serializer* serial } } +void insert_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, const mip_filter_auto_angular_zupt_response* self) +{ + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_float(serializer, self->threshold); + +} +void extract_mip_filter_auto_angular_zupt_response(microstrain_serializer* serializer, mip_filter_auto_angular_zupt_response* self) +{ + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->threshold); + +} + mip_cmd_result mip_filter_write_auto_angular_zupt(mip_interface* device, uint8_t enable, float threshold) { microstrain_serializer serializer; @@ -2202,6 +2435,17 @@ void extract_mip_filter_gravity_noise_command(microstrain_serializer* serializer } } +void insert_mip_filter_gravity_noise_response(microstrain_serializer* serializer, const mip_filter_gravity_noise_response* self) +{ + insert_mip_vector3f(serializer, self->noise); + +} +void extract_mip_filter_gravity_noise_response(microstrain_serializer* serializer, mip_filter_gravity_noise_response* self) +{ + extract_mip_vector3f(serializer, self->noise); + +} + mip_cmd_result mip_filter_write_gravity_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; @@ -2302,6 +2546,17 @@ void extract_mip_filter_pressure_altitude_noise_command(microstrain_serializer* } } +void insert_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, const mip_filter_pressure_altitude_noise_response* self) +{ + microstrain_insert_float(serializer, self->noise); + +} +void extract_mip_filter_pressure_altitude_noise_response(microstrain_serializer* serializer, mip_filter_pressure_altitude_noise_response* self) +{ + microstrain_extract_float(serializer, &self->noise); + +} + mip_cmd_result mip_filter_write_pressure_altitude_noise(mip_interface* device, float noise) { microstrain_serializer serializer; @@ -2399,6 +2654,17 @@ void extract_mip_filter_hard_iron_offset_noise_command(microstrain_serializer* s } } +void insert_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, const mip_filter_hard_iron_offset_noise_response* self) +{ + insert_mip_vector3f(serializer, self->noise); + +} +void extract_mip_filter_hard_iron_offset_noise_response(microstrain_serializer* serializer, mip_filter_hard_iron_offset_noise_response* self) +{ + extract_mip_vector3f(serializer, self->noise); + +} + mip_cmd_result mip_filter_write_hard_iron_offset_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; @@ -2499,6 +2765,17 @@ void extract_mip_filter_soft_iron_matrix_noise_command(microstrain_serializer* s } } +void insert_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, const mip_filter_soft_iron_matrix_noise_response* self) +{ + insert_mip_matrix3f(serializer, self->noise); + +} +void extract_mip_filter_soft_iron_matrix_noise_response(microstrain_serializer* serializer, mip_filter_soft_iron_matrix_noise_response* self) +{ + extract_mip_matrix3f(serializer, self->noise); + +} + mip_cmd_result mip_filter_write_soft_iron_matrix_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; @@ -2599,6 +2876,17 @@ void extract_mip_filter_mag_noise_command(microstrain_serializer* serializer, mi } } +void insert_mip_filter_mag_noise_response(microstrain_serializer* serializer, const mip_filter_mag_noise_response* self) +{ + insert_mip_vector3f(serializer, self->noise); + +} +void extract_mip_filter_mag_noise_response(microstrain_serializer* serializer, mip_filter_mag_noise_response* self) +{ + extract_mip_vector3f(serializer, self->noise); + +} + mip_cmd_result mip_filter_write_mag_noise(mip_interface* device, const float* noise) { microstrain_serializer serializer; @@ -2703,6 +2991,21 @@ void extract_mip_filter_inclination_source_command(microstrain_serializer* seria } } +void insert_mip_filter_inclination_source_response(microstrain_serializer* serializer, const mip_filter_inclination_source_response* self) +{ + insert_mip_filter_mag_param_source(serializer, self->source); + + microstrain_insert_float(serializer, self->inclination); + +} +void extract_mip_filter_inclination_source_response(microstrain_serializer* serializer, mip_filter_inclination_source_response* self) +{ + extract_mip_filter_mag_param_source(serializer, &self->source); + + microstrain_extract_float(serializer, &self->inclination); + +} + mip_cmd_result mip_filter_write_inclination_source(mip_interface* device, mip_filter_mag_param_source source, float inclination) { microstrain_serializer serializer; @@ -2809,6 +3112,21 @@ void extract_mip_filter_magnetic_declination_source_command(microstrain_serializ } } +void insert_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, const mip_filter_magnetic_declination_source_response* self) +{ + insert_mip_filter_mag_param_source(serializer, self->source); + + microstrain_insert_float(serializer, self->declination); + +} +void extract_mip_filter_magnetic_declination_source_response(microstrain_serializer* serializer, mip_filter_magnetic_declination_source_response* self) +{ + extract_mip_filter_mag_param_source(serializer, &self->source); + + microstrain_extract_float(serializer, &self->declination); + +} + mip_cmd_result mip_filter_write_magnetic_declination_source(mip_interface* device, mip_filter_mag_param_source source, float declination) { microstrain_serializer serializer; @@ -2915,6 +3233,21 @@ void extract_mip_filter_mag_field_magnitude_source_command(microstrain_serialize } } +void insert_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, const mip_filter_mag_field_magnitude_source_response* self) +{ + insert_mip_filter_mag_param_source(serializer, self->source); + + microstrain_insert_float(serializer, self->magnitude); + +} +void extract_mip_filter_mag_field_magnitude_source_response(microstrain_serializer* serializer, mip_filter_mag_field_magnitude_source_response* self) +{ + extract_mip_filter_mag_param_source(serializer, &self->source); + + microstrain_extract_float(serializer, &self->magnitude); + +} + mip_cmd_result mip_filter_write_mag_field_magnitude_source(mip_interface* device, mip_filter_mag_param_source source, float magnitude) { microstrain_serializer serializer; @@ -3029,6 +3362,29 @@ void extract_mip_filter_reference_position_command(microstrain_serializer* seria } } +void insert_mip_filter_reference_position_response(microstrain_serializer* serializer, const mip_filter_reference_position_response* self) +{ + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_double(serializer, self->latitude); + + microstrain_insert_double(serializer, self->longitude); + + microstrain_insert_double(serializer, self->altitude); + +} +void extract_mip_filter_reference_position_response(microstrain_serializer* serializer, mip_filter_reference_position_response* self) +{ + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_double(serializer, &self->latitude); + + microstrain_extract_double(serializer, &self->longitude); + + microstrain_extract_double(serializer, &self->altitude); + +} + mip_cmd_result mip_filter_write_reference_position(mip_interface* device, bool enable, double latitude, double longitude, double altitude) { microstrain_serializer serializer; @@ -3165,6 +3521,41 @@ void extract_mip_filter_accel_magnitude_error_adaptive_measurement_command(micro } } +void insert_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_accel_magnitude_error_adaptive_measurement_response* self) +{ + insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); + + microstrain_insert_float(serializer, self->frequency); + + microstrain_insert_float(serializer, self->low_limit); + + microstrain_insert_float(serializer, self->high_limit); + + microstrain_insert_float(serializer, self->low_limit_uncertainty); + + microstrain_insert_float(serializer, self->high_limit_uncertainty); + + microstrain_insert_float(serializer, self->minimum_uncertainty); + +} +void extract_mip_filter_accel_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_accel_magnitude_error_adaptive_measurement_response* self) +{ + extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); + + microstrain_extract_float(serializer, &self->frequency); + + microstrain_extract_float(serializer, &self->low_limit); + + microstrain_extract_float(serializer, &self->high_limit); + + microstrain_extract_float(serializer, &self->low_limit_uncertainty); + + microstrain_extract_float(serializer, &self->high_limit_uncertainty); + + microstrain_extract_float(serializer, &self->minimum_uncertainty); + +} + mip_cmd_result mip_filter_write_accel_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty) { microstrain_serializer serializer; @@ -3316,6 +3707,41 @@ void extract_mip_filter_mag_magnitude_error_adaptive_measurement_command(microst } } +void insert_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_magnitude_error_adaptive_measurement_response* self) +{ + insert_mip_filter_adaptive_measurement(serializer, self->adaptive_measurement); + + microstrain_insert_float(serializer, self->frequency); + + microstrain_insert_float(serializer, self->low_limit); + + microstrain_insert_float(serializer, self->high_limit); + + microstrain_insert_float(serializer, self->low_limit_uncertainty); + + microstrain_insert_float(serializer, self->high_limit_uncertainty); + + microstrain_insert_float(serializer, self->minimum_uncertainty); + +} +void extract_mip_filter_mag_magnitude_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_magnitude_error_adaptive_measurement_response* self) +{ + extract_mip_filter_adaptive_measurement(serializer, &self->adaptive_measurement); + + microstrain_extract_float(serializer, &self->frequency); + + microstrain_extract_float(serializer, &self->low_limit); + + microstrain_extract_float(serializer, &self->high_limit); + + microstrain_extract_float(serializer, &self->low_limit_uncertainty); + + microstrain_extract_float(serializer, &self->high_limit_uncertainty); + + microstrain_extract_float(serializer, &self->minimum_uncertainty); + +} + mip_cmd_result mip_filter_write_mag_magnitude_error_adaptive_measurement(mip_interface* device, mip_filter_adaptive_measurement adaptive_measurement, float frequency, float low_limit, float high_limit, float low_limit_uncertainty, float high_limit_uncertainty, float minimum_uncertainty) { microstrain_serializer serializer; @@ -3459,6 +3885,33 @@ void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_command(microst } } +void insert_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, const mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) +{ + microstrain_insert_bool(serializer, self->enable); + + microstrain_insert_float(serializer, self->frequency); + + microstrain_insert_float(serializer, self->high_limit); + + microstrain_insert_float(serializer, self->high_limit_uncertainty); + + microstrain_insert_float(serializer, self->minimum_uncertainty); + +} +void extract_mip_filter_mag_dip_angle_error_adaptive_measurement_response(microstrain_serializer* serializer, mip_filter_mag_dip_angle_error_adaptive_measurement_response* self) +{ + microstrain_extract_bool(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->frequency); + + microstrain_extract_float(serializer, &self->high_limit); + + microstrain_extract_float(serializer, &self->high_limit_uncertainty); + + microstrain_extract_float(serializer, &self->minimum_uncertainty); + +} + mip_cmd_result mip_filter_write_mag_dip_angle_error_adaptive_measurement(mip_interface* device, bool enable, float frequency, float high_limit, float high_limit_uncertainty, float minimum_uncertainty) { microstrain_serializer serializer; @@ -3580,6 +4033,21 @@ void extract_mip_filter_aiding_measurement_enable_command(microstrain_serializer } } +void insert_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, const mip_filter_aiding_measurement_enable_response* self) +{ + insert_mip_filter_aiding_measurement_enable_command_aiding_source(serializer, self->aiding_source); + + microstrain_insert_bool(serializer, self->enable); + +} +void extract_mip_filter_aiding_measurement_enable_response(microstrain_serializer* serializer, mip_filter_aiding_measurement_enable_response* self) +{ + extract_mip_filter_aiding_measurement_enable_command_aiding_source(serializer, &self->aiding_source); + + microstrain_extract_bool(serializer, &self->enable); + +} + mip_cmd_result mip_filter_write_aiding_measurement_enable(mip_interface* device, mip_filter_aiding_measurement_enable_command_aiding_source aiding_source, bool enable) { microstrain_serializer serializer; @@ -3701,6 +4169,25 @@ void extract_mip_filter_kinematic_constraint_command(microstrain_serializer* ser } } +void insert_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, const mip_filter_kinematic_constraint_response* self) +{ + microstrain_insert_u8(serializer, self->acceleration_constraint_selection); + + microstrain_insert_u8(serializer, self->velocity_constraint_selection); + + microstrain_insert_u8(serializer, self->angular_constraint_selection); + +} +void extract_mip_filter_kinematic_constraint_response(microstrain_serializer* serializer, mip_filter_kinematic_constraint_response* self) +{ + microstrain_extract_u8(serializer, &self->acceleration_constraint_selection); + + microstrain_extract_u8(serializer, &self->velocity_constraint_selection); + + microstrain_extract_u8(serializer, &self->angular_constraint_selection); + +} + mip_cmd_result mip_filter_write_kinematic_constraint(mip_interface* device, uint8_t acceleration_constraint_selection, uint8_t velocity_constraint_selection, uint8_t angular_constraint_selection) { microstrain_serializer serializer; @@ -3840,6 +4327,49 @@ void extract_mip_filter_initialization_configuration_command(microstrain_seriali } } +void insert_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, const mip_filter_initialization_configuration_response* self) +{ + microstrain_insert_u8(serializer, self->wait_for_run_command); + + insert_mip_filter_initialization_configuration_command_initial_condition_source(serializer, self->initial_cond_src); + + insert_mip_filter_initialization_configuration_command_alignment_selector(serializer, self->auto_heading_alignment_selector); + + microstrain_insert_float(serializer, self->initial_heading); + + microstrain_insert_float(serializer, self->initial_pitch); + + microstrain_insert_float(serializer, self->initial_roll); + + insert_mip_vector3f(serializer, self->initial_position); + + insert_mip_vector3f(serializer, self->initial_velocity); + + insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); + +} +void extract_mip_filter_initialization_configuration_response(microstrain_serializer* serializer, mip_filter_initialization_configuration_response* self) +{ + microstrain_extract_u8(serializer, &self->wait_for_run_command); + + extract_mip_filter_initialization_configuration_command_initial_condition_source(serializer, &self->initial_cond_src); + + extract_mip_filter_initialization_configuration_command_alignment_selector(serializer, &self->auto_heading_alignment_selector); + + microstrain_extract_float(serializer, &self->initial_heading); + + microstrain_extract_float(serializer, &self->initial_pitch); + + microstrain_extract_float(serializer, &self->initial_roll); + + extract_mip_vector3f(serializer, self->initial_position); + + extract_mip_vector3f(serializer, self->initial_velocity); + + extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); + +} + mip_cmd_result mip_filter_write_initialization_configuration(mip_interface* device, uint8_t wait_for_run_command, mip_filter_initialization_configuration_command_initial_condition_source initial_cond_src, mip_filter_initialization_configuration_command_alignment_selector auto_heading_alignment_selector, float initial_heading, float initial_pitch, float initial_roll, const float* initial_position, const float* initial_velocity, mip_filter_reference_frame reference_frame_selector) { microstrain_serializer serializer; @@ -3987,6 +4517,21 @@ void extract_mip_filter_adaptive_filter_options_command(microstrain_serializer* } } +void insert_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, const mip_filter_adaptive_filter_options_response* self) +{ + microstrain_insert_u8(serializer, self->level); + + microstrain_insert_u16(serializer, self->time_limit); + +} +void extract_mip_filter_adaptive_filter_options_response(microstrain_serializer* serializer, mip_filter_adaptive_filter_options_response* self) +{ + microstrain_extract_u8(serializer, &self->level); + + microstrain_extract_u16(serializer, &self->time_limit); + +} + mip_cmd_result mip_filter_write_adaptive_filter_options(mip_interface* device, uint8_t level, uint16_t time_limit) { microstrain_serializer serializer; @@ -4093,6 +4638,21 @@ void extract_mip_filter_multi_antenna_offset_command(microstrain_serializer* ser } } +void insert_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, const mip_filter_multi_antenna_offset_response* self) +{ + microstrain_insert_u8(serializer, self->receiver_id); + + insert_mip_vector3f(serializer, self->antenna_offset); + +} +void extract_mip_filter_multi_antenna_offset_response(microstrain_serializer* serializer, mip_filter_multi_antenna_offset_response* self) +{ + microstrain_extract_u8(serializer, &self->receiver_id); + + extract_mip_vector3f(serializer, self->antenna_offset); + +} + mip_cmd_result mip_filter_write_multi_antenna_offset(mip_interface* device, uint8_t receiver_id, const float* antenna_offset) { microstrain_serializer serializer; @@ -4213,6 +4773,25 @@ void extract_mip_filter_rel_pos_configuration_command(microstrain_serializer* se } } +void insert_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, const mip_filter_rel_pos_configuration_response* self) +{ + microstrain_insert_u8(serializer, self->source); + + insert_mip_filter_reference_frame(serializer, self->reference_frame_selector); + + insert_mip_vector3d(serializer, self->reference_coordinates); + +} +void extract_mip_filter_rel_pos_configuration_response(microstrain_serializer* serializer, mip_filter_rel_pos_configuration_response* self) +{ + microstrain_extract_u8(serializer, &self->source); + + extract_mip_filter_reference_frame(serializer, &self->reference_frame_selector); + + extract_mip_vector3d(serializer, self->reference_coordinates); + +} + mip_cmd_result mip_filter_write_rel_pos_configuration(mip_interface* device, uint8_t source, mip_filter_reference_frame reference_frame_selector, const double* reference_coordinates) { microstrain_serializer serializer; @@ -4327,6 +4906,21 @@ void extract_mip_filter_ref_point_lever_arm_command(microstrain_serializer* seri } } +void insert_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, const mip_filter_ref_point_lever_arm_response* self) +{ + insert_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, self->ref_point_sel); + + insert_mip_vector3f(serializer, self->lever_arm_offset); + +} +void extract_mip_filter_ref_point_lever_arm_response(microstrain_serializer* serializer, mip_filter_ref_point_lever_arm_response* self) +{ + extract_mip_filter_ref_point_lever_arm_command_reference_point_selector(serializer, &self->ref_point_sel); + + extract_mip_vector3f(serializer, self->lever_arm_offset); + +} + mip_cmd_result mip_filter_write_ref_point_lever_arm(mip_interface* device, mip_filter_ref_point_lever_arm_command_reference_point_selector ref_point_sel, const float* lever_arm_offset) { microstrain_serializer serializer; @@ -4477,6 +5071,21 @@ void extract_mip_filter_speed_lever_arm_command(microstrain_serializer* serializ } } +void insert_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, const mip_filter_speed_lever_arm_response* self) +{ + microstrain_insert_u8(serializer, self->source); + + insert_mip_vector3f(serializer, self->lever_arm_offset); + +} +void extract_mip_filter_speed_lever_arm_response(microstrain_serializer* serializer, mip_filter_speed_lever_arm_response* self) +{ + microstrain_extract_u8(serializer, &self->source); + + extract_mip_vector3f(serializer, self->lever_arm_offset); + +} + mip_cmd_result mip_filter_write_speed_lever_arm(mip_interface* device, uint8_t source, const float* lever_arm_offset) { microstrain_serializer serializer; @@ -4589,6 +5198,17 @@ void extract_mip_filter_wheeled_vehicle_constraint_control_command(microstrain_s } } +void insert_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, const mip_filter_wheeled_vehicle_constraint_control_response* self) +{ + microstrain_insert_u8(serializer, self->enable); + +} +void extract_mip_filter_wheeled_vehicle_constraint_control_response(microstrain_serializer* serializer, mip_filter_wheeled_vehicle_constraint_control_response* self) +{ + microstrain_extract_u8(serializer, &self->enable); + +} + mip_cmd_result mip_filter_write_wheeled_vehicle_constraint_control(mip_interface* device, uint8_t enable) { microstrain_serializer serializer; @@ -4686,6 +5306,17 @@ void extract_mip_filter_vertical_gyro_constraint_control_command(microstrain_ser } } +void insert_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, const mip_filter_vertical_gyro_constraint_control_response* self) +{ + microstrain_insert_u8(serializer, self->enable); + +} +void extract_mip_filter_vertical_gyro_constraint_control_response(microstrain_serializer* serializer, mip_filter_vertical_gyro_constraint_control_response* self) +{ + microstrain_extract_u8(serializer, &self->enable); + +} + mip_cmd_result mip_filter_write_vertical_gyro_constraint_control(mip_interface* device, uint8_t enable) { microstrain_serializer serializer; @@ -4787,6 +5418,21 @@ void extract_mip_filter_gnss_antenna_cal_control_command(microstrain_serializer* } } +void insert_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, const mip_filter_gnss_antenna_cal_control_response* self) +{ + microstrain_insert_u8(serializer, self->enable); + + microstrain_insert_float(serializer, self->max_offset); + +} +void extract_mip_filter_gnss_antenna_cal_control_response(microstrain_serializer* serializer, mip_filter_gnss_antenna_cal_control_response* self) +{ + microstrain_extract_u8(serializer, &self->enable); + + microstrain_extract_float(serializer, &self->max_offset); + +} + mip_cmd_result mip_filter_write_gnss_antenna_cal_control(mip_interface* device, uint8_t enable, float max_offset) { microstrain_serializer serializer; diff --git a/src/c/mip/definitions/commands_filter.h b/src/c/mip/definitions/commands_filter.h index 00ceac8e5..7c26898fd 100644 --- a/src/c/mip/definitions/commands_filter.h +++ b/src/c/mip/definitions/commands_filter.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include @@ -761,13 +761,9 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(mip_interface* device /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_filter_antenna_offset (0x0D,0x13) Antenna Offset [C] -/// Configure the GNSS antenna offset. +/// Set the sensor to GNSS antenna offset. /// -/// For 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. -/// -/// For 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center. -/// -/// This command should also be used for CV7 / GV7-INS NMEA Input over GPIO. +/// This is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. /// /// The magnitude of the offset vector is limited to 10 meters /// @@ -1716,7 +1712,7 @@ mip_cmd_result mip_filter_default_reference_position(mip_interface* device); /// /// Adaptive measurements can be enabled/disabled without the need for providing the additional parameters. /// In this case, only the function selector and enable value are required; all other parameters will remain at their previous values. -/// When auto-adaptive is selected, the filter and limit parameters are ignored. +/// When “auto-adaptive” is selected, the filter and limit parameters are ignored. /// Instead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality. /// /// @@ -1883,7 +1879,7 @@ enum mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_HEADING = 5, ///< External heading input MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_ALTIMETER = 6, ///< External pressure altimeter input MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_MAGNETOMETER = 7, ///< External magnetomer input - MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_BODY_FRAME_VEL = 8, ///< External body frame velocity input + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_VEHICLE_FRAME_VEL = 8, ///< External vehicle frame velocity input MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_ALL = 65535, ///< Save/load/reset all options }; typedef enum mip_filter_aiding_measurement_enable_command_aiding_source mip_filter_aiding_measurement_enable_command_aiding_source; diff --git a/src/c/mip/definitions/commands_gnss.c b/src/c/mip/definitions/commands_gnss.c index b45abcfbf..352c9eac9 100644 --- a/src/c/mip/definitions/commands_gnss.c +++ b/src/c/mip/definitions/commands_gnss.c @@ -103,6 +103,35 @@ void extract_mip_gnss_signal_configuration_command(microstrain_serializer* seria } } +void insert_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, const mip_gnss_signal_configuration_response* self) +{ + microstrain_insert_u8(serializer, self->gps_enable); + + microstrain_insert_u8(serializer, self->glonass_enable); + + microstrain_insert_u8(serializer, self->galileo_enable); + + microstrain_insert_u8(serializer, self->beidou_enable); + + for(unsigned int i=0; i < 4; i++) + microstrain_insert_u8(serializer, self->reserved[i]); + +} +void extract_mip_gnss_signal_configuration_response(microstrain_serializer* serializer, mip_gnss_signal_configuration_response* self) +{ + microstrain_extract_u8(serializer, &self->gps_enable); + + microstrain_extract_u8(serializer, &self->glonass_enable); + + microstrain_extract_u8(serializer, &self->galileo_enable); + + microstrain_extract_u8(serializer, &self->beidou_enable); + + for(unsigned int i=0; i < 4; i++) + microstrain_extract_u8(serializer, &self->reserved[i]); + +} + mip_cmd_result mip_gnss_write_signal_configuration(mip_interface* device, uint8_t gps_enable, uint8_t glonass_enable, uint8_t galileo_enable, uint8_t beidou_enable, const uint8_t* reserved) { microstrain_serializer serializer; @@ -229,6 +258,23 @@ void extract_mip_gnss_rtk_dongle_configuration_command(microstrain_serializer* s } } +void insert_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, const mip_gnss_rtk_dongle_configuration_response* self) +{ + microstrain_insert_u8(serializer, self->enable); + + for(unsigned int i=0; i < 3; i++) + microstrain_insert_u8(serializer, self->reserved[i]); + +} +void extract_mip_gnss_rtk_dongle_configuration_response(microstrain_serializer* serializer, mip_gnss_rtk_dongle_configuration_response* self) +{ + microstrain_extract_u8(serializer, &self->enable); + + for(unsigned int i=0; i < 3; i++) + microstrain_extract_u8(serializer, &self->reserved[i]); + +} + mip_cmd_result mip_gnss_write_rtk_dongle_configuration(mip_interface* device, uint8_t enable, const uint8_t* reserved) { microstrain_serializer serializer; diff --git a/src/c/mip/definitions/commands_gnss.h b/src/c/mip/definitions/commands_gnss.h index 5957ceedb..5713de72a 100644 --- a/src/c/mip/definitions/commands_gnss.h +++ b/src/c/mip/definitions/commands_gnss.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include diff --git a/src/c/mip/definitions/commands_rtk.c b/src/c/mip/definitions/commands_rtk.c index 6dbd49bf8..f3eaebae1 100644 --- a/src/c/mip/definitions/commands_rtk.c +++ b/src/c/mip/definitions/commands_rtk.c @@ -123,6 +123,17 @@ void extract_mip_rtk_connected_device_type_command(microstrain_serializer* seria } } +void insert_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, const mip_rtk_connected_device_type_response* self) +{ + insert_mip_rtk_connected_device_type_command_type(serializer, self->devType); + +} +void extract_mip_rtk_connected_device_type_response(microstrain_serializer* serializer, mip_rtk_connected_device_type_response* self) +{ + extract_mip_rtk_connected_device_type_command_type(serializer, &self->devType); + +} + mip_cmd_result mip_rtk_write_connected_device_type(mip_interface* device, mip_rtk_connected_device_type_command_type dev_type) { microstrain_serializer serializer; @@ -282,6 +293,29 @@ void extract_mip_rtk_service_status_command(microstrain_serializer* serializer, } +void insert_mip_rtk_service_status_response(microstrain_serializer* serializer, const mip_rtk_service_status_response* self) +{ + insert_mip_rtk_service_status_command_service_flags(serializer, self->flags); + + microstrain_insert_u32(serializer, self->receivedBytes); + + microstrain_insert_u32(serializer, self->lastBytes); + + microstrain_insert_u64(serializer, self->lastBytesTime); + +} +void extract_mip_rtk_service_status_response(microstrain_serializer* serializer, mip_rtk_service_status_response* self) +{ + extract_mip_rtk_service_status_command_service_flags(serializer, &self->flags); + + microstrain_extract_u32(serializer, &self->receivedBytes); + + microstrain_extract_u32(serializer, &self->lastBytes); + + microstrain_extract_u64(serializer, &self->lastBytesTime); + +} + mip_cmd_result mip_rtk_service_status(mip_interface* device, uint32_t reserved1, uint32_t reserved2, mip_rtk_service_status_command_service_flags* flags_out, uint32_t* received_bytes_out, uint32_t* last_bytes_out, uint64_t* last_bytes_time_out) { microstrain_serializer serializer; diff --git a/src/c/mip/definitions/commands_rtk.h b/src/c/mip/definitions/commands_rtk.h index 40b5d76f2..51df0136d 100644 --- a/src/c/mip/definitions/commands_rtk.h +++ b/src/c/mip/definitions/commands_rtk.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include diff --git a/src/c/mip/definitions/commands_system.c b/src/c/mip/definitions/commands_system.c index b79d9476c..f42478c3e 100644 --- a/src/c/mip/definitions/commands_system.c +++ b/src/c/mip/definitions/commands_system.c @@ -40,6 +40,17 @@ void extract_mip_system_comm_mode_command(microstrain_serializer* serializer, mi } } +void insert_mip_system_comm_mode_response(microstrain_serializer* serializer, const mip_system_comm_mode_response* self) +{ + microstrain_insert_u8(serializer, self->mode); + +} +void extract_mip_system_comm_mode_response(microstrain_serializer* serializer, mip_system_comm_mode_response* self) +{ + microstrain_extract_u8(serializer, &self->mode); + +} + mip_cmd_result mip_system_write_comm_mode(mip_interface* device, uint8_t mode) { microstrain_serializer serializer; diff --git a/src/c/mip/definitions/commands_system.h b/src/c/mip/definitions/commands_system.h index 71718063f..c30ccfec5 100644 --- a/src/c/mip/definitions/commands_system.h +++ b/src/c/mip/definitions/commands_system.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include diff --git a/src/c/mip/definitions/data_filter.h b/src/c/mip/definitions/data_filter.h index 475f7573b..9b3de23bb 100644 --- a/src/c/mip/definitions/data_filter.h +++ b/src/c/mip/definitions/data_filter.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include @@ -188,21 +188,18 @@ static inline void extract_mip_filter_status_flags(microstrain_serializer* seria enum mip_filter_aiding_measurement_type { - MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_DUAL_ANTENNA = 2, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING = 3, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_PRESSURE = 4, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_MAGNETOMETER = 5, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_SPEED = 6, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_POS_ECEF = 33, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_POS_LLH = 34, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_HEIGHT_ABOVE_ELLIPSOID = 35, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_ECEF = 40, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_NED = 41, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_BODY_FRAME = 42, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_HEADING_TRUE = 49, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_MAGNETIC_FIELD = 50, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_PRESSURE = 51, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_DUAL_ANTENNA = 2, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING = 3, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_PRESSURE = 4, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_MAGNETOMETER = 5, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_SPEED = 6, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_ECEF = 33, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_LLH = 34, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_ECEF = 40, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_NED = 41, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_VEHICLE_FRAME = 42, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING_TRUE = 49, ///< }; typedef enum mip_filter_aiding_measurement_type mip_filter_aiding_measurement_type; diff --git a/src/c/mip/definitions/data_gnss.h b/src/c/mip/definitions/data_gnss.h index 9be66b32f..4ddd6d1ab 100644 --- a/src/c/mip/definitions/data_gnss.h +++ b/src/c/mip/definitions/data_gnss.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include diff --git a/src/c/mip/definitions/data_sensor.h b/src/c/mip/definitions/data_sensor.h index a6aac295e..c8db3ec26 100644 --- a/src/c/mip/definitions/data_sensor.h +++ b/src/c/mip/definitions/data_sensor.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include diff --git a/src/c/mip/definitions/data_shared.h b/src/c/mip/definitions/data_shared.h index 1149c43bf..77170fb17 100644 --- a/src/c/mip/definitions/data_shared.h +++ b/src/c/mip/definitions/data_shared.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include diff --git a/src/c/mip/definitions/data_system.h b/src/c/mip/definitions/data_system.h index 54b4905f5..11f9c4cf9 100644 --- a/src/c/mip/definitions/data_system.h +++ b/src/c/mip/definitions/data_system.h @@ -1,6 +1,6 @@ #pragma once -#include "common.h" +#include #include #include #include diff --git a/src/cpp/mip/definitions/commands_3dm.cpp b/src/cpp/mip/definitions/commands_3dm.cpp index 44f3e61a2..0038aed3a 100644 --- a/src/cpp/mip/definitions/commands_3dm.cpp +++ b/src/cpp/mip/definitions/commands_3dm.cpp @@ -180,6 +180,22 @@ void ImuMessageFormat::extract(Serializer& serializer) } } +void ImuMessageFormat::Response::insert(Serializer& serializer) const +{ + serializer.insert(num_descriptors); + + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); + +} +void ImuMessageFormat::Response::extract(Serializer& serializer) +{ + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); + +} + TypedResult writeImuMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -277,6 +293,22 @@ void GpsMessageFormat::extract(Serializer& serializer) } } +void GpsMessageFormat::Response::insert(Serializer& serializer) const +{ + serializer.insert(num_descriptors); + + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); + +} +void GpsMessageFormat::Response::extract(Serializer& serializer) +{ + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); + +} + TypedResult writeGpsMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -374,6 +406,22 @@ void FilterMessageFormat::extract(Serializer& serializer) } } +void FilterMessageFormat::Response::insert(Serializer& serializer) const +{ + serializer.insert(num_descriptors); + + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); + +} +void FilterMessageFormat::Response::extract(Serializer& serializer) +{ + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); + +} + TypedResult writeFilterMessageFormat(C::mip_interface& device, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -454,6 +502,17 @@ void ImuGetBaseRate::extract(Serializer& serializer) (void)serializer; } +void ImuGetBaseRate::Response::insert(Serializer& serializer) const +{ + serializer.insert(rate); + +} +void ImuGetBaseRate::Response::extract(Serializer& serializer) +{ + serializer.extract(rate); + +} + TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -482,6 +541,17 @@ void GpsGetBaseRate::extract(Serializer& serializer) (void)serializer; } +void GpsGetBaseRate::Response::insert(Serializer& serializer) const +{ + serializer.insert(rate); + +} +void GpsGetBaseRate::Response::extract(Serializer& serializer) +{ + serializer.extract(rate); + +} + TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -510,6 +580,17 @@ void FilterGetBaseRate::extract(Serializer& serializer) (void)serializer; } +void FilterGetBaseRate::Response::insert(Serializer& serializer) const +{ + serializer.insert(rate); + +} +void FilterGetBaseRate::Response::extract(Serializer& serializer) +{ + serializer.extract(rate); + +} + TypedResult filterGetBaseRate(C::mip_interface& device, uint16_t* rateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -583,6 +664,21 @@ void GetBaseRate::extract(Serializer& serializer) } +void GetBaseRate::Response::insert(Serializer& serializer) const +{ + serializer.insert(desc_set); + + serializer.insert(rate); + +} +void GetBaseRate::Response::extract(Serializer& serializer) +{ + serializer.extract(desc_set); + + serializer.extract(rate); + +} + TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, uint16_t* rateOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -639,6 +735,26 @@ void MessageFormat::extract(Serializer& serializer) } } +void MessageFormat::Response::insert(Serializer& serializer) const +{ + serializer.insert(desc_set); + + serializer.insert(num_descriptors); + + for(unsigned int i=0; i < num_descriptors; i++) + serializer.insert(descriptors[i]); + +} +void MessageFormat::Response::extract(Serializer& serializer) +{ + serializer.extract(desc_set); + + serializer.extract_count(num_descriptors, sizeof(descriptors)/sizeof(descriptors[0])); + for(unsigned int i=0; i < num_descriptors; i++) + serializer.extract(descriptors[i]); + +} + TypedResult writeMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t numDescriptors, const DescriptorRate* descriptors) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -785,6 +901,22 @@ void NmeaMessageFormat::extract(Serializer& serializer) } } +void NmeaMessageFormat::Response::insert(Serializer& serializer) const +{ + serializer.insert(count); + + for(unsigned int i=0; i < count; i++) + serializer.insert(format_entries[i]); + +} +void NmeaMessageFormat::Response::extract(Serializer& serializer) +{ + serializer.extract_count(count, sizeof(format_entries)/sizeof(format_entries[0])); + for(unsigned int i=0; i < count; i++) + serializer.extract(format_entries[i]); + +} + TypedResult writeNmeaMessageFormat(C::mip_interface& device, uint8_t count, const NmeaMessage* formatEntries) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -918,6 +1050,17 @@ void UartBaudrate::extract(Serializer& serializer) } } +void UartBaudrate::Response::insert(Serializer& serializer) const +{ + serializer.insert(baud); + +} +void UartBaudrate::Response::extract(Serializer& serializer) +{ + serializer.extract(baud); + +} + TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t baud) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1036,6 +1179,21 @@ void DatastreamControl::extract(Serializer& serializer) } } +void DatastreamControl::Response::insert(Serializer& serializer) const +{ + serializer.insert(desc_set); + + serializer.insert(enabled); + +} +void DatastreamControl::Response::extract(Serializer& serializer) +{ + serializer.extract(desc_set); + + serializer.extract(enabled); + +} + TypedResult writeDatastreamControl(C::mip_interface& device, uint8_t descSet, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1170,6 +1328,30 @@ void ConstellationSettings::extract(Serializer& serializer) } } +void ConstellationSettings::Response::insert(Serializer& serializer) const +{ + serializer.insert(max_channels_available); + + serializer.insert(max_channels_use); + + serializer.insert(config_count); + + for(unsigned int i=0; i < config_count; i++) + serializer.insert(settings[i]); + +} +void ConstellationSettings::Response::extract(Serializer& serializer) +{ + serializer.extract(max_channels_available); + + serializer.extract(max_channels_use); + + serializer.extract_count(config_count, sizeof(settings)/sizeof(settings[0])); + for(unsigned int i=0; i < config_count; i++) + serializer.extract(settings[i]); + +} + TypedResult writeConstellationSettings(C::mip_interface& device, uint16_t maxChannels, uint8_t configCount, const ConstellationSettings::Settings* settings) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1283,6 +1465,30 @@ void GnssSbasSettings::extract(Serializer& serializer) } } +void GnssSbasSettings::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable_sbas); + + serializer.insert(sbas_options); + + serializer.insert(num_included_prns); + + for(unsigned int i=0; i < num_included_prns; i++) + serializer.insert(included_prns[i]); + +} +void GnssSbasSettings::Response::extract(Serializer& serializer) +{ + serializer.extract(enable_sbas); + + serializer.extract(sbas_options); + + serializer.extract_count(num_included_prns, sizeof(included_prns)/sizeof(included_prns[0])); + for(unsigned int i=0; i < num_included_prns; i++) + serializer.extract(included_prns[i]); + +} + TypedResult writeGnssSbasSettings(C::mip_interface& device, uint8_t enableSbas, GnssSbasSettings::SBASOptions sbasOptions, uint8_t numIncludedPrns, const uint16_t* includedPrns) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1389,6 +1595,21 @@ void GnssAssistedFix::extract(Serializer& serializer) } } +void GnssAssistedFix::Response::insert(Serializer& serializer) const +{ + serializer.insert(option); + + serializer.insert(flags); + +} +void GnssAssistedFix::Response::extract(Serializer& serializer) +{ + serializer.extract(option); + + serializer.extract(flags); + +} + TypedResult writeGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption option, uint8_t flags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1488,6 +1709,25 @@ void GnssTimeAssistance::extract(Serializer& serializer) } } +void GnssTimeAssistance::Response::insert(Serializer& serializer) const +{ + serializer.insert(tow); + + serializer.insert(week_number); + + serializer.insert(accuracy); + +} +void GnssTimeAssistance::Response::extract(Serializer& serializer) +{ + serializer.extract(tow); + + serializer.extract(week_number); + + serializer.extract(accuracy); + +} + TypedResult writeGnssTimeAssistance(C::mip_interface& device, double tow, uint16_t weekNumber, float accuracy) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1570,6 +1810,33 @@ void ImuLowpassFilter::extract(Serializer& serializer) } } +void ImuLowpassFilter::Response::insert(Serializer& serializer) const +{ + serializer.insert(target_descriptor); + + serializer.insert(enable); + + serializer.insert(manual); + + serializer.insert(frequency); + + serializer.insert(reserved); + +} +void ImuLowpassFilter::Response::extract(Serializer& serializer) +{ + serializer.extract(target_descriptor); + + serializer.extract(enable); + + serializer.extract(manual); + + serializer.extract(frequency); + + serializer.extract(reserved); + +} + TypedResult writeImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool enable, bool manual, uint16_t frequency, uint8_t reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1683,6 +1950,17 @@ void PpsSource::extract(Serializer& serializer) } } +void PpsSource::Response::insert(Serializer& serializer) const +{ + serializer.insert(source); + +} +void PpsSource::Response::extract(Serializer& serializer) +{ + serializer.extract(source); + +} + TypedResult writePpsSource(C::mip_interface& device, PpsSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1781,6 +2059,29 @@ void GpioConfig::extract(Serializer& serializer) } } +void GpioConfig::Response::insert(Serializer& serializer) const +{ + serializer.insert(pin); + + serializer.insert(feature); + + serializer.insert(behavior); + + serializer.insert(pin_mode); + +} +void GpioConfig::Response::extract(Serializer& serializer) +{ + serializer.extract(pin); + + serializer.extract(feature); + + serializer.extract(behavior); + + serializer.extract(pin_mode); + +} + TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature feature, GpioConfig::Behavior behavior, GpioConfig::PinMode pinMode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1899,6 +2200,21 @@ void GpioState::extract(Serializer& serializer) } } +void GpioState::Response::insert(Serializer& serializer) const +{ + serializer.insert(pin); + + serializer.insert(state); + +} +void GpioState::Response::extract(Serializer& serializer) +{ + serializer.extract(pin); + + serializer.extract(state); + +} + TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, bool state) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1969,6 +2285,25 @@ void Odometer::extract(Serializer& serializer) } } +void Odometer::Response::insert(Serializer& serializer) const +{ + serializer.insert(mode); + + serializer.insert(scaling); + + serializer.insert(uncertainty); + +} +void Odometer::Response::extract(Serializer& serializer) +{ + serializer.extract(mode); + + serializer.extract(scaling); + + serializer.extract(uncertainty); + +} + TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mode, float scaling, float uncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2070,6 +2405,30 @@ void GetEventSupport::extract(Serializer& serializer) } +void GetEventSupport::Response::insert(Serializer& serializer) const +{ + serializer.insert(query); + + serializer.insert(max_instances); + + serializer.insert(num_entries); + + for(unsigned int i=0; i < num_entries; i++) + serializer.insert(entries[i]); + +} +void GetEventSupport::Response::extract(Serializer& serializer) +{ + serializer.extract(query); + + serializer.extract(max_instances); + + serializer.extract_count(num_entries, sizeof(entries)/sizeof(entries[0])); + for(unsigned int i=0; i < num_entries; i++) + serializer.extract(entries[i]); + +} + TypedResult getEventSupport(C::mip_interface& device, GetEventSupport::Query query, uint8_t* maxInstancesOut, uint8_t* numEntriesOut, uint8_t numEntriesOutMax, GetEventSupport::Info* entriesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2126,6 +2485,21 @@ void EventControl::extract(Serializer& serializer) } } +void EventControl::Response::insert(Serializer& serializer) const +{ + serializer.insert(instance); + + serializer.insert(mode); + +} +void EventControl::Response::extract(Serializer& serializer) +{ + serializer.extract(instance); + + serializer.extract(mode); + +} + TypedResult writeEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2234,6 +2608,22 @@ void GetEventTriggerStatus::extract(Serializer& serializer) } +void GetEventTriggerStatus::Response::insert(Serializer& serializer) const +{ + serializer.insert(count); + + for(unsigned int i=0; i < count; i++) + serializer.insert(triggers[i]); + +} +void GetEventTriggerStatus::Response::extract(Serializer& serializer) +{ + serializer.extract_count(count, sizeof(triggers)/sizeof(triggers[0])); + for(unsigned int i=0; i < count; i++) + serializer.extract(triggers[i]); + +} + TypedResult getEventTriggerStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventTriggerStatus::Entry* triggersOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2295,6 +2685,22 @@ void GetEventActionStatus::extract(Serializer& serializer) } +void GetEventActionStatus::Response::insert(Serializer& serializer) const +{ + serializer.insert(count); + + for(unsigned int i=0; i < count; i++) + serializer.insert(actions[i]); + +} +void GetEventActionStatus::Response::extract(Serializer& serializer) +{ + serializer.extract_count(count, sizeof(actions)/sizeof(actions[0])); + for(unsigned int i=0; i < count; i++) + serializer.extract(actions[i]); + +} + TypedResult getEventActionStatus(C::mip_interface& device, uint8_t requestedCount, const uint8_t* requestedInstances, uint8_t* countOut, uint8_t countOutMax, GetEventActionStatus::Entry* actionsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2475,6 +2881,51 @@ void EventTrigger::extract(Serializer& serializer) } } +void EventTrigger::Response::insert(Serializer& serializer) const +{ + serializer.insert(instance); + + serializer.insert(type); + + if( type == EventTrigger::Type::GPIO ) + { + serializer.insert(parameters.gpio); + + } + if( type == EventTrigger::Type::THRESHOLD ) + { + serializer.insert(parameters.threshold); + + } + if( type == EventTrigger::Type::COMBINATION ) + { + serializer.insert(parameters.combination); + + } +} +void EventTrigger::Response::extract(Serializer& serializer) +{ + serializer.extract(instance); + + serializer.extract(type); + + if( type == EventTrigger::Type::GPIO ) + { + serializer.extract(parameters.gpio); + + } + if( type == EventTrigger::Type::THRESHOLD ) + { + serializer.extract(parameters.threshold); + + } + if( type == EventTrigger::Type::COMBINATION ) + { + serializer.extract(parameters.combination); + + } +} + TypedResult writeEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type type, const EventTrigger::Parameters& parameters) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2670,6 +3121,45 @@ void EventAction::extract(Serializer& serializer) } } +void EventAction::Response::insert(Serializer& serializer) const +{ + serializer.insert(instance); + + serializer.insert(trigger); + + serializer.insert(type); + + if( type == EventAction::Type::GPIO ) + { + serializer.insert(parameters.gpio); + + } + if( type == EventAction::Type::MESSAGE ) + { + serializer.insert(parameters.message); + + } +} +void EventAction::Response::extract(Serializer& serializer) +{ + serializer.extract(instance); + + serializer.extract(trigger); + + serializer.extract(type); + + if( type == EventAction::Type::GPIO ) + { + serializer.extract(parameters.gpio); + + } + if( type == EventAction::Type::MESSAGE ) + { + serializer.extract(parameters.message); + + } +} + TypedResult writeEventAction(C::mip_interface& device, uint8_t instance, uint8_t trigger, EventAction::Type type, const EventAction::Parameters& parameters) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2793,6 +3283,17 @@ void AccelBias::extract(Serializer& serializer) } } +void AccelBias::Response::insert(Serializer& serializer) const +{ + serializer.insert(bias); + +} +void AccelBias::Response::extract(Serializer& serializer) +{ + serializer.extract(bias); + +} + TypedResult writeAccelBias(C::mip_interface& device, const float* bias) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2882,6 +3383,17 @@ void GyroBias::extract(Serializer& serializer) } } +void GyroBias::Response::insert(Serializer& serializer) const +{ + serializer.insert(bias); + +} +void GyroBias::Response::extract(Serializer& serializer) +{ + serializer.extract(bias); + +} + TypedResult writeGyroBias(C::mip_interface& device, const float* bias) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2961,6 +3473,17 @@ void CaptureGyroBias::extract(Serializer& serializer) } +void CaptureGyroBias::Response::insert(Serializer& serializer) const +{ + serializer.insert(bias); + +} +void CaptureGyroBias::Response::extract(Serializer& serializer) +{ + serializer.extract(bias); + +} + TypedResult captureGyroBias(C::mip_interface& device, uint16_t averagingTimeMs, float* biasOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3007,6 +3530,17 @@ void MagHardIronOffset::extract(Serializer& serializer) } } +void MagHardIronOffset::Response::insert(Serializer& serializer) const +{ + serializer.insert(offset); + +} +void MagHardIronOffset::Response::extract(Serializer& serializer) +{ + serializer.extract(offset); + +} + TypedResult writeMagHardIronOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3096,6 +3630,17 @@ void MagSoftIronMatrix::extract(Serializer& serializer) } } +void MagSoftIronMatrix::Response::insert(Serializer& serializer) const +{ + serializer.insert(offset); + +} +void MagSoftIronMatrix::Response::extract(Serializer& serializer) +{ + serializer.extract(offset); + +} + TypedResult writeMagSoftIronMatrix(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3185,6 +3730,17 @@ void ConingScullingEnable::extract(Serializer& serializer) } } +void ConingScullingEnable::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + +} +void ConingScullingEnable::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + +} + TypedResult writeConingScullingEnable(C::mip_interface& device, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3279,6 +3835,25 @@ void Sensor2VehicleTransformEuler::extract(Serializer& serializer) } } +void Sensor2VehicleTransformEuler::Response::insert(Serializer& serializer) const +{ + serializer.insert(roll); + + serializer.insert(pitch); + + serializer.insert(yaw); + +} +void Sensor2VehicleTransformEuler::Response::extract(Serializer& serializer) +{ + serializer.extract(roll); + + serializer.extract(pitch); + + serializer.extract(yaw); + +} + TypedResult writeSensor2VehicleTransformEuler(C::mip_interface& device, float roll, float pitch, float yaw) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3375,6 +3950,17 @@ void Sensor2VehicleTransformQuaternion::extract(Serializer& serializer) } } +void Sensor2VehicleTransformQuaternion::Response::insert(Serializer& serializer) const +{ + serializer.insert(q); + +} +void Sensor2VehicleTransformQuaternion::Response::extract(Serializer& serializer) +{ + serializer.extract(q); + +} + TypedResult writeSensor2VehicleTransformQuaternion(C::mip_interface& device, const float* q) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3464,6 +4050,17 @@ void Sensor2VehicleTransformDcm::extract(Serializer& serializer) } } +void Sensor2VehicleTransformDcm::Response::insert(Serializer& serializer) const +{ + serializer.insert(dcm); + +} +void Sensor2VehicleTransformDcm::Response::extract(Serializer& serializer) +{ + serializer.extract(dcm); + +} + TypedResult writeSensor2VehicleTransformDcm(C::mip_interface& device, const float* dcm) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3565,6 +4162,29 @@ void ComplementaryFilter::extract(Serializer& serializer) } } +void ComplementaryFilter::Response::insert(Serializer& serializer) const +{ + serializer.insert(pitch_roll_enable); + + serializer.insert(heading_enable); + + serializer.insert(pitch_roll_time_constant); + + serializer.insert(heading_time_constant); + +} +void ComplementaryFilter::Response::extract(Serializer& serializer) +{ + serializer.extract(pitch_roll_enable); + + serializer.extract(heading_enable); + + serializer.extract(pitch_roll_time_constant); + + serializer.extract(heading_time_constant); + +} + TypedResult writeComplementaryFilter(C::mip_interface& device, bool pitchRollEnable, bool headingEnable, float pitchRollTimeConstant, float headingTimeConstant) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3670,6 +4290,21 @@ void SensorRange::extract(Serializer& serializer) } } +void SensorRange::Response::insert(Serializer& serializer) const +{ + serializer.insert(sensor); + + serializer.insert(setting); + +} +void SensorRange::Response::extract(Serializer& serializer) +{ + serializer.extract(sensor); + + serializer.extract(setting); + +} + TypedResult writeSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t setting) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3773,6 +4408,26 @@ void CalibratedSensorRanges::extract(Serializer& serializer) } +void CalibratedSensorRanges::Response::insert(Serializer& serializer) const +{ + serializer.insert(sensor); + + serializer.insert(num_ranges); + + for(unsigned int i=0; i < num_ranges; i++) + serializer.insert(ranges[i]); + +} +void CalibratedSensorRanges::Response::extract(Serializer& serializer) +{ + serializer.extract(sensor); + + serializer.extract_count(num_ranges, sizeof(ranges)/sizeof(ranges[0])); + for(unsigned int i=0; i < num_ranges; i++) + serializer.extract(ranges[i]); + +} + TypedResult calibratedSensorRanges(C::mip_interface& device, SensorRangeType sensor, uint8_t* numRangesOut, uint8_t numRangesOutMax, CalibratedSensorRanges::Entry* rangesOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3838,6 +4493,33 @@ void LowpassFilter::extract(Serializer& serializer) } } +void LowpassFilter::Response::insert(Serializer& serializer) const +{ + serializer.insert(desc_set); + + serializer.insert(field_desc); + + serializer.insert(enable); + + serializer.insert(manual); + + serializer.insert(frequency); + +} +void LowpassFilter::Response::extract(Serializer& serializer) +{ + serializer.extract(desc_set); + + serializer.extract(field_desc); + + serializer.extract(enable); + + serializer.extract(manual); + + serializer.extract(frequency); + +} + TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool enable, bool manual, float frequency) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/cpp/mip/definitions/commands_3dm.hpp b/src/cpp/mip/definitions/commands_3dm.hpp index d80419d5b..4120f5ea7 100644 --- a/src/cpp/mip/definitions/commands_3dm.hpp +++ b/src/cpp/mip/definitions/commands_3dm.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include @@ -153,8 +153,8 @@ struct NmeaMessage VTG = 5, ///< Course over Ground. Source can be the Filter or GNSS1/2 datasets. HDT = 6, ///< Heading, True. Source can be the Filter or GNSS1/2 datasets. ZDA = 7, ///< Time & Date. Source must be the GNSS1 or GNSS2 datasets. - MSRA = 129, ///< MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. - MSRR = 130, ///< MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. + PKRA = 129, ///< Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. + PKRR = 130, ///< Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. }; enum class TalkerID : uint8_t @@ -1445,8 +1445,6 @@ struct ConstellationSettings OptionFlags& operator|=(uint16_t val) { return *this = value | val; } OptionFlags& operator&=(uint16_t val) { return *this = value & val; } - bool l1saif() const { return (value & L1SAIF) > 0; } - void l1saif(bool val) { if(val) value |= L1SAIF; else value &= ~L1SAIF; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1571,12 +1569,6 @@ struct GnssSbasSettings SBASOptions& operator|=(uint16_t val) { return *this = value | val; } SBASOptions& operator&=(uint16_t val) { return *this = value & val; } - bool enableRanging() const { return (value & ENABLE_RANGING) > 0; } - void enableRanging(bool val) { if(val) value |= ENABLE_RANGING; else value &= ~ENABLE_RANGING; } - bool enableCorrections() const { return (value & ENABLE_CORRECTIONS) > 0; } - void enableCorrections(bool val) { if(val) value |= ENABLE_CORRECTIONS; else value &= ~ENABLE_CORRECTIONS; } - bool applyIntegrity() const { return (value & APPLY_INTEGRITY) > 0; } - void applyIntegrity(bool val) { if(val) value |= APPLY_INTEGRITY; else value &= ~APPLY_INTEGRITY; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2097,12 +2089,6 @@ struct GpioConfig PinMode& operator|=(uint8_t val) { return *this = value | val; } PinMode& operator&=(uint8_t val) { return *this = value & val; } - bool openDrain() const { return (value & OPEN_DRAIN) > 0; } - void openDrain(bool val) { if(val) value |= OPEN_DRAIN; else value &= ~OPEN_DRAIN; } - bool pulldown() const { return (value & PULLDOWN) > 0; } - void pulldown(bool val) { if(val) value |= PULLDOWN; else value &= ~PULLDOWN; } - bool pullup() const { return (value & PULLUP) > 0; } - void pullup(bool val) { if(val) value |= PULLUP; else value &= ~PULLUP; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2592,12 +2578,6 @@ struct GetEventTriggerStatus Status& operator|=(uint8_t val) { return *this = value | val; } Status& operator&=(uint8_t val) { return *this = value & val; } - bool active() const { return (value & ACTIVE) > 0; } - void active(bool val) { if(val) value |= ACTIVE; else value &= ~ACTIVE; } - bool enabled() const { return (value & ENABLED) > 0; } - void enabled(bool val) { if(val) value |= ENABLED; else value &= ~ENABLED; } - bool test() const { return (value & TEST) > 0; } - void test(bool val) { if(val) value |= TEST; else value &= ~TEST; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_aiding.cpp b/src/cpp/mip/definitions/commands_aiding.cpp index b3f2627c2..a477b84d9 100644 --- a/src/cpp/mip/definitions/commands_aiding.cpp +++ b/src/cpp/mip/definitions/commands_aiding.cpp @@ -209,7 +209,7 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); } -void EchoControl::insert(Serializer& serializer) const +void AidingEchoControl::insert(Serializer& serializer) const { serializer.insert(function); @@ -219,7 +219,7 @@ void EchoControl::insert(Serializer& serializer) const } } -void EchoControl::extract(Serializer& serializer) +void AidingEchoControl::extract(Serializer& serializer) { serializer.extract(function); @@ -230,7 +230,7 @@ void EchoControl::extract(Serializer& serializer) } } -TypedResult writeEchoControl(C::mip_interface& device, EchoControl::Mode mode) +TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -242,7 +242,7 @@ TypedResult writeEchoControl(C::mip_interface& device, EchoControl: return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -TypedResult readEchoControl(C::mip_interface& device, EchoControl::Mode* modeOut) +TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -251,7 +251,7 @@ TypedResult readEchoControl(C::mip_interface& device, EchoControl:: assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -265,7 +265,7 @@ TypedResult readEchoControl(C::mip_interface& device, EchoControl:: } return result; } -TypedResult saveEchoControl(C::mip_interface& device) +TypedResult saveAidingEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -275,7 +275,7 @@ TypedResult saveEchoControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -TypedResult loadEchoControl(C::mip_interface& device) +TypedResult loadAidingEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -285,7 +285,7 @@ TypedResult loadEchoControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -TypedResult defaultEchoControl(C::mip_interface& device) +TypedResult defaultAidingEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -295,7 +295,7 @@ TypedResult defaultEchoControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -void PosEcef::insert(Serializer& serializer) const +void EcefPos::insert(Serializer& serializer) const { serializer.insert(time); @@ -308,7 +308,7 @@ void PosEcef::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void PosEcef::extract(Serializer& serializer) +void EcefPos::extract(Serializer& serializer) { serializer.extract(time); @@ -322,7 +322,7 @@ void PosEcef::extract(Serializer& serializer) } -TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, PosEcef::ValidFlags validFlags) +TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -345,7 +345,7 @@ TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)serializer.length()); } -void PosLlh::insert(Serializer& serializer) const +void LlhPos::insert(Serializer& serializer) const { serializer.insert(time); @@ -362,7 +362,7 @@ void PosLlh::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void PosLlh::extract(Serializer& serializer) +void LlhPos::extract(Serializer& serializer) { serializer.extract(time); @@ -380,7 +380,7 @@ void PosLlh::extract(Serializer& serializer) } -TypedResult posLlh(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, PosLlh::ValidFlags validFlags) +TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -405,7 +405,7 @@ TypedResult posLlh(C::mip_interface& device, const Time& time, uint8_t f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)serializer.length()); } -void HeightAboveEllipsoid::insert(Serializer& serializer) const +void Height::insert(Serializer& serializer) const { serializer.insert(time); @@ -418,7 +418,7 @@ void HeightAboveEllipsoid::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void HeightAboveEllipsoid::extract(Serializer& serializer) +void Height::extract(Serializer& serializer) { serializer.extract(time); @@ -432,7 +432,7 @@ void HeightAboveEllipsoid::extract(Serializer& serializer) } -TypedResult heightAboveEllipsoid(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) +TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -449,9 +449,9 @@ TypedResult heightAboveEllipsoid(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABOVE_ELLIPSOID, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABS, buffer, (uint8_t)serializer.length()); } -void VelEcef::insert(Serializer& serializer) const +void EcefVel::insert(Serializer& serializer) const { serializer.insert(time); @@ -464,7 +464,7 @@ void VelEcef::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void VelEcef::extract(Serializer& serializer) +void EcefVel::extract(Serializer& serializer) { serializer.extract(time); @@ -478,7 +478,7 @@ void VelEcef::extract(Serializer& serializer) } -TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelEcef::ValidFlags validFlags) +TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -501,7 +501,7 @@ TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)serializer.length()); } -void VelNed::insert(Serializer& serializer) const +void NedVel::insert(Serializer& serializer) const { serializer.insert(time); @@ -514,7 +514,7 @@ void VelNed::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void VelNed::extract(Serializer& serializer) +void NedVel::extract(Serializer& serializer) { serializer.extract(time); @@ -528,7 +528,7 @@ void VelNed::extract(Serializer& serializer) } -TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelNed::ValidFlags validFlags) +TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -551,7 +551,7 @@ TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)serializer.length()); } -void VelBodyFrame::insert(Serializer& serializer) const +void VehicleFixedFrameVelocity::insert(Serializer& serializer) const { serializer.insert(time); @@ -564,7 +564,7 @@ void VelBodyFrame::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void VelBodyFrame::extract(Serializer& serializer) +void VehicleFixedFrameVelocity::extract(Serializer& serializer) { serializer.extract(time); @@ -578,7 +578,7 @@ void VelBodyFrame::extract(Serializer& serializer) } -TypedResult velBodyFrame(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelBodyFrame::ValidFlags validFlags) +TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -599,9 +599,9 @@ TypedResult velBodyFrame(C::mip_interface& device, const Time& tim assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_BODY_FRAME, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ODOM, buffer, (uint8_t)serializer.length()); } -void HeadingTrue::insert(Serializer& serializer) const +void TrueHeading::insert(Serializer& serializer) const { serializer.insert(time); @@ -614,7 +614,7 @@ void HeadingTrue::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void HeadingTrue::extract(Serializer& serializer) +void TrueHeading::extract(Serializer& serializer) { serializer.extract(time); @@ -628,7 +628,7 @@ void HeadingTrue::extract(Serializer& serializer) } -TypedResult headingTrue(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) +TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); diff --git a/src/cpp/mip/definitions/commands_aiding.hpp b/src/cpp/mip/definitions/commands_aiding.hpp index 95b9c0d3d..79fa1212f 100644 --- a/src/cpp/mip/definitions/commands_aiding.hpp +++ b/src/cpp/mip/definitions/commands_aiding.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include @@ -28,29 +28,29 @@ namespace commands_aiding { enum { - DESCRIPTOR_SET = 0x13, - - CMD_FRAME_CONFIG = 0x01, - CMD_LOCAL_FRAME = 0x03, - CMD_ECHO_CONTROL = 0x1F, - CMD_POS_LOCAL = 0x20, - CMD_POS_ECEF = 0x21, - CMD_POS_LLH = 0x22, - CMD_HEIGHT_ABOVE_ELLIPSOID = 0x23, - CMD_HEIGHT_REL = 0x24, - CMD_VEL_ECEF = 0x28, - CMD_VEL_NED = 0x29, - CMD_VEL_BODY_FRAME = 0x2A, - CMD_WHEELSPEED = 0x2B, - CMD_HEADING_TRUE = 0x31, - CMD_MAGNETIC_FIELD = 0x32, - CMD_PRESSURE = 0x33, - CMD_DELTA_POSITION = 0x38, - CMD_DELTA_ATTITUDE = 0x39, - CMD_ANGULAR_RATE_LOCAL = 0x3A, - - REPLY_FRAME_CONFIG = 0x81, - REPLY_ECHO_CONTROL = 0x9F, + DESCRIPTOR_SET = 0x13, + + CMD_FRAME_CONFIG = 0x01, + CMD_LOCAL_FRAME = 0x03, + CMD_ECHO_CONTROL = 0x1F, + CMD_POS_LOCAL = 0x20, + CMD_POS_ECEF = 0x21, + CMD_POS_LLH = 0x22, + CMD_HEIGHT_ABS = 0x23, + CMD_HEIGHT_REL = 0x24, + CMD_VEL_ECEF = 0x28, + CMD_VEL_NED = 0x29, + CMD_VEL_ODOM = 0x2A, + CMD_WHEELSPEED = 0x2B, + CMD_HEADING_TRUE = 0x31, + CMD_MAGNETIC_FIELD = 0x32, + CMD_PRESSURE = 0x33, + CMD_DELTA_POSITION = 0x38, + CMD_DELTA_ATTITUDE = 0x39, + CMD_LOCAL_ANGULAR_RATE = 0x3A, + + REPLY_FRAME_CONFIG = 0x81, + REPLY_ECHO_CONTROL = 0x9F, }; //////////////////////////////////////////////////////////////////////////////// @@ -83,9 +83,8 @@ struct Time //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_aiding_frame_config (0x13,0x01) Frame Config [CPP] -/// Defines an aiding frame associated with a specific sensor frame ID. -/// The frame ID used in this command should mirror the frame ID used in the aiding command -/// (if that aiding measurement is measured in this reference frame). +/// Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command +/// should mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame) /// /// This transform satisfies the following relationship: /// @@ -206,12 +205,12 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_echo_control (0x13,0x1F) Echo Control [CPP] +///@defgroup cpp_aiding_aiding_echo_control (0x13,0x1F) Aiding Echo Control [CPP] /// Controls command response behavior to external aiding commands /// ///@{ -struct EchoControl +struct AidingEchoControl { enum class Mode : uint8_t { @@ -228,7 +227,7 @@ struct EchoControl static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_ECHO_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "EchoControl"; + static constexpr const char* NAME = "AidingEchoControl"; static constexpr const char* DOC_NAME = "Aiding Command Echo Control"; static constexpr const bool HAS_FUNCTION_SELECTOR = true; @@ -242,9 +241,9 @@ struct EchoControl return std::make_tuple(std::ref(mode)); } - static EchoControl create_sld_all(::mip::FunctionSelector function) + static AidingEchoControl create_sld_all(::mip::FunctionSelector function) { - EchoControl cmd; + AidingEchoControl cmd; cmd.function = function; return cmd; } @@ -262,7 +261,7 @@ struct EchoControl static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::REPLY_ECHO_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "EchoControl::Response"; + static constexpr const char* NAME = "AidingEchoControl::Response"; static constexpr const char* DOC_NAME = "Aiding Command Echo Control Response"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -282,21 +281,21 @@ struct EchoControl }; }; -TypedResult writeEchoControl(C::mip_interface& device, EchoControl::Mode mode); -TypedResult readEchoControl(C::mip_interface& device, EchoControl::Mode* modeOut); -TypedResult saveEchoControl(C::mip_interface& device); -TypedResult loadEchoControl(C::mip_interface& device); -TypedResult defaultEchoControl(C::mip_interface& device); +TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode); +TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut); +TypedResult saveAidingEchoControl(C::mip_interface& device); +TypedResult loadAidingEchoControl(C::mip_interface& device); +TypedResult defaultAidingEchoControl(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_pos_ecef (0x13,0x21) Pos Ecef [CPP] +///@defgroup cpp_aiding_ecef_pos (0x13,0x21) Ecef Pos [CPP] /// Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system. /// ///@{ -struct PosEcef +struct EcefPos { struct ValidFlags : Bitfield { @@ -319,12 +318,6 @@ struct PosEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -339,7 +332,7 @@ struct PosEcef static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_POS_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "PosEcef"; + static constexpr const char* NAME = "EcefPos"; static constexpr const char* DOC_NAME = "ECEF Position"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -359,19 +352,18 @@ struct PosEcef typedef void Response; }; -TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, PosEcef::ValidFlags validFlags); +TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_pos_llh (0x13,0x22) Pos Llh [CPP] -/// Geodetic position aiding command. -/// Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. +///@defgroup cpp_aiding_llh_pos (0x13,0x22) Llh Pos [CPP] +/// Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. /// Uncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height. /// ///@{ -struct PosLlh +struct LlhPos { struct ValidFlags : Bitfield { @@ -394,12 +386,6 @@ struct PosLlh ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool latitude() const { return (value & LATITUDE) > 0; } - void latitude(bool val) { if(val) value |= LATITUDE; else value &= ~LATITUDE; } - bool longitude() const { return (value & LONGITUDE) > 0; } - void longitude(bool val) { if(val) value |= LONGITUDE; else value &= ~LONGITUDE; } - bool height() const { return (value & HEIGHT) > 0; } - void height(bool val) { if(val) value |= HEIGHT; else value &= ~HEIGHT; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -416,7 +402,7 @@ struct PosLlh static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_POS_LLH; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "PosLlh"; + static constexpr const char* NAME = "LlhPos"; static constexpr const char* DOC_NAME = "LLH Position"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -436,17 +422,17 @@ struct PosLlh typedef void Response; }; -TypedResult posLlh(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, PosLlh::ValidFlags validFlags); +TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_height_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [CPP] -/// Estimated value of the height above ellipsoid. +///@defgroup cpp_aiding_height (0x13,0x23) Height [CPP] +/// Estimated value of height. /// ///@{ -struct HeightAboveEllipsoid +struct Height { /// Parameters Time time; ///< Timestamp of the measurement. @@ -457,10 +443,10 @@ struct HeightAboveEllipsoid /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEIGHT_ABOVE_ELLIPSOID; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEIGHT_ABS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "HeightAboveEllipsoid"; - static constexpr const char* DOC_NAME = "Height Above Ellipsoid"; + static constexpr const char* NAME = "Height"; + static constexpr const char* DOC_NAME = "Height"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; auto asTuple() const @@ -479,17 +465,17 @@ struct HeightAboveEllipsoid typedef void Response; }; -TypedResult heightAboveEllipsoid(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags); +TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_vel_ecef (0x13,0x28) Vel Ecef [CPP] +///@defgroup cpp_aiding_ecef_vel (0x13,0x28) Ecef Vel [CPP] /// ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame. /// ///@{ -struct VelEcef +struct EcefVel { struct ValidFlags : Bitfield { @@ -512,12 +498,6 @@ struct VelEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -532,7 +512,7 @@ struct VelEcef static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "VelEcef"; + static constexpr const char* NAME = "EcefVel"; static constexpr const char* DOC_NAME = "ECEF Velocity"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -552,17 +532,17 @@ struct VelEcef typedef void Response; }; -TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelEcef::ValidFlags validFlags); +TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_vel_ned (0x13,0x29) Vel Ned [CPP] +///@defgroup cpp_aiding_ned_vel (0x13,0x29) Ned Vel [CPP] /// NED velocity aiding command. Coordinates are given in the local North-East-Down frame. /// ///@{ -struct VelNed +struct NedVel { struct ValidFlags : Bitfield { @@ -585,12 +565,6 @@ struct VelNed ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -605,7 +579,7 @@ struct VelNed static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_NED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "VelNed"; + static constexpr const char* NAME = "NedVel"; static constexpr const char* DOC_NAME = "NED Velocity"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -625,17 +599,18 @@ struct VelNed typedef void Response; }; -TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelNed::ValidFlags validFlags); +TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_vel_body_frame (0x13,0x2A) Vel Body Frame [CPP] -/// Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame. +///@defgroup cpp_aiding_vehicle_fixed_frame_velocity (0x13,0x2A) Vehicle Fixed Frame Velocity [CPP] +/// Estimate of velocity of the vehicle in the frame associated +/// with the given sensor ID. /// ///@{ -struct VelBodyFrame +struct VehicleFixedFrameVelocity { struct ValidFlags : Bitfield { @@ -658,12 +633,6 @@ struct VelBodyFrame ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -676,10 +645,10 @@ struct VelBodyFrame /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_BODY_FRAME; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_ODOM; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "VelBodyFrame"; - static constexpr const char* DOC_NAME = "Body Frame Velocity"; + static constexpr const char* NAME = "VehicleFixedFrameVelocity"; + static constexpr const char* DOC_NAME = "Vehicle Frame Velocity"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; auto asTuple() const @@ -698,16 +667,16 @@ struct VelBodyFrame typedef void Response; }; -TypedResult velBodyFrame(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelBodyFrame::ValidFlags validFlags); +TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_heading_true (0x13,0x31) Heading True [CPP] +///@defgroup cpp_aiding_true_heading (0x13,0x31) True Heading [CPP] /// ///@{ -struct HeadingTrue +struct TrueHeading { /// Parameters Time time; ///< Timestamp of the measurement. @@ -720,7 +689,7 @@ struct HeadingTrue static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEADING_TRUE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "HeadingTrue"; + static constexpr const char* NAME = "TrueHeading"; static constexpr const char* DOC_NAME = "True Heading"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -740,7 +709,7 @@ struct HeadingTrue typedef void Response; }; -TypedResult headingTrue(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); +TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); ///@} /// @@ -773,12 +742,6 @@ struct MagneticField ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool x() const { return (value & X) > 0; } - void x(bool val) { if(val) value |= X; else value &= ~X; } - bool y() const { return (value & Y) > 0; } - void y(bool val) { if(val) value |= Y; else value &= ~Y; } - bool z() const { return (value & Z) > 0; } - void z(bool val) { if(val) value |= Z; else value &= ~Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_base.cpp b/src/cpp/mip/definitions/commands_base.cpp index 10671dd3e..03118d5c5 100644 --- a/src/cpp/mip/definitions/commands_base.cpp +++ b/src/cpp/mip/definitions/commands_base.cpp @@ -96,306 +96,42 @@ void GetDeviceInfo::extract(Serializer& serializer) (void)serializer; } -TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut) +void GetDeviceInfo::Response::insert(Serializer& serializer) const { - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - uint8_t responseLength = sizeof(buffer); + serializer.insert(device_info); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_INFO, NULL, 0, REPLY_DEVICE_INFO, buffer, &responseLength); - - if( result == MIP_ACK_OK ) - { - Serializer deserializer(buffer, responseLength); - - assert(deviceInfoOut); - deserializer.extract(*deviceInfoOut); - - if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; - } - return result; -} -void GetDeviceDescriptors::insert(Serializer& serializer) const -{ - (void)serializer; } -void GetDeviceDescriptors::extract(Serializer& serializer) +void GetDeviceInfo::Response::extract(Serializer& serializer) { - (void)serializer; -} - -TypedResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - uint8_t responseLength = sizeof(buffer); + serializer.extract(device_info); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_DESCRIPTORS, NULL, 0, REPLY_DEVICE_DESCRIPTORS, buffer, &responseLength); - - if( result == MIP_ACK_OK ) - { - Serializer deserializer(buffer, responseLength); - - for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) - deserializer.extract(descriptorsOut[*descriptorsOutCount]); - - if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; - } - return result; -} -void BuiltInTest::insert(Serializer& serializer) const -{ - (void)serializer; -} -void BuiltInTest::extract(Serializer& serializer) -{ - (void)serializer; -} - -TypedResult builtInTest(C::mip_interface& device, uint32_t* resultOut) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - uint8_t responseLength = sizeof(buffer); - - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_BUILT_IN_TEST, NULL, 0, REPLY_BUILT_IN_TEST, buffer, &responseLength); - - if( result == MIP_ACK_OK ) - { - Serializer deserializer(buffer, responseLength); - - assert(resultOut); - deserializer.extract(*resultOut); - - if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; - } - return result; -} -void Resume::insert(Serializer& serializer) const -{ - (void)serializer; -} -void Resume::extract(Serializer& serializer) -{ - (void)serializer; -} - -TypedResult resume(C::mip_interface& device) -{ - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESUME, NULL, 0); -} -void GetExtendedDescriptors::insert(Serializer& serializer) const -{ - (void)serializer; -} -void GetExtendedDescriptors::extract(Serializer& serializer) -{ - (void)serializer; -} - -TypedResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - uint8_t responseLength = sizeof(buffer); - - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_EXTENDED_DESCRIPTORS, NULL, 0, REPLY_GET_EXTENDED_DESCRIPTORS, buffer, &responseLength); - - if( result == MIP_ACK_OK ) - { - Serializer deserializer(buffer, responseLength); - - for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) - deserializer.extract(descriptorsOut[*descriptorsOutCount]); - - if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; - } - return result; -} -void ContinuousBit::insert(Serializer& serializer) const -{ - (void)serializer; -} -void ContinuousBit::extract(Serializer& serializer) -{ - (void)serializer; } -TypedResult continuousBit(C::mip_interface& device, uint8_t* resultOut) +TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInfo* deviceInfoOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTINUOUS_BIT, NULL, 0, REPLY_CONTINUOUS_BIT, buffer, &responseLength); - - if( result == MIP_ACK_OK ) - { - Serializer deserializer(buffer, responseLength); - - assert(resultOut); - for(unsigned int i=0; i < 16; i++) - deserializer.extract(resultOut[i]); - - if( deserializer.remaining() != 0 ) - result = MIP_STATUS_ERROR; - } - return result; -} -void CommSpeed::insert(Serializer& serializer) const -{ - serializer.insert(function); - - serializer.insert(port); - - if( function == FunctionSelector::WRITE ) - { - serializer.insert(baud); - - } -} -void CommSpeed::extract(Serializer& serializer) -{ - serializer.extract(function); - - serializer.extract(port); - - if( function == FunctionSelector::WRITE ) - { - serializer.extract(baud); - - } -} - -TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); - - serializer.insert(FunctionSelector::WRITE); - serializer.insert(port); - - serializer.insert(baud); - - assert(serializer.isOk()); - - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); -} -TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); - - serializer.insert(FunctionSelector::READ); - serializer.insert(port); - - assert(serializer.isOk()); - - uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length(), REPLY_COMM_SPEED, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_INFO, NULL, 0, REPLY_DEVICE_INFO, buffer, &responseLength); if( result == MIP_ACK_OK ) { Serializer deserializer(buffer, responseLength); - deserializer.extract(port); - - assert(baudOut); - deserializer.extract(*baudOut); + assert(deviceInfoOut); + deserializer.extract(*deviceInfoOut); if( deserializer.remaining() != 0 ) result = MIP_STATUS_ERROR; } return result; } -TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); - - serializer.insert(FunctionSelector::SAVE); - serializer.insert(port); - - assert(serializer.isOk()); - - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); -} -TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); - - serializer.insert(FunctionSelector::LOAD); - serializer.insert(port); - - assert(serializer.isOk()); - - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); -} -TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); - - serializer.insert(FunctionSelector::RESET); - serializer.insert(port); - - assert(serializer.isOk()); - - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); -} -void GpsTimeUpdate::insert(Serializer& serializer) const -{ - serializer.insert(function); - - if( function == FunctionSelector::WRITE ) - { - serializer.insert(field_id); - - serializer.insert(value); - - } -} -void GpsTimeUpdate::extract(Serializer& serializer) -{ - serializer.extract(function); - - if( function == FunctionSelector::WRITE ) - { - serializer.extract(field_id); - - serializer.extract(value); - - } -} - -TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value) -{ - uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; - Serializer serializer(buffer, sizeof(buffer)); - - serializer.insert(FunctionSelector::WRITE); - serializer.insert(fieldId); - - serializer.insert(value); - - assert(serializer.isOk()); - - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)serializer.length()); -} -void SoftReset::insert(Serializer& serializer) const +void GetDeviceDescriptors::insert(Serializer& serializer) const { (void)serializer; } -void SoftReset::extract(Serializer& serializer) +void GetDeviceDescriptors::extract(Serializer& serializer) { (void)serializer; } -TypedResult softReset(C::mip_interface& device) -{ - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_RESET, NULL, 0); -} - -} // namespace commands_base -} // namespace mip - diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index 290b030dc..b9d01e942 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include @@ -121,60 +121,6 @@ struct CommandedTestBitsGq7 : Bitfield CommandedTestBitsGq7& operator|=(uint32_t val) { return *this = value | val; } CommandedTestBitsGq7& operator&=(uint32_t val) { return *this = value & val; } - bool generalHardwareFault() const { return (value & GENERAL_HARDWARE_FAULT) > 0; } - void generalHardwareFault(bool val) { if(val) value |= GENERAL_HARDWARE_FAULT; else value &= ~GENERAL_HARDWARE_FAULT; } - bool generalFirmwareFault() const { return (value & GENERAL_FIRMWARE_FAULT) > 0; } - void generalFirmwareFault(bool val) { if(val) value |= GENERAL_FIRMWARE_FAULT; else value &= ~GENERAL_FIRMWARE_FAULT; } - bool timingOverload() const { return (value & TIMING_OVERLOAD) > 0; } - void timingOverload(bool val) { if(val) value |= TIMING_OVERLOAD; else value &= ~TIMING_OVERLOAD; } - bool bufferOverrun() const { return (value & BUFFER_OVERRUN) > 0; } - void bufferOverrun(bool val) { if(val) value |= BUFFER_OVERRUN; else value &= ~BUFFER_OVERRUN; } - uint32_t reserved() const { return (value & RESERVED) >> 4; } - void reserved(uint32_t val) { value = (value & ~RESERVED) | (val << 4); } - bool ipcImuFault() const { return (value & IPC_IMU_FAULT) > 0; } - void ipcImuFault(bool val) { if(val) value |= IPC_IMU_FAULT; else value &= ~IPC_IMU_FAULT; } - bool ipcNavFault() const { return (value & IPC_NAV_FAULT) > 0; } - void ipcNavFault(bool val) { if(val) value |= IPC_NAV_FAULT; else value &= ~IPC_NAV_FAULT; } - bool ipcGnssFault() const { return (value & IPC_GNSS_FAULT) > 0; } - void ipcGnssFault(bool val) { if(val) value |= IPC_GNSS_FAULT; else value &= ~IPC_GNSS_FAULT; } - bool commsFault() const { return (value & COMMS_FAULT) > 0; } - void commsFault(bool val) { if(val) value |= COMMS_FAULT; else value &= ~COMMS_FAULT; } - bool imuAccelFault() const { return (value & IMU_ACCEL_FAULT) > 0; } - void imuAccelFault(bool val) { if(val) value |= IMU_ACCEL_FAULT; else value &= ~IMU_ACCEL_FAULT; } - bool imuGyroFault() const { return (value & IMU_GYRO_FAULT) > 0; } - void imuGyroFault(bool val) { if(val) value |= IMU_GYRO_FAULT; else value &= ~IMU_GYRO_FAULT; } - bool imuMagFault() const { return (value & IMU_MAG_FAULT) > 0; } - void imuMagFault(bool val) { if(val) value |= IMU_MAG_FAULT; else value &= ~IMU_MAG_FAULT; } - bool imuPressFault() const { return (value & IMU_PRESS_FAULT) > 0; } - void imuPressFault(bool val) { if(val) value |= IMU_PRESS_FAULT; else value &= ~IMU_PRESS_FAULT; } - uint32_t imuReserved() const { return (value & IMU_RESERVED) >> 16; } - void imuReserved(uint32_t val) { value = (value & ~IMU_RESERVED) | (val << 16); } - bool imuCalError() const { return (value & IMU_CAL_ERROR) > 0; } - void imuCalError(bool val) { if(val) value |= IMU_CAL_ERROR; else value &= ~IMU_CAL_ERROR; } - bool imuGeneralFault() const { return (value & IMU_GENERAL_FAULT) > 0; } - void imuGeneralFault(bool val) { if(val) value |= IMU_GENERAL_FAULT; else value &= ~IMU_GENERAL_FAULT; } - uint32_t filtReserved() const { return (value & FILT_RESERVED) >> 20; } - void filtReserved(uint32_t val) { value = (value & ~FILT_RESERVED) | (val << 20); } - bool filtSolutionFault() const { return (value & FILT_SOLUTION_FAULT) > 0; } - void filtSolutionFault(bool val) { if(val) value |= FILT_SOLUTION_FAULT; else value &= ~FILT_SOLUTION_FAULT; } - bool filtGeneralFault() const { return (value & FILT_GENERAL_FAULT) > 0; } - void filtGeneralFault(bool val) { if(val) value |= FILT_GENERAL_FAULT; else value &= ~FILT_GENERAL_FAULT; } - bool gnssReceiver1Fault() const { return (value & GNSS_RECEIVER1_FAULT) > 0; } - void gnssReceiver1Fault(bool val) { if(val) value |= GNSS_RECEIVER1_FAULT; else value &= ~GNSS_RECEIVER1_FAULT; } - bool gnssAntenna1Fault() const { return (value & GNSS_ANTENNA1_FAULT) > 0; } - void gnssAntenna1Fault(bool val) { if(val) value |= GNSS_ANTENNA1_FAULT; else value &= ~GNSS_ANTENNA1_FAULT; } - bool gnssReceiver2Fault() const { return (value & GNSS_RECEIVER2_FAULT) > 0; } - void gnssReceiver2Fault(bool val) { if(val) value |= GNSS_RECEIVER2_FAULT; else value &= ~GNSS_RECEIVER2_FAULT; } - bool gnssAntenna2Fault() const { return (value & GNSS_ANTENNA2_FAULT) > 0; } - void gnssAntenna2Fault(bool val) { if(val) value |= GNSS_ANTENNA2_FAULT; else value &= ~GNSS_ANTENNA2_FAULT; } - bool gnssRtcmFailure() const { return (value & GNSS_RTCM_FAILURE) > 0; } - void gnssRtcmFailure(bool val) { if(val) value |= GNSS_RTCM_FAILURE; else value &= ~GNSS_RTCM_FAILURE; } - bool gnssRtkFault() const { return (value & GNSS_RTK_FAULT) > 0; } - void gnssRtkFault(bool val) { if(val) value |= GNSS_RTK_FAULT; else value &= ~GNSS_RTK_FAULT; } - bool gnssSolutionFault() const { return (value & GNSS_SOLUTION_FAULT) > 0; } - void gnssSolutionFault(bool val) { if(val) value |= GNSS_SOLUTION_FAULT; else value &= ~GNSS_SOLUTION_FAULT; } - bool gnssGeneralFault() const { return (value & GNSS_GENERAL_FAULT) > 0; } - void gnssGeneralFault(bool val) { if(val) value |= GNSS_GENERAL_FAULT; else value &= ~GNSS_GENERAL_FAULT; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_filter.hpp b/src/cpp/mip/definitions/commands_filter.hpp index e9ab7d652..1a012f515 100644 --- a/src/cpp/mip/definitions/commands_filter.hpp +++ b/src/cpp/mip/definitions/commands_filter.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include @@ -312,20 +312,6 @@ struct EstimationControl EnableFlags& operator|=(uint16_t val) { return *this = value | val; } EnableFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gyroBias() const { return (value & GYRO_BIAS) > 0; } - void gyroBias(bool val) { if(val) value |= GYRO_BIAS; else value &= ~GYRO_BIAS; } - bool accelBias() const { return (value & ACCEL_BIAS) > 0; } - void accelBias(bool val) { if(val) value |= ACCEL_BIAS; else value &= ~ACCEL_BIAS; } - bool gyroScaleFactor() const { return (value & GYRO_SCALE_FACTOR) > 0; } - void gyroScaleFactor(bool val) { if(val) value |= GYRO_SCALE_FACTOR; else value &= ~GYRO_SCALE_FACTOR; } - bool accelScaleFactor() const { return (value & ACCEL_SCALE_FACTOR) > 0; } - void accelScaleFactor(bool val) { if(val) value |= ACCEL_SCALE_FACTOR; else value &= ~ACCEL_SCALE_FACTOR; } - bool antennaOffset() const { return (value & ANTENNA_OFFSET) > 0; } - void antennaOffset(bool val) { if(val) value |= ANTENNA_OFFSET; else value &= ~ANTENNA_OFFSET; } - bool autoMagHardIron() const { return (value & AUTO_MAG_HARD_IRON) > 0; } - void autoMagHardIron(bool val) { if(val) value |= AUTO_MAG_HARD_IRON; else value &= ~AUTO_MAG_HARD_IRON; } - bool autoMagSoftIron() const { return (value & AUTO_MAG_SOFT_IRON) > 0; } - void autoMagSoftIron(bool val) { if(val) value |= AUTO_MAG_SOFT_IRON; else value &= ~AUTO_MAG_SOFT_IRON; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -594,12 +580,6 @@ struct TareOrientation MipTareAxes& operator|=(uint8_t val) { return *this = value | val; } MipTareAxes& operator&=(uint8_t val) { return *this = value & val; } - bool roll() const { return (value & ROLL) > 0; } - void roll(bool val) { if(val) value |= ROLL; else value &= ~ROLL; } - bool pitch() const { return (value & PITCH) > 0; } - void pitch(bool val) { if(val) value |= PITCH; else value &= ~PITCH; } - bool yaw() const { return (value & YAW) > 0; } - void yaw(bool val) { if(val) value |= YAW; else value &= ~YAW; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1162,13 +1142,9 @@ TypedResult defaultSensorToVehicleOffset(C::mip_interface /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_filter_antenna_offset (0x0D,0x13) Antenna Offset [CPP] -/// Configure the GNSS antenna offset. +/// Set the sensor to GNSS antenna offset. /// -/// For 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. -/// -/// For 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center. -/// -/// This command should also be used for CV7 / GV7-INS NMEA Input over GPIO. +/// This is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. /// /// The magnitude of the offset vector is limited to 10 meters /// @@ -3085,7 +3061,7 @@ TypedResult defaultReferencePosition(C::mip_interface& device /// /// Adaptive measurements can be enabled/disabled without the need for providing the additional parameters. /// In this case, only the function selector and enable value are required; all other parameters will remain at their previous values. -/// When auto-adaptive is selected, the filter and limit parameters are ignored. +/// When “auto-adaptive” is selected, the filter and limit parameters are ignored. /// Instead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality. /// /// @@ -3389,7 +3365,7 @@ struct AidingMeasurementEnable EXTERNAL_HEADING = 5, ///< External heading input EXTERNAL_ALTIMETER = 6, ///< External pressure altimeter input EXTERNAL_MAGNETOMETER = 7, ///< External magnetomer input - BODY_FRAME_VEL = 8, ///< External body frame velocity input + VEHICLE_FRAME_VEL = 8, ///< External vehicle frame velocity input ALL = 65535, ///< Save/load/reset all options }; @@ -3622,14 +3598,6 @@ struct InitializationConfiguration AlignmentSelector& operator|=(uint8_t val) { return *this = value | val; } AlignmentSelector& operator&=(uint8_t val) { return *this = value & val; } - bool dualAntenna() const { return (value & DUAL_ANTENNA) > 0; } - void dualAntenna(bool val) { if(val) value |= DUAL_ANTENNA; else value &= ~DUAL_ANTENNA; } - bool kinematic() const { return (value & KINEMATIC) > 0; } - void kinematic(bool val) { if(val) value |= KINEMATIC; else value &= ~KINEMATIC; } - bool magnetometer() const { return (value & MAGNETOMETER) > 0; } - void magnetometer(bool val) { if(val) value |= MAGNETOMETER; else value &= ~MAGNETOMETER; } - bool external() const { return (value & EXTERNAL) > 0; } - void external(bool val) { if(val) value |= EXTERNAL; else value &= ~EXTERNAL; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_gnss.hpp b/src/cpp/mip/definitions/commands_gnss.hpp index 5823b8f59..6af23e2ae 100644 --- a/src/cpp/mip/definitions/commands_gnss.hpp +++ b/src/cpp/mip/definitions/commands_gnss.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include diff --git a/src/cpp/mip/definitions/commands_rtk.hpp b/src/cpp/mip/definitions/commands_rtk.hpp index 97b9137b5..9bfcc4a0a 100644 --- a/src/cpp/mip/definitions/commands_rtk.hpp +++ b/src/cpp/mip/definitions/commands_rtk.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include @@ -112,28 +112,6 @@ struct GetStatusFlags StatusFlagsLegacy& operator|=(uint32_t val) { return *this = value | val; } StatusFlagsLegacy& operator&=(uint32_t val) { return *this = value & val; } - uint32_t controllerstate() const { return (value & CONTROLLERSTATE) >> 0; } - void controllerstate(uint32_t val) { value = (value & ~CONTROLLERSTATE) | (val << 0); } - uint32_t platformstate() const { return (value & PLATFORMSTATE) >> 3; } - void platformstate(uint32_t val) { value = (value & ~PLATFORMSTATE) | (val << 3); } - uint32_t controllerstatuscode() const { return (value & CONTROLLERSTATUSCODE) >> 8; } - void controllerstatuscode(uint32_t val) { value = (value & ~CONTROLLERSTATUSCODE) | (val << 8); } - uint32_t platformstatuscode() const { return (value & PLATFORMSTATUSCODE) >> 11; } - void platformstatuscode(uint32_t val) { value = (value & ~PLATFORMSTATUSCODE) | (val << 11); } - uint32_t resetcode() const { return (value & RESETCODE) >> 14; } - void resetcode(uint32_t val) { value = (value & ~RESETCODE) | (val << 14); } - uint32_t signalquality() const { return (value & SIGNALQUALITY) >> 16; } - void signalquality(uint32_t val) { value = (value & ~SIGNALQUALITY) | (val << 16); } - uint32_t reserved() const { return (value & RESERVED) >> 20; } - void reserved(uint32_t val) { value = (value & ~RESERVED) | (val << 20); } - uint32_t rssi() const { return (value & RSSI) >> 20; } - void rssi(uint32_t val) { value = (value & ~RSSI) | (val << 20); } - uint32_t rsrp() const { return (value & RSRP) >> 26; } - void rsrp(uint32_t val) { value = (value & ~RSRP) | (val << 26); } - uint32_t rsrq() const { return (value & RSRQ) >> 28; } - void rsrq(uint32_t val) { value = (value & ~RSRQ) | (val << 28); } - uint32_t sinr() const { return (value & SINR) >> 30; } - void sinr(uint32_t val) { value = (value & ~SINR) | (val << 30); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -167,30 +145,6 @@ struct GetStatusFlags StatusFlags& operator|=(uint32_t val) { return *this = value | val; } StatusFlags& operator&=(uint32_t val) { return *this = value & val; } - uint32_t modemState() const { return (value & MODEM_STATE) >> 0; } - void modemState(uint32_t val) { value = (value & ~MODEM_STATE) | (val << 0); } - uint32_t connectionType() const { return (value & CONNECTION_TYPE) >> 4; } - void connectionType(uint32_t val) { value = (value & ~CONNECTION_TYPE) | (val << 4); } - uint32_t rssi() const { return (value & RSSI) >> 8; } - void rssi(uint32_t val) { value = (value & ~RSSI) | (val << 8); } - uint32_t signalQuality() const { return (value & SIGNAL_QUALITY) >> 16; } - void signalQuality(uint32_t val) { value = (value & ~SIGNAL_QUALITY) | (val << 16); } - uint32_t towerChangeIndicator() const { return (value & TOWER_CHANGE_INDICATOR) >> 20; } - void towerChangeIndicator(uint32_t val) { value = (value & ~TOWER_CHANGE_INDICATOR) | (val << 20); } - bool nmeaTimeout() const { return (value & NMEA_TIMEOUT) > 0; } - void nmeaTimeout(bool val) { if(val) value |= NMEA_TIMEOUT; else value &= ~NMEA_TIMEOUT; } - bool serverTimeout() const { return (value & SERVER_TIMEOUT) > 0; } - void serverTimeout(bool val) { if(val) value |= SERVER_TIMEOUT; else value &= ~SERVER_TIMEOUT; } - bool correctionsTimeout() const { return (value & CORRECTIONS_TIMEOUT) > 0; } - void correctionsTimeout(bool val) { if(val) value |= CORRECTIONS_TIMEOUT; else value &= ~CORRECTIONS_TIMEOUT; } - bool deviceOutOfRange() const { return (value & DEVICE_OUT_OF_RANGE) > 0; } - void deviceOutOfRange(bool val) { if(val) value |= DEVICE_OUT_OF_RANGE; else value &= ~DEVICE_OUT_OF_RANGE; } - bool correctionsUnavailable() const { return (value & CORRECTIONS_UNAVAILABLE) > 0; } - void correctionsUnavailable(bool val) { if(val) value |= CORRECTIONS_UNAVAILABLE; else value &= ~CORRECTIONS_UNAVAILABLE; } - bool reserved() const { return (value & RESERVED) > 0; } - void reserved(bool val) { if(val) value |= RESERVED; else value &= ~RESERVED; } - uint32_t version() const { return (value & VERSION) >> 30; } - void version(uint32_t val) { value = (value & ~VERSION) | (val << 30); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -736,12 +690,6 @@ struct ServiceStatus ServiceFlags& operator|=(uint8_t val) { return *this = value | val; } ServiceFlags& operator&=(uint8_t val) { return *this = value & val; } - bool throttle() const { return (value & THROTTLE) > 0; } - void throttle(bool val) { if(val) value |= THROTTLE; else value &= ~THROTTLE; } - bool correctionsUnavailable() const { return (value & CORRECTIONS_UNAVAILABLE) > 0; } - void correctionsUnavailable(bool val) { if(val) value |= CORRECTIONS_UNAVAILABLE; else value &= ~CORRECTIONS_UNAVAILABLE; } - uint8_t reserved() const { return (value & RESERVED) >> 2; } - void reserved(uint8_t val) { value = (value & ~RESERVED) | (val << 2); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_system.hpp b/src/cpp/mip/definitions/commands_system.hpp index 786bce982..323ac173d 100644 --- a/src/cpp/mip/definitions/commands_system.hpp +++ b/src/cpp/mip/definitions/commands_system.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include diff --git a/src/cpp/mip/definitions/data_filter.hpp b/src/cpp/mip/definitions/data_filter.hpp index a64a5c054..aae8ab68a 100644 --- a/src/cpp/mip/definitions/data_filter.hpp +++ b/src/cpp/mip/definitions/data_filter.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include @@ -165,82 +165,23 @@ struct FilterStatusFlags : Bitfield FilterStatusFlags& operator|=(uint16_t val) { return *this = value | val; } FilterStatusFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gx5InitNoAttitude() const { return (value & GX5_INIT_NO_ATTITUDE) > 0; } - void gx5InitNoAttitude(bool val) { if(val) value |= GX5_INIT_NO_ATTITUDE; else value &= ~GX5_INIT_NO_ATTITUDE; } - bool gx5InitNoPositionVelocity() const { return (value & GX5_INIT_NO_POSITION_VELOCITY) > 0; } - void gx5InitNoPositionVelocity(bool val) { if(val) value |= GX5_INIT_NO_POSITION_VELOCITY; else value &= ~GX5_INIT_NO_POSITION_VELOCITY; } - bool gx5RunImuUnavailable() const { return (value & GX5_RUN_IMU_UNAVAILABLE) > 0; } - void gx5RunImuUnavailable(bool val) { if(val) value |= GX5_RUN_IMU_UNAVAILABLE; else value &= ~GX5_RUN_IMU_UNAVAILABLE; } - bool gx5RunGpsUnavailable() const { return (value & GX5_RUN_GPS_UNAVAILABLE) > 0; } - void gx5RunGpsUnavailable(bool val) { if(val) value |= GX5_RUN_GPS_UNAVAILABLE; else value &= ~GX5_RUN_GPS_UNAVAILABLE; } - bool gx5RunMatrixSingularity() const { return (value & GX5_RUN_MATRIX_SINGULARITY) > 0; } - void gx5RunMatrixSingularity(bool val) { if(val) value |= GX5_RUN_MATRIX_SINGULARITY; else value &= ~GX5_RUN_MATRIX_SINGULARITY; } - bool gx5RunPositionCovarianceWarning() const { return (value & GX5_RUN_POSITION_COVARIANCE_WARNING) > 0; } - void gx5RunPositionCovarianceWarning(bool val) { if(val) value |= GX5_RUN_POSITION_COVARIANCE_WARNING; else value &= ~GX5_RUN_POSITION_COVARIANCE_WARNING; } - bool gx5RunVelocityCovarianceWarning() const { return (value & GX5_RUN_VELOCITY_COVARIANCE_WARNING) > 0; } - void gx5RunVelocityCovarianceWarning(bool val) { if(val) value |= GX5_RUN_VELOCITY_COVARIANCE_WARNING; else value &= ~GX5_RUN_VELOCITY_COVARIANCE_WARNING; } - bool gx5RunAttitudeCovarianceWarning() const { return (value & GX5_RUN_ATTITUDE_COVARIANCE_WARNING) > 0; } - void gx5RunAttitudeCovarianceWarning(bool val) { if(val) value |= GX5_RUN_ATTITUDE_COVARIANCE_WARNING; else value &= ~GX5_RUN_ATTITUDE_COVARIANCE_WARNING; } - bool gx5RunNanInSolutionWarning() const { return (value & GX5_RUN_NAN_IN_SOLUTION_WARNING) > 0; } - void gx5RunNanInSolutionWarning(bool val) { if(val) value |= GX5_RUN_NAN_IN_SOLUTION_WARNING; else value &= ~GX5_RUN_NAN_IN_SOLUTION_WARNING; } - bool gx5RunGyroBiasEstHighWarning() const { return (value & GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING) > 0; } - void gx5RunGyroBiasEstHighWarning(bool val) { if(val) value |= GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING; else value &= ~GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING; } - bool gx5RunAccelBiasEstHighWarning() const { return (value & GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING) > 0; } - void gx5RunAccelBiasEstHighWarning(bool val) { if(val) value |= GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING; else value &= ~GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING; } - bool gx5RunGyroScaleFactorEstHighWarning() const { return (value & GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING) > 0; } - void gx5RunGyroScaleFactorEstHighWarning(bool val) { if(val) value |= GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING; else value &= ~GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING; } - bool gx5RunAccelScaleFactorEstHighWarning() const { return (value & GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING) > 0; } - void gx5RunAccelScaleFactorEstHighWarning(bool val) { if(val) value |= GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING; else value &= ~GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING; } - bool gx5RunMagBiasEstHighWarning() const { return (value & GX5_RUN_MAG_BIAS_EST_HIGH_WARNING) > 0; } - void gx5RunMagBiasEstHighWarning(bool val) { if(val) value |= GX5_RUN_MAG_BIAS_EST_HIGH_WARNING; else value &= ~GX5_RUN_MAG_BIAS_EST_HIGH_WARNING; } - bool gx5RunAntOffsetCorrectionEstHighWarning() const { return (value & GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING) > 0; } - void gx5RunAntOffsetCorrectionEstHighWarning(bool val) { if(val) value |= GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING; else value &= ~GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING; } - bool gx5RunMagHardIronEstHighWarning() const { return (value & GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING) > 0; } - void gx5RunMagHardIronEstHighWarning(bool val) { if(val) value |= GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING; else value &= ~GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING; } - bool gx5RunMagSoftIronEstHighWarning() const { return (value & GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING) > 0; } - void gx5RunMagSoftIronEstHighWarning(bool val) { if(val) value |= GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING; else value &= ~GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING; } - uint16_t gq7FilterCondition() const { return (value & GQ7_FILTER_CONDITION) >> 0; } - void gq7FilterCondition(uint16_t val) { value = (value & ~GQ7_FILTER_CONDITION) | (val << 0); } - bool gq7RollPitchWarning() const { return (value & GQ7_ROLL_PITCH_WARNING) > 0; } - void gq7RollPitchWarning(bool val) { if(val) value |= GQ7_ROLL_PITCH_WARNING; else value &= ~GQ7_ROLL_PITCH_WARNING; } - bool gq7HeadingWarning() const { return (value & GQ7_HEADING_WARNING) > 0; } - void gq7HeadingWarning(bool val) { if(val) value |= GQ7_HEADING_WARNING; else value &= ~GQ7_HEADING_WARNING; } - bool gq7PositionWarning() const { return (value & GQ7_POSITION_WARNING) > 0; } - void gq7PositionWarning(bool val) { if(val) value |= GQ7_POSITION_WARNING; else value &= ~GQ7_POSITION_WARNING; } - bool gq7VelocityWarning() const { return (value & GQ7_VELOCITY_WARNING) > 0; } - void gq7VelocityWarning(bool val) { if(val) value |= GQ7_VELOCITY_WARNING; else value &= ~GQ7_VELOCITY_WARNING; } - bool gq7ImuBiasWarning() const { return (value & GQ7_IMU_BIAS_WARNING) > 0; } - void gq7ImuBiasWarning(bool val) { if(val) value |= GQ7_IMU_BIAS_WARNING; else value &= ~GQ7_IMU_BIAS_WARNING; } - bool gq7GnssClkWarning() const { return (value & GQ7_GNSS_CLK_WARNING) > 0; } - void gq7GnssClkWarning(bool val) { if(val) value |= GQ7_GNSS_CLK_WARNING; else value &= ~GQ7_GNSS_CLK_WARNING; } - bool gq7AntennaLeverArmWarning() const { return (value & GQ7_ANTENNA_LEVER_ARM_WARNING) > 0; } - void gq7AntennaLeverArmWarning(bool val) { if(val) value |= GQ7_ANTENNA_LEVER_ARM_WARNING; else value &= ~GQ7_ANTENNA_LEVER_ARM_WARNING; } - bool gq7MountingTransformWarning() const { return (value & GQ7_MOUNTING_TRANSFORM_WARNING) > 0; } - void gq7MountingTransformWarning(bool val) { if(val) value |= GQ7_MOUNTING_TRANSFORM_WARNING; else value &= ~GQ7_MOUNTING_TRANSFORM_WARNING; } - bool gq7TimeSyncWarning() const { return (value & GQ7_TIME_SYNC_WARNING) > 0; } - void gq7TimeSyncWarning(bool val) { if(val) value |= GQ7_TIME_SYNC_WARNING; else value &= ~GQ7_TIME_SYNC_WARNING; } - uint16_t gq7SolutionError() const { return (value & GQ7_SOLUTION_ERROR) >> 12; } - void gq7SolutionError(uint16_t val) { value = (value & ~GQ7_SOLUTION_ERROR) | (val << 12); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; enum class FilterAidingMeasurementType : uint8_t { - GNSS = 1, ///< - DUAL_ANTENNA = 2, ///< - HEADING = 3, ///< - PRESSURE = 4, ///< - MAGNETOMETER = 5, ///< - SPEED = 6, ///< - AIDING_POS_ECEF = 33, ///< - AIDING_POS_LLH = 34, ///< - AIDING_HEIGHT_ABOVE_ELLIPSOID = 35, ///< - AIDING_VEL_ECEF = 40, ///< - AIDING_VEL_NED = 41, ///< - AIDING_VEL_BODY_FRAME = 42, ///< - AIDING_HEADING_TRUE = 49, ///< - AIDING_MAGNETIC_FIELD = 50, ///< - AIDING_PRESSURE = 51, ///< + GNSS = 1, ///< + DUAL_ANTENNA = 2, ///< + HEADING = 3, ///< + PRESSURE = 4, ///< + MAGNETOMETER = 5, ///< + SPEED = 6, ///< + POS_ECEF = 33, ///< + POS_LLH = 34, ///< + VEL_ECEF = 40, ///< + VEL_NED = 41, ///< + VEL_VEHICLE_FRAME = 42, ///< + HEADING_TRUE = 49, ///< }; struct FilterMeasurementIndicator : Bitfield @@ -267,18 +208,6 @@ struct FilterMeasurementIndicator : Bitfield FilterMeasurementIndicator& operator|=(uint8_t val) { return *this = value | val; } FilterMeasurementIndicator& operator&=(uint8_t val) { return *this = value & val; } - bool enabled() const { return (value & ENABLED) > 0; } - void enabled(bool val) { if(val) value |= ENABLED; else value &= ~ENABLED; } - bool used() const { return (value & USED) > 0; } - void used(bool val) { if(val) value |= USED; else value &= ~USED; } - bool residualHighWarning() const { return (value & RESIDUAL_HIGH_WARNING) > 0; } - void residualHighWarning(bool val) { if(val) value |= RESIDUAL_HIGH_WARNING; else value &= ~RESIDUAL_HIGH_WARNING; } - bool sampleTimeWarning() const { return (value & SAMPLE_TIME_WARNING) > 0; } - void sampleTimeWarning(bool val) { if(val) value |= SAMPLE_TIME_WARNING; else value &= ~SAMPLE_TIME_WARNING; } - bool configurationError() const { return (value & CONFIGURATION_ERROR) > 0; } - void configurationError(bool val) { if(val) value |= CONFIGURATION_ERROR; else value &= ~CONFIGURATION_ERROR; } - bool maxNumMeasExceeded() const { return (value & MAX_NUM_MEAS_EXCEEDED) > 0; } - void maxNumMeasExceeded(bool val) { if(val) value |= MAX_NUM_MEAS_EXCEEDED; else value &= ~MAX_NUM_MEAS_EXCEEDED; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -316,38 +245,6 @@ struct GnssAidStatusFlags : Bitfield GnssAidStatusFlags& operator|=(uint16_t val) { return *this = value | val; } GnssAidStatusFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tightCoupling() const { return (value & TIGHT_COUPLING) > 0; } - void tightCoupling(bool val) { if(val) value |= TIGHT_COUPLING; else value &= ~TIGHT_COUPLING; } - bool differential() const { return (value & DIFFERENTIAL) > 0; } - void differential(bool val) { if(val) value |= DIFFERENTIAL; else value &= ~DIFFERENTIAL; } - bool integerFix() const { return (value & INTEGER_FIX) > 0; } - void integerFix(bool val) { if(val) value |= INTEGER_FIX; else value &= ~INTEGER_FIX; } - bool gpsL1() const { return (value & GPS_L1) > 0; } - void gpsL1(bool val) { if(val) value |= GPS_L1; else value &= ~GPS_L1; } - bool gpsL2() const { return (value & GPS_L2) > 0; } - void gpsL2(bool val) { if(val) value |= GPS_L2; else value &= ~GPS_L2; } - bool gpsL5() const { return (value & GPS_L5) > 0; } - void gpsL5(bool val) { if(val) value |= GPS_L5; else value &= ~GPS_L5; } - bool gloL1() const { return (value & GLO_L1) > 0; } - void gloL1(bool val) { if(val) value |= GLO_L1; else value &= ~GLO_L1; } - bool gloL2() const { return (value & GLO_L2) > 0; } - void gloL2(bool val) { if(val) value |= GLO_L2; else value &= ~GLO_L2; } - bool galE1() const { return (value & GAL_E1) > 0; } - void galE1(bool val) { if(val) value |= GAL_E1; else value &= ~GAL_E1; } - bool galE5() const { return (value & GAL_E5) > 0; } - void galE5(bool val) { if(val) value |= GAL_E5; else value &= ~GAL_E5; } - bool galE6() const { return (value & GAL_E6) > 0; } - void galE6(bool val) { if(val) value |= GAL_E6; else value &= ~GAL_E6; } - bool beiB1() const { return (value & BEI_B1) > 0; } - void beiB1(bool val) { if(val) value |= BEI_B1; else value &= ~BEI_B1; } - bool beiB2() const { return (value & BEI_B2) > 0; } - void beiB2(bool val) { if(val) value |= BEI_B2; else value &= ~BEI_B2; } - bool beiB3() const { return (value & BEI_B3) > 0; } - void beiB3(bool val) { if(val) value |= BEI_B3; else value &= ~BEI_B3; } - bool noFix() const { return (value & NO_FIX) > 0; } - void noFix(bool val) { if(val) value |= NO_FIX; else value &= ~NO_FIX; } - bool configError() const { return (value & CONFIG_ERROR) > 0; } - void configError(bool val) { if(val) value |= CONFIG_ERROR; else value &= ~CONFIG_ERROR; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2538,12 +2435,6 @@ struct GnssDualAntennaStatus DualAntennaStatusFlags& operator|=(uint16_t val) { return *this = value | val; } DualAntennaStatusFlags& operator&=(uint16_t val) { return *this = value & val; } - bool rcv1DataValid() const { return (value & RCV_1_DATA_VALID) > 0; } - void rcv1DataValid(bool val) { if(val) value |= RCV_1_DATA_VALID; else value &= ~RCV_1_DATA_VALID; } - bool rcv2DataValid() const { return (value & RCV_2_DATA_VALID) > 0; } - void rcv2DataValid(bool val) { if(val) value |= RCV_2_DATA_VALID; else value &= ~RCV_2_DATA_VALID; } - bool antennaOffsetsValid() const { return (value & ANTENNA_OFFSETS_VALID) > 0; } - void antennaOffsetsValid(bool val) { if(val) value |= ANTENNA_OFFSETS_VALID; else value &= ~ANTENNA_OFFSETS_VALID; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_gnss.hpp b/src/cpp/mip/definitions/data_gnss.hpp index 509f6f82d..30e85c380 100644 --- a/src/cpp/mip/definitions/data_gnss.hpp +++ b/src/cpp/mip/definitions/data_gnss.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include @@ -198,18 +198,6 @@ struct PosLlh ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool latLon() const { return (value & LAT_LON) > 0; } - void latLon(bool val) { if(val) value |= LAT_LON; else value &= ~LAT_LON; } - bool ellipsoidHeight() const { return (value & ELLIPSOID_HEIGHT) > 0; } - void ellipsoidHeight(bool val) { if(val) value |= ELLIPSOID_HEIGHT; else value &= ~ELLIPSOID_HEIGHT; } - bool mslHeight() const { return (value & MSL_HEIGHT) > 0; } - void mslHeight(bool val) { if(val) value |= MSL_HEIGHT; else value &= ~MSL_HEIGHT; } - bool horizontalAccuracy() const { return (value & HORIZONTAL_ACCURACY) > 0; } - void horizontalAccuracy(bool val) { if(val) value |= HORIZONTAL_ACCURACY; else value &= ~HORIZONTAL_ACCURACY; } - bool verticalAccuracy() const { return (value & VERTICAL_ACCURACY) > 0; } - void verticalAccuracy(bool val) { if(val) value |= VERTICAL_ACCURACY; else value &= ~VERTICAL_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -277,12 +265,6 @@ struct PosEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool position() const { return (value & POSITION) > 0; } - void position(bool val) { if(val) value |= POSITION; else value &= ~POSITION; } - bool positionAccuracy() const { return (value & POSITION_ACCURACY) > 0; } - void positionAccuracy(bool val) { if(val) value |= POSITION_ACCURACY; else value &= ~POSITION_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -350,20 +332,6 @@ struct VelNed ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool velocity() const { return (value & VELOCITY) > 0; } - void velocity(bool val) { if(val) value |= VELOCITY; else value &= ~VELOCITY; } - bool speed3d() const { return (value & SPEED_3D) > 0; } - void speed3d(bool val) { if(val) value |= SPEED_3D; else value &= ~SPEED_3D; } - bool groundSpeed() const { return (value & GROUND_SPEED) > 0; } - void groundSpeed(bool val) { if(val) value |= GROUND_SPEED; else value &= ~GROUND_SPEED; } - bool heading() const { return (value & HEADING) > 0; } - void heading(bool val) { if(val) value |= HEADING; else value &= ~HEADING; } - bool speedAccuracy() const { return (value & SPEED_ACCURACY) > 0; } - void speedAccuracy(bool val) { if(val) value |= SPEED_ACCURACY; else value &= ~SPEED_ACCURACY; } - bool headingAccuracy() const { return (value & HEADING_ACCURACY) > 0; } - void headingAccuracy(bool val) { if(val) value |= HEADING_ACCURACY; else value &= ~HEADING_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -431,12 +399,6 @@ struct VelEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool velocity() const { return (value & VELOCITY) > 0; } - void velocity(bool val) { if(val) value |= VELOCITY; else value &= ~VELOCITY; } - bool velocityAccuracy() const { return (value & VELOCITY_ACCURACY) > 0; } - void velocityAccuracy(bool val) { if(val) value |= VELOCITY_ACCURACY; else value &= ~VELOCITY_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -505,22 +467,6 @@ struct Dop ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gdop() const { return (value & GDOP) > 0; } - void gdop(bool val) { if(val) value |= GDOP; else value &= ~GDOP; } - bool pdop() const { return (value & PDOP) > 0; } - void pdop(bool val) { if(val) value |= PDOP; else value &= ~PDOP; } - bool hdop() const { return (value & HDOP) > 0; } - void hdop(bool val) { if(val) value |= HDOP; else value &= ~HDOP; } - bool vdop() const { return (value & VDOP) > 0; } - void vdop(bool val) { if(val) value |= VDOP; else value &= ~VDOP; } - bool tdop() const { return (value & TDOP) > 0; } - void tdop(bool val) { if(val) value |= TDOP; else value &= ~TDOP; } - bool ndop() const { return (value & NDOP) > 0; } - void ndop(bool val) { if(val) value |= NDOP; else value &= ~NDOP; } - bool edop() const { return (value & EDOP) > 0; } - void edop(bool val) { if(val) value |= EDOP; else value &= ~EDOP; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -589,12 +535,6 @@ struct UtcTime ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gnssDateTime() const { return (value & GNSS_DATE_TIME) > 0; } - void gnssDateTime(bool val) { if(val) value |= GNSS_DATE_TIME; else value &= ~GNSS_DATE_TIME; } - bool leapSecondsKnown() const { return (value & LEAP_SECONDS_KNOWN) > 0; } - void leapSecondsKnown(bool val) { if(val) value |= LEAP_SECONDS_KNOWN; else value &= ~LEAP_SECONDS_KNOWN; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -663,12 +603,6 @@ struct GpsTime ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -733,14 +667,6 @@ struct ClockInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool bias() const { return (value & BIAS) > 0; } - void bias(bool val) { if(val) value |= BIAS; else value &= ~BIAS; } - bool drift() const { return (value & DRIFT) > 0; } - void drift(bool val) { if(val) value |= DRIFT; else value &= ~DRIFT; } - bool accuracyEstimate() const { return (value & ACCURACY_ESTIMATE) > 0; } - void accuracyEstimate(bool val) { if(val) value |= ACCURACY_ESTIMATE; else value &= ~ACCURACY_ESTIMATE; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -816,10 +742,6 @@ struct FixInfo FixFlags& operator|=(uint16_t val) { return *this = value | val; } FixFlags& operator&=(uint16_t val) { return *this = value & val; } - bool sbasUsed() const { return (value & SBAS_USED) > 0; } - void sbasUsed(bool val) { if(val) value |= SBAS_USED; else value &= ~SBAS_USED; } - bool dgnssUsed() const { return (value & DGNSS_USED) > 0; } - void dgnssUsed(bool val) { if(val) value |= DGNSS_USED; else value &= ~DGNSS_USED; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -845,14 +767,6 @@ struct FixInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool fixType() const { return (value & FIX_TYPE) > 0; } - void fixType(bool val) { if(val) value |= FIX_TYPE; else value &= ~FIX_TYPE; } - bool numSv() const { return (value & NUM_SV) > 0; } - void numSv(bool val) { if(val) value |= NUM_SV; else value &= ~NUM_SV; } - bool fixFlags() const { return (value & FIX_FLAGS) > 0; } - void fixFlags(bool val) { if(val) value |= FIX_FLAGS; else value &= ~FIX_FLAGS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -918,10 +832,6 @@ struct SvInfo SVFlags& operator|=(uint16_t val) { return *this = value | val; } SVFlags& operator&=(uint16_t val) { return *this = value & val; } - bool usedForNavigation() const { return (value & USED_FOR_NAVIGATION) > 0; } - void usedForNavigation(bool val) { if(val) value |= USED_FOR_NAVIGATION; else value &= ~USED_FOR_NAVIGATION; } - bool healthy() const { return (value & HEALTHY) > 0; } - void healthy(bool val) { if(val) value |= HEALTHY; else value &= ~HEALTHY; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -950,20 +860,6 @@ struct SvInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool channel() const { return (value & CHANNEL) > 0; } - void channel(bool val) { if(val) value |= CHANNEL; else value &= ~CHANNEL; } - bool svId() const { return (value & SV_ID) > 0; } - void svId(bool val) { if(val) value |= SV_ID; else value &= ~SV_ID; } - bool carrierNoiseRatio() const { return (value & CARRIER_NOISE_RATIO) > 0; } - void carrierNoiseRatio(bool val) { if(val) value |= CARRIER_NOISE_RATIO; else value &= ~CARRIER_NOISE_RATIO; } - bool azimuth() const { return (value & AZIMUTH) > 0; } - void azimuth(bool val) { if(val) value |= AZIMUTH; else value &= ~AZIMUTH; } - bool elevation() const { return (value & ELEVATION) > 0; } - void elevation(bool val) { if(val) value |= ELEVATION; else value &= ~ELEVATION; } - bool svFlags() const { return (value & SV_FLAGS) > 0; } - void svFlags(bool val) { if(val) value |= SV_FLAGS; else value &= ~SV_FLAGS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1055,14 +951,6 @@ struct HwStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool sensorState() const { return (value & SENSOR_STATE) > 0; } - void sensorState(bool val) { if(val) value |= SENSOR_STATE; else value &= ~SENSOR_STATE; } - bool antennaState() const { return (value & ANTENNA_STATE) > 0; } - void antennaState(bool val) { if(val) value |= ANTENNA_STATE; else value &= ~ANTENNA_STATE; } - bool antennaPower() const { return (value & ANTENNA_POWER) > 0; } - void antennaPower(bool val) { if(val) value |= ANTENNA_POWER; else value &= ~ANTENNA_POWER; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1141,16 +1029,6 @@ struct DgpsInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool age() const { return (value & AGE) > 0; } - void age(bool val) { if(val) value |= AGE; else value &= ~AGE; } - bool baseStationId() const { return (value & BASE_STATION_ID) > 0; } - void baseStationId(bool val) { if(val) value |= BASE_STATION_ID; else value &= ~BASE_STATION_ID; } - bool baseStationStatus() const { return (value & BASE_STATION_STATUS) > 0; } - void baseStationStatus(bool val) { if(val) value |= BASE_STATION_STATUS; else value &= ~BASE_STATION_STATUS; } - bool numChannels() const { return (value & NUM_CHANNELS) > 0; } - void numChannels(bool val) { if(val) value |= NUM_CHANNELS; else value &= ~NUM_CHANNELS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1220,16 +1098,6 @@ struct DgpsChannel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool id() const { return (value & ID) > 0; } - void id(bool val) { if(val) value |= ID; else value &= ~ID; } - bool age() const { return (value & AGE) > 0; } - void age(bool val) { if(val) value |= AGE; else value &= ~AGE; } - bool rangeCorrection() const { return (value & RANGE_CORRECTION) > 0; } - void rangeCorrection(bool val) { if(val) value |= RANGE_CORRECTION; else value &= ~RANGE_CORRECTION; } - bool rangeRateCorrection() const { return (value & RANGE_RATE_CORRECTION) > 0; } - void rangeRateCorrection(bool val) { if(val) value |= RANGE_RATE_CORRECTION; else value &= ~RANGE_RATE_CORRECTION; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1299,16 +1167,6 @@ struct ClockInfo2 ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool bias() const { return (value & BIAS) > 0; } - void bias(bool val) { if(val) value |= BIAS; else value &= ~BIAS; } - bool drift() const { return (value & DRIFT) > 0; } - void drift(bool val) { if(val) value |= DRIFT; else value &= ~DRIFT; } - bool biasAccuracy() const { return (value & BIAS_ACCURACY) > 0; } - void biasAccuracy(bool val) { if(val) value |= BIAS_ACCURACY; else value &= ~BIAS_ACCURACY; } - bool driftAccuracy() const { return (value & DRIFT_ACCURACY) > 0; } - void driftAccuracy(bool val) { if(val) value |= DRIFT_ACCURACY; else value &= ~DRIFT_ACCURACY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1372,8 +1230,6 @@ struct GpsLeapSeconds ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool leapSeconds() const { return (value & LEAP_SECONDS) > 0; } - void leapSeconds(bool val) { if(val) value |= LEAP_SECONDS; else value &= ~LEAP_SECONDS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1437,14 +1293,6 @@ struct SbasInfo SbasStatus& operator|=(uint8_t val) { return *this = value | val; } SbasStatus& operator&=(uint8_t val) { return *this = value & val; } - bool rangeAvailable() const { return (value & RANGE_AVAILABLE) > 0; } - void rangeAvailable(bool val) { if(val) value |= RANGE_AVAILABLE; else value &= ~RANGE_AVAILABLE; } - bool correctionsAvailable() const { return (value & CORRECTIONS_AVAILABLE) > 0; } - void correctionsAvailable(bool val) { if(val) value |= CORRECTIONS_AVAILABLE; else value &= ~CORRECTIONS_AVAILABLE; } - bool integrityAvailable() const { return (value & INTEGRITY_AVAILABLE) > 0; } - void integrityAvailable(bool val) { if(val) value |= INTEGRITY_AVAILABLE; else value &= ~INTEGRITY_AVAILABLE; } - bool testMode() const { return (value & TEST_MODE) > 0; } - void testMode(bool val) { if(val) value |= TEST_MODE; else value &= ~TEST_MODE; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1473,20 +1321,6 @@ struct SbasInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool sbasSystem() const { return (value & SBAS_SYSTEM) > 0; } - void sbasSystem(bool val) { if(val) value |= SBAS_SYSTEM; else value &= ~SBAS_SYSTEM; } - bool sbasId() const { return (value & SBAS_ID) > 0; } - void sbasId(bool val) { if(val) value |= SBAS_ID; else value &= ~SBAS_ID; } - bool count() const { return (value & COUNT) > 0; } - void count(bool val) { if(val) value |= COUNT; else value &= ~COUNT; } - bool sbasStatus() const { return (value & SBAS_STATUS) > 0; } - void sbasStatus(bool val) { if(val) value |= SBAS_STATUS; else value &= ~SBAS_STATUS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1577,14 +1411,6 @@ struct SbasCorrection ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool udrei() const { return (value & UDREI) > 0; } - void udrei(bool val) { if(val) value |= UDREI; else value &= ~UDREI; } - bool pseudorangeCorrection() const { return (value & PSEUDORANGE_CORRECTION) > 0; } - void pseudorangeCorrection(bool val) { if(val) value |= PSEUDORANGE_CORRECTION; else value &= ~PSEUDORANGE_CORRECTION; } - bool ionoCorrection() const { return (value & IONO_CORRECTION) > 0; } - void ionoCorrection(bool val) { if(val) value |= IONO_CORRECTION; else value &= ~IONO_CORRECTION; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1680,14 +1506,6 @@ struct RfErrorDetection ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool rfBand() const { return (value & RF_BAND) > 0; } - void rfBand(bool val) { if(val) value |= RF_BAND; else value &= ~RF_BAND; } - bool jammingState() const { return (value & JAMMING_STATE) > 0; } - void jammingState(bool val) { if(val) value |= JAMMING_STATE; else value &= ~JAMMING_STATE; } - bool spoofingState() const { return (value & SPOOFING_STATE) > 0; } - void spoofingState(bool val) { if(val) value |= SPOOFING_STATE; else value &= ~SPOOFING_STATE; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1761,24 +1579,6 @@ struct BaseStationInfo IndicatorFlags& operator|=(uint16_t val) { return *this = value | val; } IndicatorFlags& operator&=(uint16_t val) { return *this = value & val; } - bool gps() const { return (value & GPS) > 0; } - void gps(bool val) { if(val) value |= GPS; else value &= ~GPS; } - bool glonass() const { return (value & GLONASS) > 0; } - void glonass(bool val) { if(val) value |= GLONASS; else value &= ~GLONASS; } - bool galileo() const { return (value & GALILEO) > 0; } - void galileo(bool val) { if(val) value |= GALILEO; else value &= ~GALILEO; } - bool beidou() const { return (value & BEIDOU) > 0; } - void beidou(bool val) { if(val) value |= BEIDOU; else value &= ~BEIDOU; } - bool refStation() const { return (value & REF_STATION) > 0; } - void refStation(bool val) { if(val) value |= REF_STATION; else value &= ~REF_STATION; } - bool singleReceiver() const { return (value & SINGLE_RECEIVER) > 0; } - void singleReceiver(bool val) { if(val) value |= SINGLE_RECEIVER; else value &= ~SINGLE_RECEIVER; } - bool quarterCycleBit1() const { return (value & QUARTER_CYCLE_BIT1) > 0; } - void quarterCycleBit1(bool val) { if(val) value |= QUARTER_CYCLE_BIT1; else value &= ~QUARTER_CYCLE_BIT1; } - bool quarterCycleBit2() const { return (value & QUARTER_CYCLE_BIT2) > 0; } - void quarterCycleBit2(bool val) { if(val) value |= QUARTER_CYCLE_BIT2; else value &= ~QUARTER_CYCLE_BIT2; } - uint16_t quarterCycleBits() const { return (value & QUARTER_CYCLE_BITS) >> 6; } - void quarterCycleBits(uint16_t val) { value = (value & ~QUARTER_CYCLE_BITS) | (val << 6); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1807,20 +1607,6 @@ struct BaseStationInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool ecefPosition() const { return (value & ECEF_POSITION) > 0; } - void ecefPosition(bool val) { if(val) value |= ECEF_POSITION; else value &= ~ECEF_POSITION; } - bool height() const { return (value & HEIGHT) > 0; } - void height(bool val) { if(val) value |= HEIGHT; else value &= ~HEIGHT; } - bool stationId() const { return (value & STATION_ID) > 0; } - void stationId(bool val) { if(val) value |= STATION_ID; else value &= ~STATION_ID; } - bool indicators() const { return (value & INDICATORS) > 0; } - void indicators(bool val) { if(val) value |= INDICATORS; else value &= ~INDICATORS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1893,24 +1679,6 @@ struct RtkCorrectionsStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool epochStatus() const { return (value & EPOCH_STATUS) > 0; } - void epochStatus(bool val) { if(val) value |= EPOCH_STATUS; else value &= ~EPOCH_STATUS; } - bool dongleStatus() const { return (value & DONGLE_STATUS) > 0; } - void dongleStatus(bool val) { if(val) value |= DONGLE_STATUS; else value &= ~DONGLE_STATUS; } - bool gpsLatency() const { return (value & GPS_LATENCY) > 0; } - void gpsLatency(bool val) { if(val) value |= GPS_LATENCY; else value &= ~GPS_LATENCY; } - bool glonassLatency() const { return (value & GLONASS_LATENCY) > 0; } - void glonassLatency(bool val) { if(val) value |= GLONASS_LATENCY; else value &= ~GLONASS_LATENCY; } - bool galileoLatency() const { return (value & GALILEO_LATENCY) > 0; } - void galileoLatency(bool val) { if(val) value |= GALILEO_LATENCY; else value &= ~GALILEO_LATENCY; } - bool beidouLatency() const { return (value & BEIDOU_LATENCY) > 0; } - void beidouLatency(bool val) { if(val) value |= BEIDOU_LATENCY; else value &= ~BEIDOU_LATENCY; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1941,24 +1709,6 @@ struct RtkCorrectionsStatus EpochStatus& operator|=(uint16_t val) { return *this = value | val; } EpochStatus& operator&=(uint16_t val) { return *this = value & val; } - bool antennaLocationReceived() const { return (value & ANTENNA_LOCATION_RECEIVED) > 0; } - void antennaLocationReceived(bool val) { if(val) value |= ANTENNA_LOCATION_RECEIVED; else value &= ~ANTENNA_LOCATION_RECEIVED; } - bool antennaDescriptionReceived() const { return (value & ANTENNA_DESCRIPTION_RECEIVED) > 0; } - void antennaDescriptionReceived(bool val) { if(val) value |= ANTENNA_DESCRIPTION_RECEIVED; else value &= ~ANTENNA_DESCRIPTION_RECEIVED; } - bool gpsReceived() const { return (value & GPS_RECEIVED) > 0; } - void gpsReceived(bool val) { if(val) value |= GPS_RECEIVED; else value &= ~GPS_RECEIVED; } - bool glonassReceived() const { return (value & GLONASS_RECEIVED) > 0; } - void glonassReceived(bool val) { if(val) value |= GLONASS_RECEIVED; else value &= ~GLONASS_RECEIVED; } - bool galileoReceived() const { return (value & GALILEO_RECEIVED) > 0; } - void galileoReceived(bool val) { if(val) value |= GALILEO_RECEIVED; else value &= ~GALILEO_RECEIVED; } - bool beidouReceived() const { return (value & BEIDOU_RECEIVED) > 0; } - void beidouReceived(bool val) { if(val) value |= BEIDOU_RECEIVED; else value &= ~BEIDOU_RECEIVED; } - bool usingGpsMsmMessages() const { return (value & USING_GPS_MSM_MESSAGES) > 0; } - void usingGpsMsmMessages(bool val) { if(val) value |= USING_GPS_MSM_MESSAGES; else value &= ~USING_GPS_MSM_MESSAGES; } - bool usingGlonassMsmMessages() const { return (value & USING_GLONASS_MSM_MESSAGES) > 0; } - void usingGlonassMsmMessages(bool val) { if(val) value |= USING_GLONASS_MSM_MESSAGES; else value &= ~USING_GLONASS_MSM_MESSAGES; } - bool dongleStatusReadFailed() const { return (value & DONGLE_STATUS_READ_FAILED) > 0; } - void dongleStatusReadFailed(bool val) { if(val) value |= DONGLE_STATUS_READ_FAILED; else value &= ~DONGLE_STATUS_READ_FAILED; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2034,22 +1784,6 @@ struct SatelliteStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool gnssId() const { return (value & GNSS_ID) > 0; } - void gnssId(bool val) { if(val) value |= GNSS_ID; else value &= ~GNSS_ID; } - bool satelliteId() const { return (value & SATELLITE_ID) > 0; } - void satelliteId(bool val) { if(val) value |= SATELLITE_ID; else value &= ~SATELLITE_ID; } - bool elevation() const { return (value & ELEVATION) > 0; } - void elevation(bool val) { if(val) value |= ELEVATION; else value &= ~ELEVATION; } - bool azimuth() const { return (value & AZIMUTH) > 0; } - void azimuth(bool val) { if(val) value |= AZIMUTH; else value &= ~AZIMUTH; } - bool health() const { return (value & HEALTH) > 0; } - void health(bool val) { if(val) value |= HEALTH; else value &= ~HEALTH; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2144,40 +1878,6 @@ struct Raw ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool receiverId() const { return (value & RECEIVER_ID) > 0; } - void receiverId(bool val) { if(val) value |= RECEIVER_ID; else value &= ~RECEIVER_ID; } - bool trackingChannel() const { return (value & TRACKING_CHANNEL) > 0; } - void trackingChannel(bool val) { if(val) value |= TRACKING_CHANNEL; else value &= ~TRACKING_CHANNEL; } - bool gnssId() const { return (value & GNSS_ID) > 0; } - void gnssId(bool val) { if(val) value |= GNSS_ID; else value &= ~GNSS_ID; } - bool satelliteId() const { return (value & SATELLITE_ID) > 0; } - void satelliteId(bool val) { if(val) value |= SATELLITE_ID; else value &= ~SATELLITE_ID; } - bool signalId() const { return (value & SIGNAL_ID) > 0; } - void signalId(bool val) { if(val) value |= SIGNAL_ID; else value &= ~SIGNAL_ID; } - bool signalStrength() const { return (value & SIGNAL_STRENGTH) > 0; } - void signalStrength(bool val) { if(val) value |= SIGNAL_STRENGTH; else value &= ~SIGNAL_STRENGTH; } - bool quality() const { return (value & QUALITY) > 0; } - void quality(bool val) { if(val) value |= QUALITY; else value &= ~QUALITY; } - bool pseudorange() const { return (value & PSEUDORANGE) > 0; } - void pseudorange(bool val) { if(val) value |= PSEUDORANGE; else value &= ~PSEUDORANGE; } - bool carrierPhase() const { return (value & CARRIER_PHASE) > 0; } - void carrierPhase(bool val) { if(val) value |= CARRIER_PHASE; else value &= ~CARRIER_PHASE; } - bool doppler() const { return (value & DOPPLER) > 0; } - void doppler(bool val) { if(val) value |= DOPPLER; else value &= ~DOPPLER; } - bool rangeUncertainty() const { return (value & RANGE_UNCERTAINTY) > 0; } - void rangeUncertainty(bool val) { if(val) value |= RANGE_UNCERTAINTY; else value &= ~RANGE_UNCERTAINTY; } - bool carrierPhaseUncertainty() const { return (value & CARRIER_PHASE_UNCERTAINTY) > 0; } - void carrierPhaseUncertainty(bool val) { if(val) value |= CARRIER_PHASE_UNCERTAINTY; else value &= ~CARRIER_PHASE_UNCERTAINTY; } - bool dopplerUncertainty() const { return (value & DOPPLER_UNCERTAINTY) > 0; } - void dopplerUncertainty(bool val) { if(val) value |= DOPPLER_UNCERTAINTY; else value &= ~DOPPLER_UNCERTAINTY; } - bool lockTime() const { return (value & LOCK_TIME) > 0; } - void lockTime(bool val) { if(val) value |= LOCK_TIME; else value &= ~LOCK_TIME; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2257,12 +1957,6 @@ struct GpsEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool ephemeris() const { return (value & EPHEMERIS) > 0; } - void ephemeris(bool val) { if(val) value |= EPHEMERIS; else value &= ~EPHEMERIS; } - bool modernData() const { return (value & MODERN_DATA) > 0; } - void modernData(bool val) { if(val) value |= MODERN_DATA; else value &= ~MODERN_DATA; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2357,12 +2051,6 @@ struct GalileoEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool ephemeris() const { return (value & EPHEMERIS) > 0; } - void ephemeris(bool val) { if(val) value |= EPHEMERIS; else value &= ~EPHEMERIS; } - bool modernData() const { return (value & MODERN_DATA) > 0; } - void modernData(bool val) { if(val) value |= MODERN_DATA; else value &= ~MODERN_DATA; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2456,10 +2144,6 @@ struct GloEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool ephemeris() const { return (value & EPHEMERIS) > 0; } - void ephemeris(bool val) { if(val) value |= EPHEMERIS; else value &= ~EPHEMERIS; } - bool flags() const { return (value & FLAGS) > 0; } - void flags(bool val) { if(val) value |= FLAGS; else value &= ~FLAGS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2547,16 +2231,6 @@ struct GpsIonoCorr ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool alpha() const { return (value & ALPHA) > 0; } - void alpha(bool val) { if(val) value |= ALPHA; else value &= ~ALPHA; } - bool beta() const { return (value & BETA) > 0; } - void beta(bool val) { if(val) value |= BETA; else value &= ~BETA; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2624,16 +2298,6 @@ struct GalileoIonoCorr ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - bool alpha() const { return (value & ALPHA) > 0; } - void alpha(bool val) { if(val) value |= ALPHA; else value &= ~ALPHA; } - bool disturbanceFlags() const { return (value & DISTURBANCE_FLAGS) > 0; } - void disturbanceFlags(bool val) { if(val) value |= DISTURBANCE_FLAGS; else value &= ~DISTURBANCE_FLAGS; } - uint16_t flags() const { return (value & FLAGS) >> 0; } - void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_sensor.hpp b/src/cpp/mip/definitions/data_sensor.hpp index dd6eb1217..1c781a76b 100644 --- a/src/cpp/mip/definitions/data_sensor.hpp +++ b/src/cpp/mip/definitions/data_sensor.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include @@ -765,16 +765,6 @@ struct GpsTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool ppsValid() const { return (value & PPS_VALID) > 0; } - void ppsValid(bool val) { if(val) value |= PPS_VALID; else value &= ~PPS_VALID; } - bool timeRefresh() const { return (value & TIME_REFRESH) > 0; } - void timeRefresh(bool val) { if(val) value |= TIME_REFRESH; else value &= ~TIME_REFRESH; } - bool timeInitialized() const { return (value & TIME_INITIALIZED) > 0; } - void timeInitialized(bool val) { if(val) value |= TIME_INITIALIZED; else value &= ~TIME_INITIALIZED; } - bool towValid() const { return (value & TOW_VALID) > 0; } - void towValid(bool val) { if(val) value |= TOW_VALID; else value &= ~TOW_VALID; } - bool weekNumberValid() const { return (value & WEEK_NUMBER_VALID) > 0; } - void weekNumberValid(bool val) { if(val) value |= WEEK_NUMBER_VALID; else value &= ~WEEK_NUMBER_VALID; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -970,26 +960,6 @@ struct OverrangeStatus Status& operator|=(uint16_t val) { return *this = value | val; } Status& operator&=(uint16_t val) { return *this = value & val; } - bool accelX() const { return (value & ACCEL_X) > 0; } - void accelX(bool val) { if(val) value |= ACCEL_X; else value &= ~ACCEL_X; } - bool accelY() const { return (value & ACCEL_Y) > 0; } - void accelY(bool val) { if(val) value |= ACCEL_Y; else value &= ~ACCEL_Y; } - bool accelZ() const { return (value & ACCEL_Z) > 0; } - void accelZ(bool val) { if(val) value |= ACCEL_Z; else value &= ~ACCEL_Z; } - bool gyroX() const { return (value & GYRO_X) > 0; } - void gyroX(bool val) { if(val) value |= GYRO_X; else value &= ~GYRO_X; } - bool gyroY() const { return (value & GYRO_Y) > 0; } - void gyroY(bool val) { if(val) value |= GYRO_Y; else value &= ~GYRO_Y; } - bool gyroZ() const { return (value & GYRO_Z) > 0; } - void gyroZ(bool val) { if(val) value |= GYRO_Z; else value &= ~GYRO_Z; } - bool magX() const { return (value & MAG_X) > 0; } - void magX(bool val) { if(val) value |= MAG_X; else value &= ~MAG_X; } - bool magY() const { return (value & MAG_Y) > 0; } - void magY(bool val) { if(val) value |= MAG_Y; else value &= ~MAG_Y; } - bool magZ() const { return (value & MAG_Z) > 0; } - void magZ(bool val) { if(val) value |= MAG_Z; else value &= ~MAG_Z; } - bool press() const { return (value & PRESS) > 0; } - void press(bool val) { if(val) value |= PRESS; else value &= ~PRESS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_shared.hpp b/src/cpp/mip/definitions/data_shared.hpp index 2896fb33b..630c4c456 100644 --- a/src/cpp/mip/definitions/data_shared.hpp +++ b/src/cpp/mip/definitions/data_shared.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include @@ -206,12 +206,6 @@ struct GpsTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool tow() const { return (value & TOW) > 0; } - void tow(bool val) { if(val) value |= TOW; else value &= ~TOW; } - bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } - void weekNumber(bool val) { if(val) value |= WEEK_NUMBER; else value &= ~WEEK_NUMBER; } - uint16_t timeValid() const { return (value & TIME_VALID) >> 0; } - void timeValid(uint16_t val) { value = (value & ~TIME_VALID) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -417,8 +411,6 @@ struct ExternalTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool nanoseconds() const { return (value & NANOSECONDS) > 0; } - void nanoseconds(bool val) { if(val) value |= NANOSECONDS; else value &= ~NANOSECONDS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -491,8 +483,6 @@ struct ExternalTimeDelta ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } - bool dtNanos() const { return (value & DT_NANOS) > 0; } - void dtNanos(bool val) { if(val) value |= DT_NANOS; else value &= ~DT_NANOS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_system.hpp b/src/cpp/mip/definitions/data_system.hpp index fe009316a..36085aef6 100644 --- a/src/cpp/mip/definitions/data_system.hpp +++ b/src/cpp/mip/definitions/data_system.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include #include #include From 4c7f8d316eaf21c00d6fd1476f6056d6f0c49ad3 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 13:19:41 -0400 Subject: [PATCH 072/147] Fix bad definition files. --- src/cpp/mip/definitions/commands_aiding.cpp | 54 ++ src/cpp/mip/definitions/commands_base.cpp | 340 +++++++++ src/cpp/mip/definitions/commands_filter.cpp | 646 ++++++++++++++++++ src/cpp/mip/definitions/commands_gnss.cpp | 62 ++ src/cpp/mip/definitions/commands_rtk.cpp | 129 ++++ src/cpp/mip/definitions/commands_system.cpp | 11 + .../mip/metadata/definitions/commands_3dm.hpp | 8 +- .../metadata/definitions/commands_aiding.hpp | 136 ++-- .../metadata/definitions/commands_filter.hpp | 10 +- .../mip/metadata/definitions/data_filter.hpp | 17 +- .../mip/metadata/definitions/data_sensor.hpp | 2 +- 11 files changed, 1327 insertions(+), 88 deletions(-) diff --git a/src/cpp/mip/definitions/commands_aiding.cpp b/src/cpp/mip/definitions/commands_aiding.cpp index a477b84d9..7a80059a0 100644 --- a/src/cpp/mip/definitions/commands_aiding.cpp +++ b/src/cpp/mip/definitions/commands_aiding.cpp @@ -98,6 +98,49 @@ void FrameConfig::extract(Serializer& serializer) } } +void FrameConfig::Response::insert(Serializer& serializer) const +{ + serializer.insert(frame_id); + + serializer.insert(format); + + serializer.insert(tracking_enabled); + + serializer.insert(translation); + + if( format == FrameConfig::Format::EULER ) + { + serializer.insert(rotation.euler); + + } + if( format == FrameConfig::Format::QUATERNION ) + { + serializer.insert(rotation.quaternion); + + } +} +void FrameConfig::Response::extract(Serializer& serializer) +{ + serializer.extract(frame_id); + + serializer.extract(format); + + serializer.extract(tracking_enabled); + + serializer.extract(translation); + + if( format == FrameConfig::Format::EULER ) + { + serializer.extract(rotation.euler); + + } + if( format == FrameConfig::Format::QUATERNION ) + { + serializer.extract(rotation.quaternion); + + } +} + TypedResult writeFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool trackingEnabled, const float* translation, const FrameConfig::Rotation& rotation) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -230,6 +273,17 @@ void AidingEchoControl::extract(Serializer& serializer) } } +void AidingEchoControl::Response::insert(Serializer& serializer) const +{ + serializer.insert(mode); + +} +void AidingEchoControl::Response::extract(Serializer& serializer) +{ + serializer.extract(mode); + +} + TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/cpp/mip/definitions/commands_base.cpp b/src/cpp/mip/definitions/commands_base.cpp index 03118d5c5..e8edbaec2 100644 --- a/src/cpp/mip/definitions/commands_base.cpp +++ b/src/cpp/mip/definitions/commands_base.cpp @@ -135,3 +135,343 @@ void GetDeviceDescriptors::extract(Serializer& serializer) (void)serializer; } +void GetDeviceDescriptors::Response::insert(Serializer& serializer) const +{ + for(unsigned int i=0; i < descriptors_count; i++) + serializer.insert(descriptors[i]); + +} +void GetDeviceDescriptors::Response::extract(Serializer& serializer) +{ + for(descriptors_count = 0; (descriptors_count < sizeof(descriptors)/sizeof(descriptors[0])) && (serializer.remaining() > 0); (descriptors_count)++) + serializer.extract(descriptors[descriptors_count]); + +} + +TypedResult getDeviceDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t responseLength = sizeof(buffer); + + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_DEVICE_DESCRIPTORS, NULL, 0, REPLY_DEVICE_DESCRIPTORS, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) + deserializer.extract(descriptorsOut[*descriptorsOutCount]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +void BuiltInTest::insert(Serializer& serializer) const +{ + (void)serializer; +} +void BuiltInTest::extract(Serializer& serializer) +{ + (void)serializer; +} + +void BuiltInTest::Response::insert(Serializer& serializer) const +{ + serializer.insert(result); + +} +void BuiltInTest::Response::extract(Serializer& serializer) +{ + serializer.extract(result); + +} + +TypedResult builtInTest(C::mip_interface& device, uint32_t* resultOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t responseLength = sizeof(buffer); + + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_BUILT_IN_TEST, NULL, 0, REPLY_BUILT_IN_TEST, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(resultOut); + deserializer.extract(*resultOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +void Resume::insert(Serializer& serializer) const +{ + (void)serializer; +} +void Resume::extract(Serializer& serializer) +{ + (void)serializer; +} + +TypedResult resume(C::mip_interface& device) +{ + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RESUME, NULL, 0); +} +void GetExtendedDescriptors::insert(Serializer& serializer) const +{ + (void)serializer; +} +void GetExtendedDescriptors::extract(Serializer& serializer) +{ + (void)serializer; +} + +void GetExtendedDescriptors::Response::insert(Serializer& serializer) const +{ + for(unsigned int i=0; i < descriptors_count; i++) + serializer.insert(descriptors[i]); + +} +void GetExtendedDescriptors::Response::extract(Serializer& serializer) +{ + for(descriptors_count = 0; (descriptors_count < sizeof(descriptors)/sizeof(descriptors[0])) && (serializer.remaining() > 0); (descriptors_count)++) + serializer.extract(descriptors[descriptors_count]); + +} + +TypedResult getExtendedDescriptors(C::mip_interface& device, uint16_t* descriptorsOut, size_t descriptorsOutMax, uint8_t* descriptorsOutCount) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t responseLength = sizeof(buffer); + + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_EXTENDED_DESCRIPTORS, NULL, 0, REPLY_GET_EXTENDED_DESCRIPTORS, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + for(*descriptorsOutCount = 0; (*descriptorsOutCount < descriptorsOutMax) && (deserializer.remaining() > 0); (*descriptorsOutCount)++) + deserializer.extract(descriptorsOut[*descriptorsOutCount]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +void ContinuousBit::insert(Serializer& serializer) const +{ + (void)serializer; +} +void ContinuousBit::extract(Serializer& serializer) +{ + (void)serializer; +} + +void ContinuousBit::Response::insert(Serializer& serializer) const +{ + for(unsigned int i=0; i < 16; i++) + serializer.insert(result[i]); + +} +void ContinuousBit::Response::extract(Serializer& serializer) +{ + for(unsigned int i=0; i < 16; i++) + serializer.extract(result[i]); + +} + +TypedResult continuousBit(C::mip_interface& device, uint8_t* resultOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + uint8_t responseLength = sizeof(buffer); + + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTINUOUS_BIT, NULL, 0, REPLY_CONTINUOUS_BIT, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + assert(resultOut); + for(unsigned int i=0; i < 16; i++) + deserializer.extract(resultOut[i]); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +void CommSpeed::insert(Serializer& serializer) const +{ + serializer.insert(function); + + serializer.insert(port); + + if( function == FunctionSelector::WRITE ) + { + serializer.insert(baud); + + } +} +void CommSpeed::extract(Serializer& serializer) +{ + serializer.extract(function); + + serializer.extract(port); + + if( function == FunctionSelector::WRITE ) + { + serializer.extract(baud); + + } +} + +void CommSpeed::Response::insert(Serializer& serializer) const +{ + serializer.insert(port); + + serializer.insert(baud); + +} +void CommSpeed::Response::extract(Serializer& serializer) +{ + serializer.extract(port); + + serializer.extract(baud); + +} + +TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, uint32_t baud) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + serializer.insert(FunctionSelector::WRITE); + serializer.insert(port); + + serializer.insert(baud); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); +} +TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + serializer.insert(FunctionSelector::READ); + serializer.insert(port); + + assert(serializer.isOk()); + + uint8_t responseLength = sizeof(buffer); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length(), REPLY_COMM_SPEED, buffer, &responseLength); + + if( result == MIP_ACK_OK ) + { + Serializer deserializer(buffer, responseLength); + + deserializer.extract(port); + + assert(baudOut); + deserializer.extract(*baudOut); + + if( deserializer.remaining() != 0 ) + result = MIP_STATUS_ERROR; + } + return result; +} +TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + serializer.insert(FunctionSelector::SAVE); + serializer.insert(port); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); +} +TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + serializer.insert(FunctionSelector::LOAD); + serializer.insert(port); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); +} +TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + serializer.insert(FunctionSelector::RESET); + serializer.insert(port); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); +} +void GpsTimeUpdate::insert(Serializer& serializer) const +{ + serializer.insert(function); + + if( function == FunctionSelector::WRITE ) + { + serializer.insert(field_id); + + serializer.insert(value); + + } +} +void GpsTimeUpdate::extract(Serializer& serializer) +{ + serializer.extract(function); + + if( function == FunctionSelector::WRITE ) + { + serializer.extract(field_id); + + serializer.extract(value); + + } +} + +TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeUpdate::FieldId fieldId, uint32_t value) +{ + uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; + Serializer serializer(buffer, sizeof(buffer)); + + serializer.insert(FunctionSelector::WRITE); + serializer.insert(fieldId); + + serializer.insert(value); + + assert(serializer.isOk()); + + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)serializer.length()); +} +void SoftReset::insert(Serializer& serializer) const +{ + (void)serializer; +} +void SoftReset::extract(Serializer& serializer) +{ + (void)serializer; +} + +TypedResult softReset(C::mip_interface& device) +{ + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_RESET, NULL, 0); +} + +} // namespace commands_base +} // namespace mip + diff --git a/src/cpp/mip/definitions/commands_filter.cpp b/src/cpp/mip/definitions/commands_filter.cpp index f0f6c80d4..9a444f810 100644 --- a/src/cpp/mip/definitions/commands_filter.cpp +++ b/src/cpp/mip/definitions/commands_filter.cpp @@ -88,6 +88,17 @@ void EstimationControl::extract(Serializer& serializer) } } +void EstimationControl::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + +} +void EstimationControl::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + +} + TypedResult writeEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -324,6 +335,17 @@ void TareOrientation::extract(Serializer& serializer) } } +void TareOrientation::Response::insert(Serializer& serializer) const +{ + serializer.insert(axes); + +} +void TareOrientation::Response::extract(Serializer& serializer) +{ + serializer.extract(axes); + +} + TypedResult writeTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes axes) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -410,6 +432,17 @@ void VehicleDynamicsMode::extract(Serializer& serializer) } } +void VehicleDynamicsMode::Response::insert(Serializer& serializer) const +{ + serializer.insert(mode); + +} +void VehicleDynamicsMode::Response::extract(Serializer& serializer) +{ + serializer.extract(mode); + +} + TypedResult writeVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -504,6 +537,25 @@ void SensorToVehicleRotationEuler::extract(Serializer& serializer) } } +void SensorToVehicleRotationEuler::Response::insert(Serializer& serializer) const +{ + serializer.insert(roll); + + serializer.insert(pitch); + + serializer.insert(yaw); + +} +void SensorToVehicleRotationEuler::Response::extract(Serializer& serializer) +{ + serializer.extract(roll); + + serializer.extract(pitch); + + serializer.extract(yaw); + +} + TypedResult writeSensorToVehicleRotationEuler(C::mip_interface& device, float roll, float pitch, float yaw) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -600,6 +652,17 @@ void SensorToVehicleRotationDcm::extract(Serializer& serializer) } } +void SensorToVehicleRotationDcm::Response::insert(Serializer& serializer) const +{ + serializer.insert(dcm); + +} +void SensorToVehicleRotationDcm::Response::extract(Serializer& serializer) +{ + serializer.extract(dcm); + +} + TypedResult writeSensorToVehicleRotationDcm(C::mip_interface& device, const float* dcm) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -689,6 +752,17 @@ void SensorToVehicleRotationQuaternion::extract(Serializer& serializer) } } +void SensorToVehicleRotationQuaternion::Response::insert(Serializer& serializer) const +{ + serializer.insert(quat); + +} +void SensorToVehicleRotationQuaternion::Response::extract(Serializer& serializer) +{ + serializer.extract(quat); + +} + TypedResult writeSensorToVehicleRotationQuaternion(C::mip_interface& device, const float* quat) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -778,6 +852,17 @@ void SensorToVehicleOffset::extract(Serializer& serializer) } } +void SensorToVehicleOffset::Response::insert(Serializer& serializer) const +{ + serializer.insert(offset); + +} +void SensorToVehicleOffset::Response::extract(Serializer& serializer) +{ + serializer.extract(offset); + +} + TypedResult writeSensorToVehicleOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -867,6 +952,17 @@ void AntennaOffset::extract(Serializer& serializer) } } +void AntennaOffset::Response::insert(Serializer& serializer) const +{ + serializer.insert(offset); + +} +void AntennaOffset::Response::extract(Serializer& serializer) +{ + serializer.extract(offset); + +} + TypedResult writeAntennaOffset(C::mip_interface& device, const float* offset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -956,6 +1052,17 @@ void GnssSource::extract(Serializer& serializer) } } +void GnssSource::Response::insert(Serializer& serializer) const +{ + serializer.insert(source); + +} +void GnssSource::Response::extract(Serializer& serializer) +{ + serializer.extract(source); + +} + TypedResult writeGnssSource(C::mip_interface& device, GnssSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1042,6 +1149,17 @@ void HeadingSource::extract(Serializer& serializer) } } +void HeadingSource::Response::insert(Serializer& serializer) const +{ + serializer.insert(source); + +} +void HeadingSource::Response::extract(Serializer& serializer) +{ + serializer.extract(source); + +} + TypedResult writeHeadingSource(C::mip_interface& device, HeadingSource::Source source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1128,6 +1246,17 @@ void AutoInitControl::extract(Serializer& serializer) } } +void AutoInitControl::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + +} +void AutoInitControl::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + +} + TypedResult writeAutoInitControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1214,6 +1343,17 @@ void AccelNoise::extract(Serializer& serializer) } } +void AccelNoise::Response::insert(Serializer& serializer) const +{ + serializer.insert(noise); + +} +void AccelNoise::Response::extract(Serializer& serializer) +{ + serializer.extract(noise); + +} + TypedResult writeAccelNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1303,6 +1443,17 @@ void GyroNoise::extract(Serializer& serializer) } } +void GyroNoise::Response::insert(Serializer& serializer) const +{ + serializer.insert(noise); + +} +void GyroNoise::Response::extract(Serializer& serializer) +{ + serializer.extract(noise); + +} + TypedResult writeGyroNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1396,6 +1547,21 @@ void AccelBiasModel::extract(Serializer& serializer) } } +void AccelBiasModel::Response::insert(Serializer& serializer) const +{ + serializer.insert(beta); + + serializer.insert(noise); + +} +void AccelBiasModel::Response::extract(Serializer& serializer) +{ + serializer.extract(beta); + + serializer.extract(noise); + +} + TypedResult writeAccelBiasModel(C::mip_interface& device, const float* beta, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1497,6 +1663,21 @@ void GyroBiasModel::extract(Serializer& serializer) } } +void GyroBiasModel::Response::insert(Serializer& serializer) const +{ + serializer.insert(beta); + + serializer.insert(noise); + +} +void GyroBiasModel::Response::extract(Serializer& serializer) +{ + serializer.extract(beta); + + serializer.extract(noise); + +} + TypedResult writeGyroBiasModel(C::mip_interface& device, const float* beta, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1594,6 +1775,17 @@ void AltitudeAiding::extract(Serializer& serializer) } } +void AltitudeAiding::Response::insert(Serializer& serializer) const +{ + serializer.insert(selector); + +} +void AltitudeAiding::Response::extract(Serializer& serializer) +{ + serializer.extract(selector); + +} + TypedResult writeAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector selector) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1680,6 +1872,17 @@ void PitchRollAiding::extract(Serializer& serializer) } } +void PitchRollAiding::Response::insert(Serializer& serializer) const +{ + serializer.insert(source); + +} +void PitchRollAiding::Response::extract(Serializer& serializer) +{ + serializer.extract(source); + +} + TypedResult writePitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource source) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1770,6 +1973,21 @@ void AutoZupt::extract(Serializer& serializer) } } +void AutoZupt::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + + serializer.insert(threshold); + +} +void AutoZupt::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + + serializer.extract(threshold); + +} + TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, float threshold) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -1865,6 +2083,21 @@ void AutoAngularZupt::extract(Serializer& serializer) } } +void AutoAngularZupt::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + + serializer.insert(threshold); + +} +void AutoAngularZupt::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + + serializer.extract(threshold); + +} + TypedResult writeAutoAngularZupt(C::mip_interface& device, uint8_t enable, float threshold) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2013,6 +2246,17 @@ void GravityNoise::extract(Serializer& serializer) } } +void GravityNoise::Response::insert(Serializer& serializer) const +{ + serializer.insert(noise); + +} +void GravityNoise::Response::extract(Serializer& serializer) +{ + serializer.extract(noise); + +} + TypedResult writeGravityNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2102,6 +2346,17 @@ void PressureAltitudeNoise::extract(Serializer& serializer) } } +void PressureAltitudeNoise::Response::insert(Serializer& serializer) const +{ + serializer.insert(noise); + +} +void PressureAltitudeNoise::Response::extract(Serializer& serializer) +{ + serializer.extract(noise); + +} + TypedResult writePressureAltitudeNoise(C::mip_interface& device, float noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2188,6 +2443,17 @@ void HardIronOffsetNoise::extract(Serializer& serializer) } } +void HardIronOffsetNoise::Response::insert(Serializer& serializer) const +{ + serializer.insert(noise); + +} +void HardIronOffsetNoise::Response::extract(Serializer& serializer) +{ + serializer.extract(noise); + +} + TypedResult writeHardIronOffsetNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2277,6 +2543,17 @@ void SoftIronMatrixNoise::extract(Serializer& serializer) } } +void SoftIronMatrixNoise::Response::insert(Serializer& serializer) const +{ + serializer.insert(noise); + +} +void SoftIronMatrixNoise::Response::extract(Serializer& serializer) +{ + serializer.extract(noise); + +} + TypedResult writeSoftIronMatrixNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2366,6 +2643,17 @@ void MagNoise::extract(Serializer& serializer) } } +void MagNoise::Response::insert(Serializer& serializer) const +{ + serializer.insert(noise); + +} +void MagNoise::Response::extract(Serializer& serializer) +{ + serializer.extract(noise); + +} + TypedResult writeMagNoise(C::mip_interface& device, const float* noise) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2459,6 +2747,21 @@ void InclinationSource::extract(Serializer& serializer) } } +void InclinationSource::Response::insert(Serializer& serializer) const +{ + serializer.insert(source); + + serializer.insert(inclination); + +} +void InclinationSource::Response::extract(Serializer& serializer) +{ + serializer.extract(source); + + serializer.extract(inclination); + +} + TypedResult writeInclinationSource(C::mip_interface& device, FilterMagParamSource source, float inclination) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2554,6 +2857,21 @@ void MagneticDeclinationSource::extract(Serializer& serializer) } } +void MagneticDeclinationSource::Response::insert(Serializer& serializer) const +{ + serializer.insert(source); + + serializer.insert(declination); + +} +void MagneticDeclinationSource::Response::extract(Serializer& serializer) +{ + serializer.extract(source); + + serializer.extract(declination); + +} + TypedResult writeMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource source, float declination) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2649,6 +2967,21 @@ void MagFieldMagnitudeSource::extract(Serializer& serializer) } } +void MagFieldMagnitudeSource::Response::insert(Serializer& serializer) const +{ + serializer.insert(source); + + serializer.insert(magnitude); + +} +void MagFieldMagnitudeSource::Response::extract(Serializer& serializer) +{ + serializer.extract(source); + + serializer.extract(magnitude); + +} + TypedResult writeMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource source, float magnitude) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2752,6 +3085,29 @@ void ReferencePosition::extract(Serializer& serializer) } } +void ReferencePosition::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + + serializer.insert(latitude); + + serializer.insert(longitude); + + serializer.insert(altitude); + +} +void ReferencePosition::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + + serializer.extract(latitude); + + serializer.extract(longitude); + + serializer.extract(altitude); + +} + TypedResult writeReferencePosition(C::mip_interface& device, bool enable, double latitude, double longitude, double altitude) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -2877,6 +3233,41 @@ void AccelMagnitudeErrorAdaptiveMeasurement::extract(Serializer& serializer) } } +void AccelMagnitudeErrorAdaptiveMeasurement::Response::insert(Serializer& serializer) const +{ + serializer.insert(adaptive_measurement); + + serializer.insert(frequency); + + serializer.insert(low_limit); + + serializer.insert(high_limit); + + serializer.insert(low_limit_uncertainty); + + serializer.insert(high_limit_uncertainty); + + serializer.insert(minimum_uncertainty); + +} +void AccelMagnitudeErrorAdaptiveMeasurement::Response::extract(Serializer& serializer) +{ + serializer.extract(adaptive_measurement); + + serializer.extract(frequency); + + serializer.extract(low_limit); + + serializer.extract(high_limit); + + serializer.extract(low_limit_uncertainty); + + serializer.extract(high_limit_uncertainty); + + serializer.extract(minimum_uncertainty); + +} + TypedResult writeAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3017,6 +3408,41 @@ void MagMagnitudeErrorAdaptiveMeasurement::extract(Serializer& serializer) } } +void MagMagnitudeErrorAdaptiveMeasurement::Response::insert(Serializer& serializer) const +{ + serializer.insert(adaptive_measurement); + + serializer.insert(frequency); + + serializer.insert(low_limit); + + serializer.insert(high_limit); + + serializer.insert(low_limit_uncertainty); + + serializer.insert(high_limit_uncertainty); + + serializer.insert(minimum_uncertainty); + +} +void MagMagnitudeErrorAdaptiveMeasurement::Response::extract(Serializer& serializer) +{ + serializer.extract(adaptive_measurement); + + serializer.extract(frequency); + + serializer.extract(low_limit); + + serializer.extract(high_limit); + + serializer.extract(low_limit_uncertainty); + + serializer.extract(high_limit_uncertainty); + + serializer.extract(minimum_uncertainty); + +} + TypedResult writeMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement adaptiveMeasurement, float frequency, float lowLimit, float highLimit, float lowLimitUncertainty, float highLimitUncertainty, float minimumUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3149,6 +3575,33 @@ void MagDipAngleErrorAdaptiveMeasurement::extract(Serializer& serializer) } } +void MagDipAngleErrorAdaptiveMeasurement::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + + serializer.insert(frequency); + + serializer.insert(high_limit); + + serializer.insert(high_limit_uncertainty); + + serializer.insert(minimum_uncertainty); + +} +void MagDipAngleErrorAdaptiveMeasurement::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + + serializer.extract(frequency); + + serializer.extract(high_limit); + + serializer.extract(high_limit_uncertainty); + + serializer.extract(minimum_uncertainty); + +} + TypedResult writeMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool enable, float frequency, float highLimit, float highLimitUncertainty, float minimumUncertainty) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3259,6 +3712,21 @@ void AidingMeasurementEnable::extract(Serializer& serializer) } } +void AidingMeasurementEnable::Response::insert(Serializer& serializer) const +{ + serializer.insert(aiding_source); + + serializer.insert(enable); + +} +void AidingMeasurementEnable::Response::extract(Serializer& serializer) +{ + serializer.extract(aiding_source); + + serializer.extract(enable); + +} + TypedResult writeAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3378,6 +3846,25 @@ void KinematicConstraint::extract(Serializer& serializer) } } +void KinematicConstraint::Response::insert(Serializer& serializer) const +{ + serializer.insert(acceleration_constraint_selection); + + serializer.insert(velocity_constraint_selection); + + serializer.insert(angular_constraint_selection); + +} +void KinematicConstraint::Response::extract(Serializer& serializer) +{ + serializer.extract(acceleration_constraint_selection); + + serializer.extract(velocity_constraint_selection); + + serializer.extract(angular_constraint_selection); + +} + TypedResult writeKinematicConstraint(C::mip_interface& device, uint8_t accelerationConstraintSelection, uint8_t velocityConstraintSelection, uint8_t angularConstraintSelection) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3506,6 +3993,49 @@ void InitializationConfiguration::extract(Serializer& serializer) } } +void InitializationConfiguration::Response::insert(Serializer& serializer) const +{ + serializer.insert(wait_for_run_command); + + serializer.insert(initial_cond_src); + + serializer.insert(auto_heading_alignment_selector); + + serializer.insert(initial_heading); + + serializer.insert(initial_pitch); + + serializer.insert(initial_roll); + + serializer.insert(initial_position); + + serializer.insert(initial_velocity); + + serializer.insert(reference_frame_selector); + +} +void InitializationConfiguration::Response::extract(Serializer& serializer) +{ + serializer.extract(wait_for_run_command); + + serializer.extract(initial_cond_src); + + serializer.extract(auto_heading_alignment_selector); + + serializer.extract(initial_heading); + + serializer.extract(initial_pitch); + + serializer.extract(initial_roll); + + serializer.extract(initial_position); + + serializer.extract(initial_velocity); + + serializer.extract(reference_frame_selector); + +} + TypedResult writeInitializationConfiguration(C::mip_interface& device, uint8_t waitForRunCommand, InitializationConfiguration::InitialConditionSource initialCondSrc, InitializationConfiguration::AlignmentSelector autoHeadingAlignmentSelector, float initialHeading, float initialPitch, float initialRoll, const float* initialPosition, const float* initialVelocity, FilterReferenceFrame referenceFrameSelector) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3642,6 +4172,21 @@ void AdaptiveFilterOptions::extract(Serializer& serializer) } } +void AdaptiveFilterOptions::Response::insert(Serializer& serializer) const +{ + serializer.insert(level); + + serializer.insert(time_limit); + +} +void AdaptiveFilterOptions::Response::extract(Serializer& serializer) +{ + serializer.extract(level); + + serializer.extract(time_limit); + +} + TypedResult writeAdaptiveFilterOptions(C::mip_interface& device, uint8_t level, uint16_t timeLimit) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3737,6 +4282,21 @@ void MultiAntennaOffset::extract(Serializer& serializer) } } +void MultiAntennaOffset::Response::insert(Serializer& serializer) const +{ + serializer.insert(receiver_id); + + serializer.insert(antenna_offset); + +} +void MultiAntennaOffset::Response::extract(Serializer& serializer) +{ + serializer.extract(receiver_id); + + serializer.extract(antenna_offset); + +} + TypedResult writeMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, const float* antennaOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3846,6 +4406,25 @@ void RelPosConfiguration::extract(Serializer& serializer) } } +void RelPosConfiguration::Response::insert(Serializer& serializer) const +{ + serializer.insert(source); + + serializer.insert(reference_frame_selector); + + serializer.insert(reference_coordinates); + +} +void RelPosConfiguration::Response::extract(Serializer& serializer) +{ + serializer.extract(source); + + serializer.extract(reference_frame_selector); + + serializer.extract(reference_coordinates); + +} + TypedResult writeRelPosConfiguration(C::mip_interface& device, uint8_t source, FilterReferenceFrame referenceFrameSelector, const double* referenceCoordinates) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -3949,6 +4528,21 @@ void RefPointLeverArm::extract(Serializer& serializer) } } +void RefPointLeverArm::Response::insert(Serializer& serializer) const +{ + serializer.insert(ref_point_sel); + + serializer.insert(lever_arm_offset); + +} +void RefPointLeverArm::Response::extract(Serializer& serializer) +{ + serializer.extract(ref_point_sel); + + serializer.extract(lever_arm_offset); + +} + TypedResult writeRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector refPointSel, const float* leverArmOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4087,6 +4681,21 @@ void SpeedLeverArm::extract(Serializer& serializer) } } +void SpeedLeverArm::Response::insert(Serializer& serializer) const +{ + serializer.insert(source); + + serializer.insert(lever_arm_offset); + +} +void SpeedLeverArm::Response::extract(Serializer& serializer) +{ + serializer.extract(source); + + serializer.extract(lever_arm_offset); + +} + TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t source, const float* leverArmOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4188,6 +4797,17 @@ void WheeledVehicleConstraintControl::extract(Serializer& serializer) } } +void WheeledVehicleConstraintControl::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + +} +void WheeledVehicleConstraintControl::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + +} + TypedResult writeWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4274,6 +4894,17 @@ void VerticalGyroConstraintControl::extract(Serializer& serializer) } } +void VerticalGyroConstraintControl::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + +} +void VerticalGyroConstraintControl::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + +} + TypedResult writeVerticalGyroConstraintControl(C::mip_interface& device, uint8_t enable) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -4364,6 +4995,21 @@ void GnssAntennaCalControl::extract(Serializer& serializer) } } +void GnssAntennaCalControl::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + + serializer.insert(max_offset); + +} +void GnssAntennaCalControl::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + + serializer.extract(max_offset); + +} + TypedResult writeGnssAntennaCalControl(C::mip_interface& device, uint8_t enable, float maxOffset) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/cpp/mip/definitions/commands_gnss.cpp b/src/cpp/mip/definitions/commands_gnss.cpp index 96b032a22..078d367c1 100644 --- a/src/cpp/mip/definitions/commands_gnss.cpp +++ b/src/cpp/mip/definitions/commands_gnss.cpp @@ -50,6 +50,22 @@ void ReceiverInfo::extract(Serializer& serializer) (void)serializer; } +void ReceiverInfo::Response::insert(Serializer& serializer) const +{ + serializer.insert(num_receivers); + + for(unsigned int i=0; i < num_receivers; i++) + serializer.insert(receiver_info[i]); + +} +void ReceiverInfo::Response::extract(Serializer& serializer) +{ + serializer.extract_count(num_receivers, sizeof(receiver_info)/sizeof(receiver_info[0])); + for(unsigned int i=0; i < num_receivers; i++) + serializer.extract(receiver_info[i]); + +} + TypedResult receiverInfo(C::mip_interface& device, uint8_t* numReceiversOut, uint8_t numReceiversOutMax, ReceiverInfo::Info* receiverInfoOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -110,6 +126,35 @@ void SignalConfiguration::extract(Serializer& serializer) } } +void SignalConfiguration::Response::insert(Serializer& serializer) const +{ + serializer.insert(gps_enable); + + serializer.insert(glonass_enable); + + serializer.insert(galileo_enable); + + serializer.insert(beidou_enable); + + for(unsigned int i=0; i < 4; i++) + serializer.insert(reserved[i]); + +} +void SignalConfiguration::Response::extract(Serializer& serializer) +{ + serializer.extract(gps_enable); + + serializer.extract(glonass_enable); + + serializer.extract(galileo_enable); + + serializer.extract(beidou_enable); + + for(unsigned int i=0; i < 4; i++) + serializer.extract(reserved[i]); + +} + TypedResult writeSignalConfiguration(C::mip_interface& device, uint8_t gpsEnable, uint8_t glonassEnable, uint8_t galileoEnable, uint8_t beidouEnable, const uint8_t* reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -225,6 +270,23 @@ void RtkDongleConfiguration::extract(Serializer& serializer) } } +void RtkDongleConfiguration::Response::insert(Serializer& serializer) const +{ + serializer.insert(enable); + + for(unsigned int i=0; i < 3; i++) + serializer.insert(reserved[i]); + +} +void RtkDongleConfiguration::Response::extract(Serializer& serializer) +{ + serializer.extract(enable); + + for(unsigned int i=0; i < 3; i++) + serializer.extract(reserved[i]); + +} + TypedResult writeRtkDongleConfiguration(C::mip_interface& device, uint8_t enable, const uint8_t* reserved) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/cpp/mip/definitions/commands_rtk.cpp b/src/cpp/mip/definitions/commands_rtk.cpp index 8fb96bff5..e9f26bed0 100644 --- a/src/cpp/mip/definitions/commands_rtk.cpp +++ b/src/cpp/mip/definitions/commands_rtk.cpp @@ -29,6 +29,17 @@ void GetStatusFlags::extract(Serializer& serializer) (void)serializer; } +void GetStatusFlags::Response::insert(Serializer& serializer) const +{ + serializer.insert(flags); + +} +void GetStatusFlags::Response::extract(Serializer& serializer) +{ + serializer.extract(flags); + +} + TypedResult getStatusFlags(C::mip_interface& device, GetStatusFlags::StatusFlags* flagsOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -57,6 +68,19 @@ void GetImei::extract(Serializer& serializer) (void)serializer; } +void GetImei::Response::insert(Serializer& serializer) const +{ + for(unsigned int i=0; i < 32; i++) + serializer.insert(IMEI[i]); + +} +void GetImei::Response::extract(Serializer& serializer) +{ + for(unsigned int i=0; i < 32; i++) + serializer.extract(IMEI[i]); + +} + TypedResult getImei(C::mip_interface& device, char* imeiOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -86,6 +110,19 @@ void GetImsi::extract(Serializer& serializer) (void)serializer; } +void GetImsi::Response::insert(Serializer& serializer) const +{ + for(unsigned int i=0; i < 32; i++) + serializer.insert(IMSI[i]); + +} +void GetImsi::Response::extract(Serializer& serializer) +{ + for(unsigned int i=0; i < 32; i++) + serializer.extract(IMSI[i]); + +} + TypedResult getImsi(C::mip_interface& device, char* imsiOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -115,6 +152,19 @@ void GetIccid::extract(Serializer& serializer) (void)serializer; } +void GetIccid::Response::insert(Serializer& serializer) const +{ + for(unsigned int i=0; i < 32; i++) + serializer.insert(ICCID[i]); + +} +void GetIccid::Response::extract(Serializer& serializer) +{ + for(unsigned int i=0; i < 32; i++) + serializer.extract(ICCID[i]); + +} + TypedResult getIccid(C::mip_interface& device, char* iccidOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -156,6 +206,17 @@ void ConnectedDeviceType::extract(Serializer& serializer) } } +void ConnectedDeviceType::Response::insert(Serializer& serializer) const +{ + serializer.insert(devType); + +} +void ConnectedDeviceType::Response::extract(Serializer& serializer) +{ + serializer.extract(devType); + +} + TypedResult writeConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type devtype) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -230,6 +291,19 @@ void GetActCode::extract(Serializer& serializer) (void)serializer; } +void GetActCode::Response::insert(Serializer& serializer) const +{ + for(unsigned int i=0; i < 32; i++) + serializer.insert(ActivationCode[i]); + +} +void GetActCode::Response::extract(Serializer& serializer) +{ + for(unsigned int i=0; i < 32; i++) + serializer.extract(ActivationCode[i]); + +} + TypedResult getActCode(C::mip_interface& device, char* activationcodeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -259,6 +333,19 @@ void GetModemFirmwareVersion::extract(Serializer& serializer) (void)serializer; } +void GetModemFirmwareVersion::Response::insert(Serializer& serializer) const +{ + for(unsigned int i=0; i < 32; i++) + serializer.insert(ModemFirmwareVersion[i]); + +} +void GetModemFirmwareVersion::Response::extract(Serializer& serializer) +{ + for(unsigned int i=0; i < 32; i++) + serializer.extract(ModemFirmwareVersion[i]); + +} + TypedResult getModemFirmwareVersion(C::mip_interface& device, char* modemfirmwareversionOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -288,6 +375,25 @@ void GetRssi::extract(Serializer& serializer) (void)serializer; } +void GetRssi::Response::insert(Serializer& serializer) const +{ + serializer.insert(valid); + + serializer.insert(rssi); + + serializer.insert(signalQuality); + +} +void GetRssi::Response::extract(Serializer& serializer) +{ + serializer.extract(valid); + + serializer.extract(rssi); + + serializer.extract(signalQuality); + +} + TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* rssiOut, int32_t* signalqualityOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -328,6 +434,29 @@ void ServiceStatus::extract(Serializer& serializer) } +void ServiceStatus::Response::insert(Serializer& serializer) const +{ + serializer.insert(flags); + + serializer.insert(receivedBytes); + + serializer.insert(lastBytes); + + serializer.insert(lastBytesTime); + +} +void ServiceStatus::Response::extract(Serializer& serializer) +{ + serializer.extract(flags); + + serializer.extract(receivedBytes); + + serializer.extract(lastBytes); + + serializer.extract(lastBytesTime); + +} + TypedResult serviceStatus(C::mip_interface& device, uint32_t reserved1, uint32_t reserved2, ServiceStatus::ServiceFlags* flagsOut, uint32_t* receivedbytesOut, uint32_t* lastbytesOut, uint64_t* lastbytestimeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/cpp/mip/definitions/commands_system.cpp b/src/cpp/mip/definitions/commands_system.cpp index 10133c89d..d5194ddb0 100644 --- a/src/cpp/mip/definitions/commands_system.cpp +++ b/src/cpp/mip/definitions/commands_system.cpp @@ -41,6 +41,17 @@ void CommMode::extract(Serializer& serializer) } } +void CommMode::Response::insert(Serializer& serializer) const +{ + serializer.insert(mode); + +} +void CommMode::Response::extract(Serializer& serializer) +{ + serializer.extract(mode); + +} + TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index 7e7d1a913..df5f7dd75 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -751,8 +751,8 @@ struct MetadataFor { 5, "VTG", "Course over Ground. Source can be the Filter or GNSS1/2 datasets." }, { 6, "HDT", "Heading, True. Source can be the Filter or GNSS1/2 datasets." }, { 7, "ZDA", "Time & Date. Source must be the GNSS1 or GNSS2 datasets." }, - { 129, "MSRA", "MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED." }, - { 130, "MSRR", "MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED." }, + { 129, "PKRA", "Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED." }, + { 130, "PKRR", "Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED." }, }; static constexpr inline EnumInfo value = { @@ -3691,7 +3691,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagSoftIronMatrix", /* .title = */ "Magnetometer Soft Iron Matrix", - /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \\begin{bmatrix} 0 & 1 & 2 \\\ 3 & 4 & 5 \\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n", + /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \begin{bmatrix} 0 & 1 & 2 \\ 3 & 4 & 5 \\ 6 & 7 & 8 \end{bmatrix} EQEND\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3963,7 +3963,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformDcm", /* .title = */ "Sensor to Vehicle Frame Transformation Direction Cosine Matrix", - /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.\n\nThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
\nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
\n\nWhere:
\n\nEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND\nThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not\nbe exactly equal to array used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.\n\nThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
\nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
\n\nWhere:
\n\nEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND\nThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not\nbe exactly equal to array used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, diff --git a/src/cpp/mip/metadata/definitions/commands_aiding.hpp b/src/cpp/mip/metadata/definitions/commands_aiding.hpp index a0f98d3d1..7c289a55d 100644 --- a/src/cpp/mip/metadata/definitions/commands_aiding.hpp +++ b/src/cpp/mip/metadata/definitions/commands_aiding.hpp @@ -185,7 +185,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_aiding::FrameConfig", /* .title = */ "Frame Configuration", - /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID.\nThe frame ID used in this command should mirror the frame ID used in the aiding command\n(if that aiding measurement is measured in this reference frame).\n\nThis transform satisfies the following relationship:\n\nEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
\n\nWhere:
\nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

\nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
\nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
\n\nRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element\nin the rotation vector is ignored and should be set to 0.\n\nWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.\n\nExample: GNSS antenna lever arm\n\nFrame ID: 1\nFormat: 1 (Euler)\nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)\nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)\n", + /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command\nshould mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame)\n\nThis transform satisfies the following relationship:\n\nEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
\n\nWhere:
\nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

\nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
\nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
\n\nRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element\nin the rotation vector is ignored and should be set to 0.\n\nWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.\n\nExample: GNSS antenna lever arm\n\nFrame ID: 1\nFormat: 1 (Euler)\nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)\nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -195,9 +195,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EchoControl::Mode; + using type = commands_aiding::AidingEchoControl::Mode; static constexpr inline EnumInfo::Entry entries[] = { { 0, "SUPPRESS_ACK", "Suppresses the usual command ack field for aiding messages." }, @@ -215,16 +215,16 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EchoControl::Response; + using type = commands_aiding::AidingEchoControl::Response; static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "mode", /* .docs = */ "Controls data echoing.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -232,7 +232,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::EchoControl::Response", + /* .name = */ "commands_aiding::AidingEchoControl::Response", /* .title = */ "None", /* .docs = */ "", /* .parameters = */ parameters, @@ -244,17 +244,17 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EchoControl; + using type = commands_aiding::AidingEchoControl; static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { /* .name = */ "mode", /* .docs = */ "Controls data echoing.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -262,7 +262,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::EchoControl", + /* .name = */ "commands_aiding::AidingEchoControl", /* .title = */ "Aiding Command Echo Control", /* .docs = */ "Controls command response behavior to external aiding commands", /* .parameters = */ parameters, @@ -337,9 +337,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::PosEcef::ValidFlags; + using type = commands_aiding::EcefPos::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -357,9 +357,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::PosEcef; + using type = commands_aiding::EcefPos; static constexpr inline ParameterInfo parameters[] = { { @@ -401,8 +401,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -410,7 +410,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::PosEcef", + /* .name = */ "commands_aiding::EcefPos", /* .title = */ "ECEF Position", /* .docs = */ "Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system.", /* .parameters = */ parameters, @@ -422,9 +422,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::PosLlh::ValidFlags; + using type = commands_aiding::LlhPos::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "Latitude", "" }, @@ -442,9 +442,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::PosLlh; + using type = commands_aiding::LlhPos; static constexpr inline ParameterInfo parameters[] = { { @@ -504,8 +504,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -513,9 +513,9 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::PosLlh", + /* .name = */ "commands_aiding::LlhPos", /* .title = */ "LLH Position", - /* .docs = */ "Geodetic position aiding command.\nCoordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid.\nUncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height.", + /* .docs = */ "Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid.\nUncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -525,9 +525,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::HeightAboveEllipsoid; + using type = commands_aiding::Height; static constexpr inline ParameterInfo parameters[] = { { @@ -578,9 +578,9 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::HeightAboveEllipsoid", - /* .title = */ "Height Above Ellipsoid", - /* .docs = */ "Estimated value of the height above ellipsoid.", + /* .name = */ "commands_aiding::Height", + /* .title = */ "Height", + /* .docs = */ "Estimated value of height.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -590,9 +590,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VelEcef::ValidFlags; + using type = commands_aiding::EcefVel::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -610,9 +610,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VelEcef; + using type = commands_aiding::EcefVel; static constexpr inline ParameterInfo parameters[] = { { @@ -654,8 +654,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -663,7 +663,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::VelEcef", + /* .name = */ "commands_aiding::EcefVel", /* .title = */ "ECEF Velocity", /* .docs = */ "ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame.", /* .parameters = */ parameters, @@ -675,9 +675,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VelNed::ValidFlags; + using type = commands_aiding::NedVel::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -695,9 +695,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VelNed; + using type = commands_aiding::NedVel; static constexpr inline ParameterInfo parameters[] = { { @@ -739,8 +739,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -748,7 +748,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::VelNed", + /* .name = */ "commands_aiding::NedVel", /* .title = */ "NED Velocity", /* .docs = */ "NED velocity aiding command. Coordinates are given in the local North-East-Down frame.", /* .parameters = */ parameters, @@ -760,9 +760,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VelBodyFrame::ValidFlags; + using type = commands_aiding::VehicleFixedFrameVelocity::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -780,9 +780,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VelBodyFrame; + using type = commands_aiding::VehicleFixedFrameVelocity; static constexpr inline ParameterInfo parameters[] = { { @@ -824,8 +824,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -833,9 +833,9 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::VelBodyFrame", - /* .title = */ "Body Frame Velocity", - /* .docs = */ "Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame.", + /* .name = */ "commands_aiding::VehicleFixedFrameVelocity", + /* .title = */ "Vehicle Frame Velocity", + /* .docs = */ "Estimate of velocity of the vehicle in the frame associated\nwith the given sensor ID.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -845,9 +845,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::HeadingTrue; + using type = commands_aiding::TrueHeading; static constexpr inline ParameterInfo parameters[] = { { @@ -898,7 +898,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::HeadingTrue", + /* .name = */ "commands_aiding::TrueHeading", /* .title = */ "True Heading", /* .docs = */ "", /* .parameters = */ parameters, @@ -1063,15 +1063,15 @@ struct MetadataFor static constexpr inline std::initializer_list ALL_COMMANDS_AIDING = { &MetadataFor::value, &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, }; diff --git a/src/cpp/mip/metadata/definitions/commands_filter.hpp b/src/cpp/mip/metadata/definitions/commands_filter.hpp index aec302139..00e1db970 100644 --- a/src/cpp/mip/metadata/definitions/commands_filter.hpp +++ b/src/cpp/mip/metadata/definitions/commands_filter.hpp @@ -665,7 +665,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationDcm", /* .title = */ "Sensor to Vehicle Frame Rotation DCM", - /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \\begin{bmatrix} 0 & 1 & 2\\\ 3 & 4 & 5\\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \begin{bmatrix} 0 & 1 & 2\\ 3 & 4 & 5\\ 6 & 7 & 8 \end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -724,7 +724,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationQuaternion", /* .title = */ "Sensor to Vehicle Frame Rotation Quaternion", - /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.\n\nNote: This is the rotation, the inverse of the transformation.\nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may not\nbe equivalent in value to the quaternion used to set the rotation, due to normalization.
\n
\nQuaternion element definition:

\n
\nEQSTART Q_{SEN}^{VEH} = \\begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \\end{bmatrix} EQEND\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.\n\nNote: This is the rotation, the inverse of the transformation.\nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may not\nbe equivalent in value to the quaternion used to set the rotation, due to normalization.
\n
\nQuaternion element definition:

\n
\nEQSTART Q_{SEN}^{VEH} = \begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \end{bmatrix} EQEND\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -842,7 +842,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AntennaOffset", /* .title = */ "GNSS Antenna Offset Control", - /* .docs = */ "Configure the GNSS antenna offset.\n\nFor 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.\n\nFor 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center.\n\nThis command should also be used for CV7 / GV7-INS NMEA Input over GPIO.\n\nThe magnitude of the offset vector is limited to 10 meters\n", + /* .docs = */ "Set the sensor to GNSS antenna offset.\n\nThis is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.\n\nThe magnitude of the offset vector is limited to 10 meters\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2549,7 +2549,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AccelMagnitudeErrorAdaptiveMeasurement", /* .title = */ "Gravity Magnitude Error Adaptive Measurement", - /* .docs = */ "Enable or disable the gravity magnitude error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nAdaptive measurements can be enabled/disabled without the need for providing the additional parameters.\nIn this case, only the function selector and enable value are required; all other parameters will remain at their previous values.\nWhen auto-adaptive is selected, the filter and limit parameters are ignored.\nInstead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality.\n", + /* .docs = */ "Enable or disable the gravity magnitude error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nAdaptive measurements can be enabled/disabled without the need for providing the additional parameters.\nIn this case, only the function selector and enable value are required; all other parameters will remain at their previous values.\nWhen “auto-adaptive” is selected, the filter and limit parameters are ignored.\nInstead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2870,7 +2870,7 @@ struct MetadataFor { 5, "EXTERNAL_HEADING", "External heading input" }, { 6, "EXTERNAL_ALTIMETER", "External pressure altimeter input" }, { 7, "EXTERNAL_MAGNETOMETER", "External magnetomer input" }, - { 8, "BODY_FRAME_VEL", "External body frame velocity input" }, + { 8, "VEHICLE_FRAME_VEL", "External vehicle frame velocity input" }, { 65535, "ALL", "Save/load/reset all options" }, }; diff --git a/src/cpp/mip/metadata/definitions/data_filter.hpp b/src/cpp/mip/metadata/definitions/data_filter.hpp index f50c4e187..58ba47315 100644 --- a/src/cpp/mip/metadata/definitions/data_filter.hpp +++ b/src/cpp/mip/metadata/definitions/data_filter.hpp @@ -189,7 +189,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AttitudeDcm", /* .title = */ "None", - /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2431,15 +2431,12 @@ struct MetadataFor { 4, "PRESSURE", "" }, { 5, "MAGNETOMETER", "" }, { 6, "SPEED", "" }, - { 33, "AIDING_POS_ECEF", "" }, - { 34, "AIDING_POS_LLH", "" }, - { 35, "AIDING_HEIGHT_ABOVE_ELLIPSOID", "" }, - { 40, "AIDING_VEL_ECEF", "" }, - { 41, "AIDING_VEL_NED", "" }, - { 42, "AIDING_VEL_BODY_FRAME", "" }, - { 49, "AIDING_HEADING_TRUE", "" }, - { 50, "AIDING_MAGNETIC_FIELD", "" }, - { 51, "AIDING_PRESSURE", "" }, + { 33, "POS_ECEF", "" }, + { 34, "POS_LLH", "" }, + { 40, "VEL_ECEF", "" }, + { 41, "VEL_NED", "" }, + { 42, "VEL_VEHICLE_FRAME", "" }, + { 49, "HEADING_TRUE", "" }, }; static constexpr inline EnumInfo value = { diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index 727311874..cf7d8052c 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -320,7 +320,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::CompOrientationMatrix", /* .title = */ "Complementary Filter Orientation Matrix", - /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, From 8816d9736b6e7a7a9b7b10364688c0995a4d4572 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 14:09:21 -0400 Subject: [PATCH 073/147] - Rename MIP_LOG_* --> MICROSTRAIN_LOG_*. - Use platform.hpp defines in serial and tcp files. --- examples/example_utils.cpp | 2 +- examples/watch_imu.c | 2 +- src/c/microstrain/common/embedded_time.h | 1 - src/c/microstrain/common/logging.c | 6 +- src/c/microstrain/common/logging.h | 70 +++++++++---------- .../connections/serial/serial_port.c | 50 ++++++------- .../connections/serial/serial_port.h | 6 +- .../microstrain/connections/tcp/tcp_socket.c | 14 ++-- .../microstrain/connections/tcp/tcp_socket.h | 4 +- 9 files changed, 79 insertions(+), 76 deletions(-) diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index 6d05ade7d..6bd5264fe 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -115,7 +115,7 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, std::unique_ptr handleCommonArgs(int argc, const char* argv[], int maxArgs) { // Setup the logger for the MIP SDK - MIP_LOG_INIT(&customLog, MICROSTRAIN_LOG_LEVEL_DEBUG, nullptr); + MICROSTRAIN_LOG_INIT(&customLog, MICROSTRAIN_LOG_LEVEL_DEBUG, nullptr); if( argc < 3 || argc > maxArgs ) { diff --git a/examples/watch_imu.c b/examples/watch_imu.c index e236214ab..2280a9f87 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -159,7 +159,7 @@ int main(int argc, const char* argv[]) return usage(argv[0]); // Initialize the MIP logger before opening the port so we can print errors if they occur - MIP_LOG_INIT(&customLog, MICROSTRAIN_LOG_LEVEL_INFO, NULL); + MICROSTRAIN_LOG_INIT(&customLog, MICROSTRAIN_LOG_LEVEL_INFO, NULL); if( !open_port(argv[1], baudrate) ) return 1; diff --git a/src/c/microstrain/common/embedded_time.h b/src/c/microstrain/common/embedded_time.h index d6ec2ca39..9cc33648b 100644 --- a/src/c/microstrain/common/embedded_time.h +++ b/src/c/microstrain/common/embedded_time.h @@ -4,7 +4,6 @@ #include - #ifdef __cplusplus namespace microstrain { namespace C { diff --git a/src/c/microstrain/common/logging.c b/src/c/microstrain/common/logging.c index ac709b0fe..27a1c0bd8 100644 --- a/src/c/microstrain/common/logging.c +++ b/src/c/microstrain/common/logging.c @@ -17,11 +17,11 @@ void* microstrain_log_user_data_ = NULL; //////////////////////////////////////////////////////////////////////////////// ///@brief Initializes the logger with a callback and user data. -/// Call MIP_LOG_INIT instead of using this function directly. +/// Call MICROSTRAIN_LOG_INIT instead of using this function directly. /// This function does not have to be called unless the user wants logging /// ///@param callback The callback to execute when there is data to log -///@param level The level that the MIP SDK should log at +///@param level The level that the MicroStrain SDK should log at ///@param user User data that will be passed to the callback every time it is excuted /// void microstrain_logging_init(microstrain_log_callback callback, microstrain_log_level level, void* user) @@ -64,7 +64,7 @@ void* microstrain_logging_user_data() //////////////////////////////////////////////////////////////////////////////// ///@brief Internal log function called by logging macros. /// Call MIP_LOG_* macros instead of using this function directly -///@copydetails mip::C::microstrain_log_callback +///@copydetails microstrain::C::microstrain_log_callback /// void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...) { diff --git a/src/c/microstrain/common/logging.h b/src/c/microstrain/common/logging.h index 6c5fe097e..c241cc651 100644 --- a/src/c/microstrain/common/logging.h +++ b/src/c/microstrain/common/logging.h @@ -8,7 +8,7 @@ extern "C" { #endif //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_c +///@addtogroup microstrain_c ///@{ //////////////////////////////////////////////////////////////////////////////// ///@defgroup microstrain_logging MicroStrain Logging [C] @@ -50,90 +50,90 @@ void* microstrain_logging_user_data(); void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// -///@brief Helper macro used to initialize the MIP logger. +///@brief Helper macro used to initialize the MicroStrain logger. /// This function does not need to be called unless the user wants logging /// ///@param callback The callback to execute when there is data to log -///@param level The level that the MIP SDK should log at +///@param level The level that the MicroStrain SDK should log at ///@param user User data that will be passed to the callback every time it is excuted /// #ifdef MICROSTRAIN_ENABLE_LOGGING -#define MIP_LOG_INIT(callback, level, user) microstrain_logging_init(callback, level, user) +#define MICROSTRAIN_LOG_INIT(callback, level, user) microstrain_logging_init(callback, level, user) #else -#define MIP_LOG_INIT(callback, level, user) (void)0 +#define MICROSTRAIN_LOG_INIT(callback, level, user) (void)0 #endif //////////////////////////////////////////////////////////////////////////////// -///@brief Helper macro used to log data inside the MIP SDK. Prefer specific -/// log level functions like MIP_LOG_INFO, etc. when possible. -///@copydetails mip::C::microstrain_log_callback +///@brief Helper macro used to log data inside the MicroStrain SDK. Prefer specific +/// log level functions like MICROSTRAIN_LOG_INFO, etc. when possible. +///@copydetails microstrain::C::microstrain_log_callback /// #ifdef MICROSTRAIN_ENABLE_LOGGING -#define MIP_LOG_LOG(level, ...) microstrain_logging_log(level, __VA_ARGS__) +#define MICROSTRAIN_LOG_LOG(level, ...) microstrain_logging_log(level, __VA_ARGS__) #else -#define MIP_LOG_LOG(level, ...) (void)0 +#define MICROSTRAIN_LOG_LOG(level, ...) (void)0 #endif #ifndef MICROSTRAIN_LOGGING_MAX_LEVEL -#define MICROSTRAIN_LOGGING_MAX_LEVEL MIP_LOG_LEVEL_WARN +#define MICROSTRAIN_LOGGING_MAX_LEVEL MICROSTRAIN_LOG_LEVEL_WARN #endif //////////////////////////////////////////////////////////////////////////////// -///@brief Helper macro used to log data inside the MIP SDK at fatal level +///@brief Helper macro used to log data inside the MicroStrain SDK at fatal level /// -///@param context Context of what called this function. Could be a MIP device, serial connection, etc. +///@param context Context of what called this function. Could be a mip device, serial connection, etc. ///@param fmt printf style format string ///@param ... Variadic args used to populate the fmt string /// #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_FATAL -#define MIP_LOG_FATAL(...) MIP_LOG_LOG(MICROSTRAIN_LOG_LEVEL_FATAL, __VA_ARGS__) +#define MICROSTRAIN_LOG_FATAL(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_FATAL, __VA_ARGS__) #else -#define MIP_LOG_FATAL(...) (void)0 +#define MICROSTRAIN_LOG_FATAL(...) (void)0 #endif //////////////////////////////////////////////////////////////////////////////// -///@brief Helper macro used to log data inside the MIP SDK at error level -///@copydetails mip::C::MIP_LOG_FATAL +///@brief Helper macro used to log data inside the MicroStrain SDK at error level +///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_ERROR -#define MIP_LOG_ERROR(...) MIP_LOG_LOG(MICROSTRAIN_LOG_LEVEL_ERROR, __VA_ARGS__) +#define MICROSTRAIN_LOG_ERROR(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_ERROR, __VA_ARGS__) #else -#define MIP_LOG_ERROR(...) (void)0 +#define MICROSTRAIN_LOG_ERROR(...) (void)0 #endif //////////////////////////////////////////////////////////////////////////////// -///@brief Helper macro used to log data inside the MIP SDK at warn level -///@copydetails mip::C::MIP_LOG_FATAL +///@brief Helper macro used to log data inside the MicroStrain SDK at warn level +///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_WARN -#define MIP_LOG_WARN(...) MIP_LOG_LOG(MICROSTRAIN_LOG_LEVEL_WARN, __VA_ARGS__) +#define MICROSTRAIN_LOG_WARN(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_WARN, __VA_ARGS__) #else -#define MIP_LOG_WARN(...) (void)0 +#define MICROSTRAIN_LOG_WARN(...) (void)0 #endif //////////////////////////////////////////////////////////////////////////////// -///@brief Helper macro used to log data inside the MIP SDK at info level -///@copydetails mip::C::MIP_LOG_FATAL +///@brief Helper macro used to log data inside the MicroStrain SDK at info level +///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_INFO -#define MIP_LOG_INFO(...) MIP_LOG_LOG(MIP_LOG_LEVEL_INFO, __VA_ARGS__) +#define MICROSTRAIN_LOG_INFO(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_INFO, __VA_ARGS__) #else -#define MIP_LOG_INFO(...) (void)0 +#define MICROSTRAIN_LOG_INFO(...) (void)0 #endif //////////////////////////////////////////////////////////////////////////////// -///@brief Helper macro used to log data inside the MIP SDK at debug level -///@copydetails mip::C::MIP_LOG_FATAL +///@brief Helper macro used to log data inside the MicroStrain SDK at debug level +///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_DEBUG -#define MIP_LOG_DEBUG(...) MIP_LOG_LOG(MIP_LOG_LEVEL_DEBUG, __VA_ARGS__) +#define MICROSTRAIN_LOG_DEBUG(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_DEBUG, __VA_ARGS__) #else -#define MIP_LOG_DEBUG(...) (void)0 +#define MICROSTRAIN_LOG_DEBUG(...) (void)0 #endif //////////////////////////////////////////////////////////////////////////////// -///@brief Helper macro used to log data inside the MIP SDK at trace level -///@copydetails mip::C::MIP_LOG_FATAL +///@brief Helper macro used to log data inside the MicroStrain SDK at trace level +///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_TRACE -#define MIP_LOG_TRACE(...) MIP_LOG_LOG(MIP_LOG_LEVEL_TRACE, __VA_ARGS__) +#define MICROSTRAIN_LOG_TRACE(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_TRACE, __VA_ARGS__) #else -#define MIP_LOG_TRACE(...) (void)0 +#define MICROSTRAIN_LOG_TRACE(...) (void)0 #endif ///@} diff --git a/src/c/microstrain/connections/serial/serial_port.c b/src/c/microstrain/connections/serial/serial_port.c index 21e8a637d..b255486a9 100644 --- a/src/c/microstrain/connections/serial/serial_port.c +++ b/src/c/microstrain/connections/serial/serial_port.c @@ -3,17 +3,17 @@ #include "serial_port.h" -#if defined WIN32 +#if defined MICROSTRAIN_PLATFORM_WINDOWS #include #include -#elif defined __APPLE__ +#elif defined MICROSTRAIN_PLATFORM_APPLE #include #endif #define COM_PORT_BUFFER_SIZE 0x200 -#ifndef WIN32 //Unix only +#if defined MICROSTRAIN_PLATFORM_APPLE || defined MICROSTRAIN_PLATFORM_LINUX #define INVALID_HANDLE_VALUE -1 @@ -33,7 +33,7 @@ speed_t baud_rate_to_speed(int baud_rate) return B115200; case 230400: return B230400; -#ifdef __linux__ //Linux onnly baudrates +#ifdef MICROSTRAIN_PLATFORM_LINUX //Linux onnly baudrates case 460800: return B460800; case 500000: @@ -75,7 +75,7 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) if(port_str == NULL) return false; - MIP_LOG_DEBUG("Opening serial port %s at %d\n", port_str, baudrate); + MICROSTRAIN_LOG_DEBUG("Opening serial port %s at %d\n", port_str, baudrate); #ifdef WIN32 BOOL ready; DCB dcb; @@ -118,14 +118,14 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) //Check for an invalid handle if(port->handle == INVALID_HANDLE_VALUE) { - MIP_LOG_ERROR("Unable to open com port (%d)\n", last_error); + MICROSTRAIN_LOG_ERROR("Unable to open com port (%d)\n", last_error); return false; } //Setup the com port buffer sizes if(SetupComm(port->handle, COM_PORT_BUFFER_SIZE, COM_PORT_BUFFER_SIZE) == 0) { - MIP_LOG_ERROR("Unable to setup com port buffer size (%d)\n", last_error); + MICROSTRAIN_LOG_ERROR("Unable to setup com port buffer size (%d)\n", last_error); CloseHandle(port->handle); port->handle = INVALID_HANDLE_VALUE; return false; @@ -151,7 +151,7 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) //Close the serial port, mutex, and exit if(!ready) { - MIP_LOG_ERROR("Unable to get com state\n"); + MICROSTRAIN_LOG_ERROR("Unable to get com state\n"); CloseHandle(port->handle); port->handle = INVALID_HANDLE_VALUE; return false; @@ -169,7 +169,7 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) //Close the serial port and exit if(!ready) { - MIP_LOG_ERROR("Unable to set com state\n"); + MICROSTRAIN_LOG_ERROR("Unable to set com state\n"); CloseHandle(port->handle); port->handle = INVALID_HANDLE_VALUE; return false; @@ -186,20 +186,20 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) if (port->handle < 0) { - MIP_LOG_ERROR("Unable to open port (%d): %s\n", errno, strerror(errno)); + MICROSTRAIN_LOG_ERROR("Unable to open port (%d): %s\n", errno, strerror(errno)); return false; } if( ioctl(port->handle, TIOCEXCL) < 0 ) { - MIP_LOG_WARN("Unable to set exclusive mode on serial port (%d): %s\n", errno, strerror(errno)); + MICROSTRAIN_LOG_WARN("Unable to set exclusive mode on serial port (%d): %s\n", errno, strerror(errno)); } // Set up baud rate and other serial device options struct termios serial_port_settings; if (tcgetattr(port->handle, &serial_port_settings) < 0) { - MIP_LOG_ERROR("Unable to get serial port settings (%d): %s\n", errno, strerror(errno)); + MICROSTRAIN_LOG_ERROR("Unable to get serial port settings (%d): %s\n", errno, strerror(errno)); close(port->handle); port->handle = -1; return false; @@ -208,7 +208,7 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) #ifndef __APPLE__ if (cfsetispeed(&serial_port_settings, baud_rate_to_speed(baudrate)) < 0 || cfsetospeed(&serial_port_settings, baud_rate_to_speed(baudrate)) < 0) { - MIP_LOG_ERROR("Unable to set baud rate (%d): %s\n", errno, strerror(errno)); + MICROSTRAIN_LOG_ERROR("Unable to set baud rate (%d): %s\n", errno, strerror(errno)); close(port->handle); port->handle = -1; return false; @@ -228,7 +228,7 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) // Persist the settings if(tcsetattr(port->handle, TCSANOW, &serial_port_settings) < 0) { - MIP_LOG_ERROR("Unable to save serial port settings (%d): %s\n", errno, strerror(errno)); + MICROSTRAIN_LOG_ERROR("Unable to save serial port settings (%d): %s\n", errno, strerror(errno)); close(port->handle); port->handle = -1; return false; @@ -239,7 +239,7 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) speed_t speed = baudrate; if (ioctl(port->handle, IOSSIOSPEED, &speed) < 0) { - MIP_LOG_ERROR("Unable to set baud rate (%d): %s\n", errno, strerror(errno)); + MICROSTRAIN_LOG_ERROR("Unable to set baud rate (%d): %s\n", errno, strerror(errno)); close(port->handle); port->handle = -1; return false; @@ -298,7 +298,7 @@ bool serial_port_write(serial_port *port, const void *buffer, size_t num_bytes, if(*bytes_written == num_bytes) return true; else if(*bytes_written == (size_t)-1) - MIP_LOG_ERROR("Failed to write serial data (%d): %s\n", errno, strerror(errno)); + MICROSTRAIN_LOG_ERROR("Failed to write serial data (%d): %s\n", errno, strerror(errno)); #endif @@ -314,14 +314,14 @@ bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, int wai if(!serial_port_is_open(port)) return false; -#ifdef WIN32 //Windows +#ifdef MICROSTRAIN_PLATFORM_WINDOWS uint32_t bytes_available = serial_port_read_count(port); DWORD last_error = GetLastError(); if (last_error != 0) { - MIP_LOG_ERROR("Failed to read serial port. Error: %lx\n", last_error); + MICROSTRAIN_LOG_ERROR("Failed to read serial port. Error: %lx\n", last_error); serial_port_close(port); return false; } @@ -351,18 +351,18 @@ bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, int wai // Keep reading and polling while there is still data available if (poll_status == -1) { - MIP_LOG_ERROR("Failed to poll serial port (%d): %s\n", errno, strerror(errno)); + MICROSTRAIN_LOG_ERROR("Failed to poll serial port (%d): %s\n", errno, strerror(errno)); return false; } else if (poll_fd.revents & POLLHUP) { - MIP_LOG_ERROR("Poll encountered HUP, closing device"); + MICROSTRAIN_LOG_ERROR("Poll encountered HUP, closing device"); serial_port_close(port); return false; } else if (poll_fd.revents & POLLERR || poll_fd.revents & POLLNVAL) { - MIP_LOG_ERROR("Poll encountered error\n"); + MICROSTRAIN_LOG_ERROR("Poll encountered error\n"); return false; } else if (poll_status > 0 && poll_fd.revents & POLLIN) @@ -371,7 +371,7 @@ bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, int wai if(local_bytes_read == (ssize_t)-1 && errno != EAGAIN) { - MIP_LOG_ERROR("Failed to read serial data (%d): %s\n", errno, strerror(errno)); + MICROSTRAIN_LOG_ERROR("Failed to read serial data (%d): %s\n", errno, strerror(errno)); return false; } if(local_bytes_read >= 0) @@ -387,7 +387,7 @@ bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, int wai uint32_t serial_port_read_count(serial_port *port) { -#ifdef WIN32 //Windows +#ifdef MICROSTRAIN_PLATFORM_WINDOWS //Windows // Clear the last error, if any SetLastError(0); #endif @@ -396,7 +396,7 @@ uint32_t serial_port_read_count(serial_port *port) if(!serial_port_is_open(port)) return 0; -#ifdef WIN32 //Windows +#ifdef MICROSTRAIN_PLATFORM_WINDOWS //Windows COMSTAT com_status; DWORD errors; @@ -418,7 +418,7 @@ uint32_t serial_port_read_count(serial_port *port) bool serial_port_is_open(const serial_port *port) { -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS return port->handle != INVALID_HANDLE_VALUE; #else return port->handle >= 0; diff --git a/src/c/microstrain/connections/serial/serial_port.h b/src/c/microstrain/connections/serial/serial_port.h index a56b0c259..7d526b54c 100644 --- a/src/c/microstrain/connections/serial/serial_port.h +++ b/src/c/microstrain/connections/serial/serial_port.h @@ -1,6 +1,8 @@ #pragma once -#ifdef WIN32 +#include + +#ifdef MICROSTRAIN_PLATFORM_WINDOWS #ifndef WIN32_LEAN_AND_MEAN #define WIN32_LEAN_AND_MEAN #endif @@ -39,7 +41,7 @@ extern "C" { typedef struct serial_port { -#ifdef WIN32 //Windows +#ifdef MICROSTRAIN_PLATFORM_WINDOWS HANDLE handle; #else //Linux int handle; diff --git a/src/c/microstrain/connections/tcp/tcp_socket.c b/src/c/microstrain/connections/tcp/tcp_socket.c index 8e85d2e37..d346ace98 100644 --- a/src/c/microstrain/connections/tcp/tcp_socket.c +++ b/src/c/microstrain/connections/tcp/tcp_socket.c @@ -3,7 +3,7 @@ #include "microstrain/common/logging.h" -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS #include #include @@ -68,7 +68,7 @@ static bool tcp_socket_open_common(tcp_socket* socket_ptr, const char* hostname, if( connect(socket_ptr->handle, addr->ai_addr, addr->ai_addrlen) == 0 ) break; -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS closesocket(socket_ptr->handle); #else close(socket_ptr->handle); @@ -81,7 +81,7 @@ static bool tcp_socket_open_common(tcp_socket* socket_ptr, const char* hostname, if( socket_ptr->handle == INVALID_SOCKET ) return false; -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS if( setsockopt(socket_ptr->handle, SOL_SOCKET, SO_RCVTIMEO, (char*)&timeout_ms, sizeof(timeout_ms)) != 0 ) return false; @@ -104,7 +104,7 @@ static bool tcp_socket_open_common(tcp_socket* socket_ptr, const char* hostname, bool tcp_socket_open(tcp_socket* socket_ptr, const char* hostname, uint16_t port, unsigned int timeout_ms) { -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS // Initialize winsock for each connection since there's no global init function. // This is safe to do multiple times, as long as it's shutdown the same number of times. @@ -112,7 +112,7 @@ bool tcp_socket_open(tcp_socket* socket_ptr, const char* hostname, uint16_t port int result = WSAStartup(MAKEWORD(2,2), &wsaData); if(result != 0) { - MIP_LOG_ERROR("WSAStartup() failed: %d\n", result); + MICROSTRAIN_LOG_ERROR("WSAStartup() failed: %d\n", result); return false; } @@ -126,7 +126,7 @@ bool tcp_socket_close(tcp_socket* socket_ptr) if( socket_ptr->handle == INVALID_SOCKET ) return false; -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS closesocket(socket_ptr->handle); WSACleanup(); // See tcp_socket_open #else @@ -156,7 +156,7 @@ bool tcp_socket_recv(tcp_socket* socket_ptr, void* buffer, size_t num_bytes, siz if( local_bytes_read < 0 ) { -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS return false; #else if(errno != EAGAIN && errno != EWOULDBLOCK) diff --git a/src/c/microstrain/connections/tcp/tcp_socket.h b/src/c/microstrain/connections/tcp/tcp_socket.h index 62827286c..314fd6058 100644 --- a/src/c/microstrain/connections/tcp/tcp_socket.h +++ b/src/c/microstrain/connections/tcp/tcp_socket.h @@ -1,6 +1,8 @@ #pragma once -#ifdef WIN32 +#include + +#ifdef MICROSTRAIN_PLATFORM_WINDOWS #ifndef WIN32_LEAN_AND_MEAN #define WIN32_LEAN_AND_MEAN From aef05aa95416237195f1e6ee1d943d6abd4c9406 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Wed, 21 Aug 2024 14:38:30 -0400 Subject: [PATCH 074/147] Updated/added helper header for including all files (per module) --- .../connections/microstrain_connections_all.h | 5 ++++ src/c/microstrain/microstrain_all.h | 8 ++++++ src/c/mip/mip_all.h | 25 +++++++++++-------- .../microstrain_connections_all.hpp | 7 ++++++ src/cpp/microstrain/microstrain_all.hpp | 10 ++++++++ src/cpp/mip/extras/mip_extras_all.hpp | 6 +++++ src/cpp/mip/mip_all.hpp | 20 +++++++-------- 7 files changed, 61 insertions(+), 20 deletions(-) create mode 100644 src/c/microstrain/connections/microstrain_connections_all.h create mode 100644 src/c/microstrain/microstrain_all.h create mode 100644 src/cpp/microstrain/connections/microstrain_connections_all.hpp create mode 100644 src/cpp/microstrain/microstrain_all.hpp create mode 100644 src/cpp/mip/extras/mip_extras_all.hpp diff --git a/src/c/microstrain/connections/microstrain_connections_all.h b/src/c/microstrain/connections/microstrain_connections_all.h new file mode 100644 index 000000000..72c3046b8 --- /dev/null +++ b/src/c/microstrain/connections/microstrain_connections_all.h @@ -0,0 +1,5 @@ +#pragma once + +// MicroStrain Connections +#include "serial/serial_port.h" +#include "tcp/tcp_socket.h" diff --git a/src/c/microstrain/microstrain_all.h b/src/c/microstrain/microstrain_all.h new file mode 100644 index 000000000..0afb5561e --- /dev/null +++ b/src/c/microstrain/microstrain_all.h @@ -0,0 +1,8 @@ +#pragma once + +// MicroStrain Common +#include "common/device_models.h" +#include "common/embedded_time.h" +#include "common/logging.h" +#include "common/platform.h" +#include "common/serialization.h" diff --git a/src/c/mip/mip_all.h b/src/c/mip/mip_all.h index 6f7e81262..2500b2561 100644 --- a/src/c/mip/mip_all.h +++ b/src/c/mip/mip_all.h @@ -1,29 +1,34 @@ #pragma once -//MIP Core +// MIP Core #include "mip_cmdqueue.h" +#include "mip_descriptors.h" #include "mip_dispatch.h" #include "mip_field.h" #include "mip_interface.h" #include "mip_offsets.h" #include "mip_packet.h" #include "mip_parser.h" -#include "mip_descriptors.h" +#include "mip_result.h" +#include "mip_serialization.h" +#include "mip_types.h" +#include "mip_version.h" -//MIP Utils -#include "microstrain/common/serialization.h" +// MIP Utils +#include "utils/byte_ring.h" -//MIP Commands -#include "definitions/commands_base.h" +// MIP Commands #include "definitions/commands_3dm.h" +#include "definitions/commands_aiding.h" +#include "definitions/commands_base.h" #include "definitions/commands_filter.h" #include "definitions/commands_gnss.h" #include "definitions/commands_rtk.h" #include "definitions/commands_system.h" -//MIP Data +// MIP Data +#include "definitions/data_filter.h" +#include "definitions/data_gnss.h" +#include "definitions/data_sensor.h" #include "definitions/data_shared.h" #include "definitions/data_system.h" -#include "definitions/data_sensor.h" -#include "definitions/data_gnss.h" -#include "definitions/data_filter.h" diff --git a/src/cpp/microstrain/connections/microstrain_connections_all.hpp b/src/cpp/microstrain/connections/microstrain_connections_all.hpp new file mode 100644 index 000000000..c1854be61 --- /dev/null +++ b/src/cpp/microstrain/connections/microstrain_connections_all.hpp @@ -0,0 +1,7 @@ +#pragma once + +// MicroStrain Connections +#include "microstrain/connections/connection.hpp" +#include "microstrain/connections/recording/recording_connection.hpp" +#include "microstrain/connections/serial/serial_connection.hpp" +#include "microstrain/connections/tcp/tcp_connection.hpp" diff --git a/src/cpp/microstrain/microstrain_all.hpp b/src/cpp/microstrain/microstrain_all.hpp new file mode 100644 index 000000000..1463696ac --- /dev/null +++ b/src/cpp/microstrain/microstrain_all.hpp @@ -0,0 +1,10 @@ +#pragma once + +// MicroStrain Common +#include "common/embedded_time.hpp" +#include "common/index.hpp" +#include "common/logging.hpp" +#include "common/platform.hpp" +#include "common/serialization.hpp" +#include "common/serialization/readwrite.hpp" +#include "common/serialization/serializer.hpp" diff --git a/src/cpp/mip/extras/mip_extras_all.hpp b/src/cpp/mip/extras/mip_extras_all.hpp new file mode 100644 index 000000000..c5659aaaf --- /dev/null +++ b/src/cpp/mip/extras/mip_extras_all.hpp @@ -0,0 +1,6 @@ +#pragma once + +// MIP Extras Core +#include "composite_result.hpp" +#include "descriptor_id.hpp" +#include "version.hpp" diff --git a/src/cpp/mip/mip_all.hpp b/src/cpp/mip/mip_all.hpp index 54c63d45e..bd41594ed 100644 --- a/src/cpp/mip/mip_all.hpp +++ b/src/cpp/mip/mip_all.hpp @@ -1,27 +1,27 @@ #pragma once -//MIP Core +// MIP Core #include "mip_cmdqueue.hpp" +#include "mip_descriptors.hpp" #include "mip_field.hpp" #include "mip_interface.hpp" #include "mip_packet.hpp" #include "mip_parser.hpp" +#include "mip_result.hpp" +#include "mip/mip_version.h" -#include "mip_descriptors.hpp" - -//MIP Commands +// MIP Commands +#include "definitions/commands_3dm.hpp" #include "definitions/commands_aiding.hpp" #include "definitions/commands_base.hpp" -#include "definitions/commands_3dm.hpp" #include "definitions/commands_filter.hpp" #include "definitions/commands_gnss.hpp" #include "definitions/commands_rtk.hpp" #include "definitions/commands_system.hpp" -#include "definitions/commands_aiding.hpp" -//MIP Data +// MIP Data +#include "definitions/data_filter.hpp" +#include "definitions/data_gnss.hpp" +#include "definitions/data_sensor.hpp" #include "definitions/data_shared.hpp" #include "definitions/data_system.hpp" -#include "definitions/data_sensor.hpp" -#include "definitions/data_gnss.hpp" -#include "definitions/data_filter.hpp" From e87d70433c667cccc9fabf8d97d426fa9bc572a7 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 17:24:28 -0400 Subject: [PATCH 075/147] Fix C header including .hpp header. --- src/c/microstrain/connections/serial/serial_port.h | 2 +- src/c/microstrain/connections/tcp/tcp_socket.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/c/microstrain/connections/serial/serial_port.h b/src/c/microstrain/connections/serial/serial_port.h index 7d526b54c..b4d5d3332 100644 --- a/src/c/microstrain/connections/serial/serial_port.h +++ b/src/c/microstrain/connections/serial/serial_port.h @@ -1,6 +1,6 @@ #pragma once -#include +#include #ifdef MICROSTRAIN_PLATFORM_WINDOWS #ifndef WIN32_LEAN_AND_MEAN diff --git a/src/c/microstrain/connections/tcp/tcp_socket.h b/src/c/microstrain/connections/tcp/tcp_socket.h index 314fd6058..5d3adf33c 100644 --- a/src/c/microstrain/connections/tcp/tcp_socket.h +++ b/src/c/microstrain/connections/tcp/tcp_socket.h @@ -1,6 +1,6 @@ #pragma once -#include +#include #ifdef MICROSTRAIN_PLATFORM_WINDOWS From ad1c81be35a0e74830bf1c7990d7851f8405f784 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 17:24:40 -0400 Subject: [PATCH 076/147] Fix mip::extract/insert. --- src/cpp/mip/mip_serialization.hpp | 24 ++++++++++++++++++++---- 1 file changed, 20 insertions(+), 4 deletions(-) diff --git a/src/cpp/mip/mip_serialization.hpp b/src/cpp/mip/mip_serialization.hpp index 0909fa32e..5a3a78be0 100644 --- a/src/cpp/mip/mip_serialization.hpp +++ b/src/cpp/mip/mip_serialization.hpp @@ -17,10 +17,26 @@ namespace serialization using namespace microstrain::serialization::big_endian; } -} // namespace mip +using microstrain::insert; +using microstrain::extract; + +// Explicitly overload insert/extract versions that take raw buffers +// since the endianness can't be deduced from the arguments. +template +inline bool extract(T& object, const uint8_t* buffer, size_t bufferLength, size_t offset=0, bool exactSize=false) +{ + using namespace microstrain::serialization; + return extract(object, buffer, bufferLength, offset, exactSize); +} -// These functions must be in the microstrain namespace in order to be seen as overloads. -namespace microstrain +template +inline bool insert(const T& object, uint8_t* buffer, size_t bufferLength, size_t offset=0) { -} // namespace microstrain + using namespace microstrain::serialization; + return insert(object, buffer, bufferLength, offset); +} + + +} // namespace mip + From 1e42ebead6d6bdc289e94bc857d87d478b88ba48 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 22 Aug 2024 11:12:29 -0400 Subject: [PATCH 077/147] Fix definitions to include bitfield access functions. --- src/cpp/mip/definitions/commands_3dm.hpp | 20 ++ src/cpp/mip/definitions/commands_aiding.hpp | 36 +++ src/cpp/mip/definitions/commands_base.hpp | 54 ++++ src/cpp/mip/definitions/commands_filter.hpp | 28 ++ src/cpp/mip/definitions/commands_rtk.hpp | 52 +++ src/cpp/mip/definitions/data_filter.hpp | 106 ++++++ src/cpp/mip/definitions/data_gnss.hpp | 336 ++++++++++++++++++++ src/cpp/mip/definitions/data_sensor.hpp | 30 ++ src/cpp/mip/definitions/data_shared.hpp | 10 + 9 files changed, 672 insertions(+) diff --git a/src/cpp/mip/definitions/commands_3dm.hpp b/src/cpp/mip/definitions/commands_3dm.hpp index 4120f5ea7..0243505f5 100644 --- a/src/cpp/mip/definitions/commands_3dm.hpp +++ b/src/cpp/mip/definitions/commands_3dm.hpp @@ -1445,6 +1445,8 @@ struct ConstellationSettings OptionFlags& operator|=(uint16_t val) { return *this = value | val; } OptionFlags& operator&=(uint16_t val) { return *this = value & val; } + bool l1saif() const { return (value & L1SAIF) > 0; } + void l1saif(bool val) { value &= ~L1SAIF; if(val) value |= L1SAIF; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1569,6 +1571,12 @@ struct GnssSbasSettings SBASOptions& operator|=(uint16_t val) { return *this = value | val; } SBASOptions& operator&=(uint16_t val) { return *this = value & val; } + bool enableRanging() const { return (value & ENABLE_RANGING) > 0; } + void enableRanging(bool val) { value &= ~ENABLE_RANGING; if(val) value |= ENABLE_RANGING; } + bool enableCorrections() const { return (value & ENABLE_CORRECTIONS) > 0; } + void enableCorrections(bool val) { value &= ~ENABLE_CORRECTIONS; if(val) value |= ENABLE_CORRECTIONS; } + bool applyIntegrity() const { return (value & APPLY_INTEGRITY) > 0; } + void applyIntegrity(bool val) { value &= ~APPLY_INTEGRITY; if(val) value |= APPLY_INTEGRITY; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2089,6 +2097,12 @@ struct GpioConfig PinMode& operator|=(uint8_t val) { return *this = value | val; } PinMode& operator&=(uint8_t val) { return *this = value & val; } + bool openDrain() const { return (value & OPEN_DRAIN) > 0; } + void openDrain(bool val) { value &= ~OPEN_DRAIN; if(val) value |= OPEN_DRAIN; } + bool pulldown() const { return (value & PULLDOWN) > 0; } + void pulldown(bool val) { value &= ~PULLDOWN; if(val) value |= PULLDOWN; } + bool pullup() const { return (value & PULLUP) > 0; } + void pullup(bool val) { value &= ~PULLUP; if(val) value |= PULLUP; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2578,6 +2592,12 @@ struct GetEventTriggerStatus Status& operator|=(uint8_t val) { return *this = value | val; } Status& operator&=(uint8_t val) { return *this = value & val; } + bool active() const { return (value & ACTIVE) > 0; } + void active(bool val) { value &= ~ACTIVE; if(val) value |= ACTIVE; } + bool enabled() const { return (value & ENABLED) > 0; } + void enabled(bool val) { value &= ~ENABLED; if(val) value |= ENABLED; } + bool test() const { return (value & TEST) > 0; } + void test(bool val) { value &= ~TEST; if(val) value |= TEST; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_aiding.hpp b/src/cpp/mip/definitions/commands_aiding.hpp index 79fa1212f..d09ed6a77 100644 --- a/src/cpp/mip/definitions/commands_aiding.hpp +++ b/src/cpp/mip/definitions/commands_aiding.hpp @@ -318,6 +318,12 @@ struct EcefPos ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { value &= ~X; if(val) value |= X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { value &= ~Y; if(val) value |= Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { value &= ~Z; if(val) value |= Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -386,6 +392,12 @@ struct LlhPos ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool latitude() const { return (value & LATITUDE) > 0; } + void latitude(bool val) { value &= ~LATITUDE; if(val) value |= LATITUDE; } + bool longitude() const { return (value & LONGITUDE) > 0; } + void longitude(bool val) { value &= ~LONGITUDE; if(val) value |= LONGITUDE; } + bool height() const { return (value & HEIGHT) > 0; } + void height(bool val) { value &= ~HEIGHT; if(val) value |= HEIGHT; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -498,6 +510,12 @@ struct EcefVel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { value &= ~X; if(val) value |= X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { value &= ~Y; if(val) value |= Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { value &= ~Z; if(val) value |= Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -565,6 +583,12 @@ struct NedVel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { value &= ~X; if(val) value |= X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { value &= ~Y; if(val) value |= Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { value &= ~Z; if(val) value |= Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -633,6 +657,12 @@ struct VehicleFixedFrameVelocity ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { value &= ~X; if(val) value |= X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { value &= ~Y; if(val) value |= Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { value &= ~Z; if(val) value |= Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -742,6 +772,12 @@ struct MagneticField ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool x() const { return (value & X) > 0; } + void x(bool val) { value &= ~X; if(val) value |= X; } + bool y() const { return (value & Y) > 0; } + void y(bool val) { value &= ~Y; if(val) value |= Y; } + bool z() const { return (value & Z) > 0; } + void z(bool val) { value &= ~Z; if(val) value |= Z; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index b9d01e942..81ab1e895 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -121,6 +121,60 @@ struct CommandedTestBitsGq7 : Bitfield CommandedTestBitsGq7& operator|=(uint32_t val) { return *this = value | val; } CommandedTestBitsGq7& operator&=(uint32_t val) { return *this = value & val; } + bool generalHardwareFault() const { return (value & GENERAL_HARDWARE_FAULT) > 0; } + void generalHardwareFault(bool val) { value &= ~GENERAL_HARDWARE_FAULT; if(val) value |= GENERAL_HARDWARE_FAULT; } + bool generalFirmwareFault() const { return (value & GENERAL_FIRMWARE_FAULT) > 0; } + void generalFirmwareFault(bool val) { value &= ~GENERAL_FIRMWARE_FAULT; if(val) value |= GENERAL_FIRMWARE_FAULT; } + bool timingOverload() const { return (value & TIMING_OVERLOAD) > 0; } + void timingOverload(bool val) { value &= ~TIMING_OVERLOAD; if(val) value |= TIMING_OVERLOAD; } + bool bufferOverrun() const { return (value & BUFFER_OVERRUN) > 0; } + void bufferOverrun(bool val) { value &= ~BUFFER_OVERRUN; if(val) value |= BUFFER_OVERRUN; } + uint32_t reserved() const { return (value & RESERVED) >> 4; } + void reserved(uint32_t val) { value = (value & ~RESERVED) | (val << 4); } + bool ipcImuFault() const { return (value & IPC_IMU_FAULT) > 0; } + void ipcImuFault(bool val) { value &= ~IPC_IMU_FAULT; if(val) value |= IPC_IMU_FAULT; } + bool ipcNavFault() const { return (value & IPC_NAV_FAULT) > 0; } + void ipcNavFault(bool val) { value &= ~IPC_NAV_FAULT; if(val) value |= IPC_NAV_FAULT; } + bool ipcGnssFault() const { return (value & IPC_GNSS_FAULT) > 0; } + void ipcGnssFault(bool val) { value &= ~IPC_GNSS_FAULT; if(val) value |= IPC_GNSS_FAULT; } + bool commsFault() const { return (value & COMMS_FAULT) > 0; } + void commsFault(bool val) { value &= ~COMMS_FAULT; if(val) value |= COMMS_FAULT; } + bool imuAccelFault() const { return (value & IMU_ACCEL_FAULT) > 0; } + void imuAccelFault(bool val) { value &= ~IMU_ACCEL_FAULT; if(val) value |= IMU_ACCEL_FAULT; } + bool imuGyroFault() const { return (value & IMU_GYRO_FAULT) > 0; } + void imuGyroFault(bool val) { value &= ~IMU_GYRO_FAULT; if(val) value |= IMU_GYRO_FAULT; } + bool imuMagFault() const { return (value & IMU_MAG_FAULT) > 0; } + void imuMagFault(bool val) { value &= ~IMU_MAG_FAULT; if(val) value |= IMU_MAG_FAULT; } + bool imuPressFault() const { return (value & IMU_PRESS_FAULT) > 0; } + void imuPressFault(bool val) { value &= ~IMU_PRESS_FAULT; if(val) value |= IMU_PRESS_FAULT; } + uint32_t imuReserved() const { return (value & IMU_RESERVED) >> 16; } + void imuReserved(uint32_t val) { value = (value & ~IMU_RESERVED) | (val << 16); } + bool imuCalError() const { return (value & IMU_CAL_ERROR) > 0; } + void imuCalError(bool val) { value &= ~IMU_CAL_ERROR; if(val) value |= IMU_CAL_ERROR; } + bool imuGeneralFault() const { return (value & IMU_GENERAL_FAULT) > 0; } + void imuGeneralFault(bool val) { value &= ~IMU_GENERAL_FAULT; if(val) value |= IMU_GENERAL_FAULT; } + uint32_t filtReserved() const { return (value & FILT_RESERVED) >> 20; } + void filtReserved(uint32_t val) { value = (value & ~FILT_RESERVED) | (val << 20); } + bool filtSolutionFault() const { return (value & FILT_SOLUTION_FAULT) > 0; } + void filtSolutionFault(bool val) { value &= ~FILT_SOLUTION_FAULT; if(val) value |= FILT_SOLUTION_FAULT; } + bool filtGeneralFault() const { return (value & FILT_GENERAL_FAULT) > 0; } + void filtGeneralFault(bool val) { value &= ~FILT_GENERAL_FAULT; if(val) value |= FILT_GENERAL_FAULT; } + bool gnssReceiver1Fault() const { return (value & GNSS_RECEIVER1_FAULT) > 0; } + void gnssReceiver1Fault(bool val) { value &= ~GNSS_RECEIVER1_FAULT; if(val) value |= GNSS_RECEIVER1_FAULT; } + bool gnssAntenna1Fault() const { return (value & GNSS_ANTENNA1_FAULT) > 0; } + void gnssAntenna1Fault(bool val) { value &= ~GNSS_ANTENNA1_FAULT; if(val) value |= GNSS_ANTENNA1_FAULT; } + bool gnssReceiver2Fault() const { return (value & GNSS_RECEIVER2_FAULT) > 0; } + void gnssReceiver2Fault(bool val) { value &= ~GNSS_RECEIVER2_FAULT; if(val) value |= GNSS_RECEIVER2_FAULT; } + bool gnssAntenna2Fault() const { return (value & GNSS_ANTENNA2_FAULT) > 0; } + void gnssAntenna2Fault(bool val) { value &= ~GNSS_ANTENNA2_FAULT; if(val) value |= GNSS_ANTENNA2_FAULT; } + bool gnssRtcmFailure() const { return (value & GNSS_RTCM_FAILURE) > 0; } + void gnssRtcmFailure(bool val) { value &= ~GNSS_RTCM_FAILURE; if(val) value |= GNSS_RTCM_FAILURE; } + bool gnssRtkFault() const { return (value & GNSS_RTK_FAULT) > 0; } + void gnssRtkFault(bool val) { value &= ~GNSS_RTK_FAULT; if(val) value |= GNSS_RTK_FAULT; } + bool gnssSolutionFault() const { return (value & GNSS_SOLUTION_FAULT) > 0; } + void gnssSolutionFault(bool val) { value &= ~GNSS_SOLUTION_FAULT; if(val) value |= GNSS_SOLUTION_FAULT; } + bool gnssGeneralFault() const { return (value & GNSS_GENERAL_FAULT) > 0; } + void gnssGeneralFault(bool val) { value &= ~GNSS_GENERAL_FAULT; if(val) value |= GNSS_GENERAL_FAULT; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_filter.hpp b/src/cpp/mip/definitions/commands_filter.hpp index 1a012f515..7eb355be8 100644 --- a/src/cpp/mip/definitions/commands_filter.hpp +++ b/src/cpp/mip/definitions/commands_filter.hpp @@ -312,6 +312,20 @@ struct EstimationControl EnableFlags& operator|=(uint16_t val) { return *this = value | val; } EnableFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gyroBias() const { return (value & GYRO_BIAS) > 0; } + void gyroBias(bool val) { value &= ~GYRO_BIAS; if(val) value |= GYRO_BIAS; } + bool accelBias() const { return (value & ACCEL_BIAS) > 0; } + void accelBias(bool val) { value &= ~ACCEL_BIAS; if(val) value |= ACCEL_BIAS; } + bool gyroScaleFactor() const { return (value & GYRO_SCALE_FACTOR) > 0; } + void gyroScaleFactor(bool val) { value &= ~GYRO_SCALE_FACTOR; if(val) value |= GYRO_SCALE_FACTOR; } + bool accelScaleFactor() const { return (value & ACCEL_SCALE_FACTOR) > 0; } + void accelScaleFactor(bool val) { value &= ~ACCEL_SCALE_FACTOR; if(val) value |= ACCEL_SCALE_FACTOR; } + bool antennaOffset() const { return (value & ANTENNA_OFFSET) > 0; } + void antennaOffset(bool val) { value &= ~ANTENNA_OFFSET; if(val) value |= ANTENNA_OFFSET; } + bool autoMagHardIron() const { return (value & AUTO_MAG_HARD_IRON) > 0; } + void autoMagHardIron(bool val) { value &= ~AUTO_MAG_HARD_IRON; if(val) value |= AUTO_MAG_HARD_IRON; } + bool autoMagSoftIron() const { return (value & AUTO_MAG_SOFT_IRON) > 0; } + void autoMagSoftIron(bool val) { value &= ~AUTO_MAG_SOFT_IRON; if(val) value |= AUTO_MAG_SOFT_IRON; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -580,6 +594,12 @@ struct TareOrientation MipTareAxes& operator|=(uint8_t val) { return *this = value | val; } MipTareAxes& operator&=(uint8_t val) { return *this = value & val; } + bool roll() const { return (value & ROLL) > 0; } + void roll(bool val) { value &= ~ROLL; if(val) value |= ROLL; } + bool pitch() const { return (value & PITCH) > 0; } + void pitch(bool val) { value &= ~PITCH; if(val) value |= PITCH; } + bool yaw() const { return (value & YAW) > 0; } + void yaw(bool val) { value &= ~YAW; if(val) value |= YAW; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -3598,6 +3618,14 @@ struct InitializationConfiguration AlignmentSelector& operator|=(uint8_t val) { return *this = value | val; } AlignmentSelector& operator&=(uint8_t val) { return *this = value & val; } + bool dualAntenna() const { return (value & DUAL_ANTENNA) > 0; } + void dualAntenna(bool val) { value &= ~DUAL_ANTENNA; if(val) value |= DUAL_ANTENNA; } + bool kinematic() const { return (value & KINEMATIC) > 0; } + void kinematic(bool val) { value &= ~KINEMATIC; if(val) value |= KINEMATIC; } + bool magnetometer() const { return (value & MAGNETOMETER) > 0; } + void magnetometer(bool val) { value &= ~MAGNETOMETER; if(val) value |= MAGNETOMETER; } + bool external() const { return (value & EXTERNAL) > 0; } + void external(bool val) { value &= ~EXTERNAL; if(val) value |= EXTERNAL; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/commands_rtk.hpp b/src/cpp/mip/definitions/commands_rtk.hpp index 9bfcc4a0a..9b2dc749d 100644 --- a/src/cpp/mip/definitions/commands_rtk.hpp +++ b/src/cpp/mip/definitions/commands_rtk.hpp @@ -112,6 +112,28 @@ struct GetStatusFlags StatusFlagsLegacy& operator|=(uint32_t val) { return *this = value | val; } StatusFlagsLegacy& operator&=(uint32_t val) { return *this = value & val; } + uint32_t controllerstate() const { return (value & CONTROLLERSTATE) >> 0; } + void controllerstate(uint32_t val) { value = (value & ~CONTROLLERSTATE) | (val << 0); } + uint32_t platformstate() const { return (value & PLATFORMSTATE) >> 3; } + void platformstate(uint32_t val) { value = (value & ~PLATFORMSTATE) | (val << 3); } + uint32_t controllerstatuscode() const { return (value & CONTROLLERSTATUSCODE) >> 8; } + void controllerstatuscode(uint32_t val) { value = (value & ~CONTROLLERSTATUSCODE) | (val << 8); } + uint32_t platformstatuscode() const { return (value & PLATFORMSTATUSCODE) >> 11; } + void platformstatuscode(uint32_t val) { value = (value & ~PLATFORMSTATUSCODE) | (val << 11); } + uint32_t resetcode() const { return (value & RESETCODE) >> 14; } + void resetcode(uint32_t val) { value = (value & ~RESETCODE) | (val << 14); } + uint32_t signalquality() const { return (value & SIGNALQUALITY) >> 16; } + void signalquality(uint32_t val) { value = (value & ~SIGNALQUALITY) | (val << 16); } + uint32_t reserved() const { return (value & RESERVED) >> 20; } + void reserved(uint32_t val) { value = (value & ~RESERVED) | (val << 20); } + uint32_t rssi() const { return (value & RSSI) >> 20; } + void rssi(uint32_t val) { value = (value & ~RSSI) | (val << 20); } + uint32_t rsrp() const { return (value & RSRP) >> 26; } + void rsrp(uint32_t val) { value = (value & ~RSRP) | (val << 26); } + uint32_t rsrq() const { return (value & RSRQ) >> 28; } + void rsrq(uint32_t val) { value = (value & ~RSRQ) | (val << 28); } + uint32_t sinr() const { return (value & SINR) >> 30; } + void sinr(uint32_t val) { value = (value & ~SINR) | (val << 30); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -145,6 +167,30 @@ struct GetStatusFlags StatusFlags& operator|=(uint32_t val) { return *this = value | val; } StatusFlags& operator&=(uint32_t val) { return *this = value & val; } + uint32_t modemState() const { return (value & MODEM_STATE) >> 0; } + void modemState(uint32_t val) { value = (value & ~MODEM_STATE) | (val << 0); } + uint32_t connectionType() const { return (value & CONNECTION_TYPE) >> 4; } + void connectionType(uint32_t val) { value = (value & ~CONNECTION_TYPE) | (val << 4); } + uint32_t rssi() const { return (value & RSSI) >> 8; } + void rssi(uint32_t val) { value = (value & ~RSSI) | (val << 8); } + uint32_t signalQuality() const { return (value & SIGNAL_QUALITY) >> 16; } + void signalQuality(uint32_t val) { value = (value & ~SIGNAL_QUALITY) | (val << 16); } + uint32_t towerChangeIndicator() const { return (value & TOWER_CHANGE_INDICATOR) >> 20; } + void towerChangeIndicator(uint32_t val) { value = (value & ~TOWER_CHANGE_INDICATOR) | (val << 20); } + bool nmeaTimeout() const { return (value & NMEA_TIMEOUT) > 0; } + void nmeaTimeout(bool val) { value &= ~NMEA_TIMEOUT; if(val) value |= NMEA_TIMEOUT; } + bool serverTimeout() const { return (value & SERVER_TIMEOUT) > 0; } + void serverTimeout(bool val) { value &= ~SERVER_TIMEOUT; if(val) value |= SERVER_TIMEOUT; } + bool correctionsTimeout() const { return (value & CORRECTIONS_TIMEOUT) > 0; } + void correctionsTimeout(bool val) { value &= ~CORRECTIONS_TIMEOUT; if(val) value |= CORRECTIONS_TIMEOUT; } + bool deviceOutOfRange() const { return (value & DEVICE_OUT_OF_RANGE) > 0; } + void deviceOutOfRange(bool val) { value &= ~DEVICE_OUT_OF_RANGE; if(val) value |= DEVICE_OUT_OF_RANGE; } + bool correctionsUnavailable() const { return (value & CORRECTIONS_UNAVAILABLE) > 0; } + void correctionsUnavailable(bool val) { value &= ~CORRECTIONS_UNAVAILABLE; if(val) value |= CORRECTIONS_UNAVAILABLE; } + bool reserved() const { return (value & RESERVED) > 0; } + void reserved(bool val) { value &= ~RESERVED; if(val) value |= RESERVED; } + uint32_t version() const { return (value & VERSION) >> 30; } + void version(uint32_t val) { value = (value & ~VERSION) | (val << 30); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -690,6 +736,12 @@ struct ServiceStatus ServiceFlags& operator|=(uint8_t val) { return *this = value | val; } ServiceFlags& operator&=(uint8_t val) { return *this = value & val; } + bool throttle() const { return (value & THROTTLE) > 0; } + void throttle(bool val) { value &= ~THROTTLE; if(val) value |= THROTTLE; } + bool correctionsUnavailable() const { return (value & CORRECTIONS_UNAVAILABLE) > 0; } + void correctionsUnavailable(bool val) { value &= ~CORRECTIONS_UNAVAILABLE; if(val) value |= CORRECTIONS_UNAVAILABLE; } + uint8_t reserved() const { return (value & RESERVED) >> 2; } + void reserved(uint8_t val) { value = (value & ~RESERVED) | (val << 2); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_filter.hpp b/src/cpp/mip/definitions/data_filter.hpp index aae8ab68a..2edfc45f1 100644 --- a/src/cpp/mip/definitions/data_filter.hpp +++ b/src/cpp/mip/definitions/data_filter.hpp @@ -165,6 +165,62 @@ struct FilterStatusFlags : Bitfield FilterStatusFlags& operator|=(uint16_t val) { return *this = value | val; } FilterStatusFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gx5InitNoAttitude() const { return (value & GX5_INIT_NO_ATTITUDE) > 0; } + void gx5InitNoAttitude(bool val) { value &= ~GX5_INIT_NO_ATTITUDE; if(val) value |= GX5_INIT_NO_ATTITUDE; } + bool gx5InitNoPositionVelocity() const { return (value & GX5_INIT_NO_POSITION_VELOCITY) > 0; } + void gx5InitNoPositionVelocity(bool val) { value &= ~GX5_INIT_NO_POSITION_VELOCITY; if(val) value |= GX5_INIT_NO_POSITION_VELOCITY; } + bool gx5RunImuUnavailable() const { return (value & GX5_RUN_IMU_UNAVAILABLE) > 0; } + void gx5RunImuUnavailable(bool val) { value &= ~GX5_RUN_IMU_UNAVAILABLE; if(val) value |= GX5_RUN_IMU_UNAVAILABLE; } + bool gx5RunGpsUnavailable() const { return (value & GX5_RUN_GPS_UNAVAILABLE) > 0; } + void gx5RunGpsUnavailable(bool val) { value &= ~GX5_RUN_GPS_UNAVAILABLE; if(val) value |= GX5_RUN_GPS_UNAVAILABLE; } + bool gx5RunMatrixSingularity() const { return (value & GX5_RUN_MATRIX_SINGULARITY) > 0; } + void gx5RunMatrixSingularity(bool val) { value &= ~GX5_RUN_MATRIX_SINGULARITY; if(val) value |= GX5_RUN_MATRIX_SINGULARITY; } + bool gx5RunPositionCovarianceWarning() const { return (value & GX5_RUN_POSITION_COVARIANCE_WARNING) > 0; } + void gx5RunPositionCovarianceWarning(bool val) { value &= ~GX5_RUN_POSITION_COVARIANCE_WARNING; if(val) value |= GX5_RUN_POSITION_COVARIANCE_WARNING; } + bool gx5RunVelocityCovarianceWarning() const { return (value & GX5_RUN_VELOCITY_COVARIANCE_WARNING) > 0; } + void gx5RunVelocityCovarianceWarning(bool val) { value &= ~GX5_RUN_VELOCITY_COVARIANCE_WARNING; if(val) value |= GX5_RUN_VELOCITY_COVARIANCE_WARNING; } + bool gx5RunAttitudeCovarianceWarning() const { return (value & GX5_RUN_ATTITUDE_COVARIANCE_WARNING) > 0; } + void gx5RunAttitudeCovarianceWarning(bool val) { value &= ~GX5_RUN_ATTITUDE_COVARIANCE_WARNING; if(val) value |= GX5_RUN_ATTITUDE_COVARIANCE_WARNING; } + bool gx5RunNanInSolutionWarning() const { return (value & GX5_RUN_NAN_IN_SOLUTION_WARNING) > 0; } + void gx5RunNanInSolutionWarning(bool val) { value &= ~GX5_RUN_NAN_IN_SOLUTION_WARNING; if(val) value |= GX5_RUN_NAN_IN_SOLUTION_WARNING; } + bool gx5RunGyroBiasEstHighWarning() const { return (value & GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING) > 0; } + void gx5RunGyroBiasEstHighWarning(bool val) { value &= ~GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING; if(val) value |= GX5_RUN_GYRO_BIAS_EST_HIGH_WARNING; } + bool gx5RunAccelBiasEstHighWarning() const { return (value & GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING) > 0; } + void gx5RunAccelBiasEstHighWarning(bool val) { value &= ~GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING; if(val) value |= GX5_RUN_ACCEL_BIAS_EST_HIGH_WARNING; } + bool gx5RunGyroScaleFactorEstHighWarning() const { return (value & GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING) > 0; } + void gx5RunGyroScaleFactorEstHighWarning(bool val) { value &= ~GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING; if(val) value |= GX5_RUN_GYRO_SCALE_FACTOR_EST_HIGH_WARNING; } + bool gx5RunAccelScaleFactorEstHighWarning() const { return (value & GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING) > 0; } + void gx5RunAccelScaleFactorEstHighWarning(bool val) { value &= ~GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING; if(val) value |= GX5_RUN_ACCEL_SCALE_FACTOR_EST_HIGH_WARNING; } + bool gx5RunMagBiasEstHighWarning() const { return (value & GX5_RUN_MAG_BIAS_EST_HIGH_WARNING) > 0; } + void gx5RunMagBiasEstHighWarning(bool val) { value &= ~GX5_RUN_MAG_BIAS_EST_HIGH_WARNING; if(val) value |= GX5_RUN_MAG_BIAS_EST_HIGH_WARNING; } + bool gx5RunAntOffsetCorrectionEstHighWarning() const { return (value & GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING) > 0; } + void gx5RunAntOffsetCorrectionEstHighWarning(bool val) { value &= ~GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING; if(val) value |= GX5_RUN_ANT_OFFSET_CORRECTION_EST_HIGH_WARNING; } + bool gx5RunMagHardIronEstHighWarning() const { return (value & GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING) > 0; } + void gx5RunMagHardIronEstHighWarning(bool val) { value &= ~GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING; if(val) value |= GX5_RUN_MAG_HARD_IRON_EST_HIGH_WARNING; } + bool gx5RunMagSoftIronEstHighWarning() const { return (value & GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING) > 0; } + void gx5RunMagSoftIronEstHighWarning(bool val) { value &= ~GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING; if(val) value |= GX5_RUN_MAG_SOFT_IRON_EST_HIGH_WARNING; } + uint16_t gq7FilterCondition() const { return (value & GQ7_FILTER_CONDITION) >> 0; } + void gq7FilterCondition(uint16_t val) { value = (value & ~GQ7_FILTER_CONDITION) | (val << 0); } + bool gq7RollPitchWarning() const { return (value & GQ7_ROLL_PITCH_WARNING) > 0; } + void gq7RollPitchWarning(bool val) { value &= ~GQ7_ROLL_PITCH_WARNING; if(val) value |= GQ7_ROLL_PITCH_WARNING; } + bool gq7HeadingWarning() const { return (value & GQ7_HEADING_WARNING) > 0; } + void gq7HeadingWarning(bool val) { value &= ~GQ7_HEADING_WARNING; if(val) value |= GQ7_HEADING_WARNING; } + bool gq7PositionWarning() const { return (value & GQ7_POSITION_WARNING) > 0; } + void gq7PositionWarning(bool val) { value &= ~GQ7_POSITION_WARNING; if(val) value |= GQ7_POSITION_WARNING; } + bool gq7VelocityWarning() const { return (value & GQ7_VELOCITY_WARNING) > 0; } + void gq7VelocityWarning(bool val) { value &= ~GQ7_VELOCITY_WARNING; if(val) value |= GQ7_VELOCITY_WARNING; } + bool gq7ImuBiasWarning() const { return (value & GQ7_IMU_BIAS_WARNING) > 0; } + void gq7ImuBiasWarning(bool val) { value &= ~GQ7_IMU_BIAS_WARNING; if(val) value |= GQ7_IMU_BIAS_WARNING; } + bool gq7GnssClkWarning() const { return (value & GQ7_GNSS_CLK_WARNING) > 0; } + void gq7GnssClkWarning(bool val) { value &= ~GQ7_GNSS_CLK_WARNING; if(val) value |= GQ7_GNSS_CLK_WARNING; } + bool gq7AntennaLeverArmWarning() const { return (value & GQ7_ANTENNA_LEVER_ARM_WARNING) > 0; } + void gq7AntennaLeverArmWarning(bool val) { value &= ~GQ7_ANTENNA_LEVER_ARM_WARNING; if(val) value |= GQ7_ANTENNA_LEVER_ARM_WARNING; } + bool gq7MountingTransformWarning() const { return (value & GQ7_MOUNTING_TRANSFORM_WARNING) > 0; } + void gq7MountingTransformWarning(bool val) { value &= ~GQ7_MOUNTING_TRANSFORM_WARNING; if(val) value |= GQ7_MOUNTING_TRANSFORM_WARNING; } + bool gq7TimeSyncWarning() const { return (value & GQ7_TIME_SYNC_WARNING) > 0; } + void gq7TimeSyncWarning(bool val) { value &= ~GQ7_TIME_SYNC_WARNING; if(val) value |= GQ7_TIME_SYNC_WARNING; } + uint16_t gq7SolutionError() const { return (value & GQ7_SOLUTION_ERROR) >> 12; } + void gq7SolutionError(uint16_t val) { value = (value & ~GQ7_SOLUTION_ERROR) | (val << 12); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -208,6 +264,18 @@ struct FilterMeasurementIndicator : Bitfield FilterMeasurementIndicator& operator|=(uint8_t val) { return *this = value | val; } FilterMeasurementIndicator& operator&=(uint8_t val) { return *this = value & val; } + bool enabled() const { return (value & ENABLED) > 0; } + void enabled(bool val) { value &= ~ENABLED; if(val) value |= ENABLED; } + bool used() const { return (value & USED) > 0; } + void used(bool val) { value &= ~USED; if(val) value |= USED; } + bool residualHighWarning() const { return (value & RESIDUAL_HIGH_WARNING) > 0; } + void residualHighWarning(bool val) { value &= ~RESIDUAL_HIGH_WARNING; if(val) value |= RESIDUAL_HIGH_WARNING; } + bool sampleTimeWarning() const { return (value & SAMPLE_TIME_WARNING) > 0; } + void sampleTimeWarning(bool val) { value &= ~SAMPLE_TIME_WARNING; if(val) value |= SAMPLE_TIME_WARNING; } + bool configurationError() const { return (value & CONFIGURATION_ERROR) > 0; } + void configurationError(bool val) { value &= ~CONFIGURATION_ERROR; if(val) value |= CONFIGURATION_ERROR; } + bool maxNumMeasExceeded() const { return (value & MAX_NUM_MEAS_EXCEEDED) > 0; } + void maxNumMeasExceeded(bool val) { value &= ~MAX_NUM_MEAS_EXCEEDED; if(val) value |= MAX_NUM_MEAS_EXCEEDED; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -245,6 +313,38 @@ struct GnssAidStatusFlags : Bitfield GnssAidStatusFlags& operator|=(uint16_t val) { return *this = value | val; } GnssAidStatusFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tightCoupling() const { return (value & TIGHT_COUPLING) > 0; } + void tightCoupling(bool val) { value &= ~TIGHT_COUPLING; if(val) value |= TIGHT_COUPLING; } + bool differential() const { return (value & DIFFERENTIAL) > 0; } + void differential(bool val) { value &= ~DIFFERENTIAL; if(val) value |= DIFFERENTIAL; } + bool integerFix() const { return (value & INTEGER_FIX) > 0; } + void integerFix(bool val) { value &= ~INTEGER_FIX; if(val) value |= INTEGER_FIX; } + bool gpsL1() const { return (value & GPS_L1) > 0; } + void gpsL1(bool val) { value &= ~GPS_L1; if(val) value |= GPS_L1; } + bool gpsL2() const { return (value & GPS_L2) > 0; } + void gpsL2(bool val) { value &= ~GPS_L2; if(val) value |= GPS_L2; } + bool gpsL5() const { return (value & GPS_L5) > 0; } + void gpsL5(bool val) { value &= ~GPS_L5; if(val) value |= GPS_L5; } + bool gloL1() const { return (value & GLO_L1) > 0; } + void gloL1(bool val) { value &= ~GLO_L1; if(val) value |= GLO_L1; } + bool gloL2() const { return (value & GLO_L2) > 0; } + void gloL2(bool val) { value &= ~GLO_L2; if(val) value |= GLO_L2; } + bool galE1() const { return (value & GAL_E1) > 0; } + void galE1(bool val) { value &= ~GAL_E1; if(val) value |= GAL_E1; } + bool galE5() const { return (value & GAL_E5) > 0; } + void galE5(bool val) { value &= ~GAL_E5; if(val) value |= GAL_E5; } + bool galE6() const { return (value & GAL_E6) > 0; } + void galE6(bool val) { value &= ~GAL_E6; if(val) value |= GAL_E6; } + bool beiB1() const { return (value & BEI_B1) > 0; } + void beiB1(bool val) { value &= ~BEI_B1; if(val) value |= BEI_B1; } + bool beiB2() const { return (value & BEI_B2) > 0; } + void beiB2(bool val) { value &= ~BEI_B2; if(val) value |= BEI_B2; } + bool beiB3() const { return (value & BEI_B3) > 0; } + void beiB3(bool val) { value &= ~BEI_B3; if(val) value |= BEI_B3; } + bool noFix() const { return (value & NO_FIX) > 0; } + void noFix(bool val) { value &= ~NO_FIX; if(val) value |= NO_FIX; } + bool configError() const { return (value & CONFIG_ERROR) > 0; } + void configError(bool val) { value &= ~CONFIG_ERROR; if(val) value |= CONFIG_ERROR; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2435,6 +2535,12 @@ struct GnssDualAntennaStatus DualAntennaStatusFlags& operator|=(uint16_t val) { return *this = value | val; } DualAntennaStatusFlags& operator&=(uint16_t val) { return *this = value & val; } + bool rcv1DataValid() const { return (value & RCV_1_DATA_VALID) > 0; } + void rcv1DataValid(bool val) { value &= ~RCV_1_DATA_VALID; if(val) value |= RCV_1_DATA_VALID; } + bool rcv2DataValid() const { return (value & RCV_2_DATA_VALID) > 0; } + void rcv2DataValid(bool val) { value &= ~RCV_2_DATA_VALID; if(val) value |= RCV_2_DATA_VALID; } + bool antennaOffsetsValid() const { return (value & ANTENNA_OFFSETS_VALID) > 0; } + void antennaOffsetsValid(bool val) { value &= ~ANTENNA_OFFSETS_VALID; if(val) value |= ANTENNA_OFFSETS_VALID; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_gnss.hpp b/src/cpp/mip/definitions/data_gnss.hpp index 30e85c380..c1ca92478 100644 --- a/src/cpp/mip/definitions/data_gnss.hpp +++ b/src/cpp/mip/definitions/data_gnss.hpp @@ -198,6 +198,18 @@ struct PosLlh ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool latLon() const { return (value & LAT_LON) > 0; } + void latLon(bool val) { value &= ~LAT_LON; if(val) value |= LAT_LON; } + bool ellipsoidHeight() const { return (value & ELLIPSOID_HEIGHT) > 0; } + void ellipsoidHeight(bool val) { value &= ~ELLIPSOID_HEIGHT; if(val) value |= ELLIPSOID_HEIGHT; } + bool mslHeight() const { return (value & MSL_HEIGHT) > 0; } + void mslHeight(bool val) { value &= ~MSL_HEIGHT; if(val) value |= MSL_HEIGHT; } + bool horizontalAccuracy() const { return (value & HORIZONTAL_ACCURACY) > 0; } + void horizontalAccuracy(bool val) { value &= ~HORIZONTAL_ACCURACY; if(val) value |= HORIZONTAL_ACCURACY; } + bool verticalAccuracy() const { return (value & VERTICAL_ACCURACY) > 0; } + void verticalAccuracy(bool val) { value &= ~VERTICAL_ACCURACY; if(val) value |= VERTICAL_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -265,6 +277,12 @@ struct PosEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool position() const { return (value & POSITION) > 0; } + void position(bool val) { value &= ~POSITION; if(val) value |= POSITION; } + bool positionAccuracy() const { return (value & POSITION_ACCURACY) > 0; } + void positionAccuracy(bool val) { value &= ~POSITION_ACCURACY; if(val) value |= POSITION_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -332,6 +350,20 @@ struct VelNed ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool velocity() const { return (value & VELOCITY) > 0; } + void velocity(bool val) { value &= ~VELOCITY; if(val) value |= VELOCITY; } + bool speed3d() const { return (value & SPEED_3D) > 0; } + void speed3d(bool val) { value &= ~SPEED_3D; if(val) value |= SPEED_3D; } + bool groundSpeed() const { return (value & GROUND_SPEED) > 0; } + void groundSpeed(bool val) { value &= ~GROUND_SPEED; if(val) value |= GROUND_SPEED; } + bool heading() const { return (value & HEADING) > 0; } + void heading(bool val) { value &= ~HEADING; if(val) value |= HEADING; } + bool speedAccuracy() const { return (value & SPEED_ACCURACY) > 0; } + void speedAccuracy(bool val) { value &= ~SPEED_ACCURACY; if(val) value |= SPEED_ACCURACY; } + bool headingAccuracy() const { return (value & HEADING_ACCURACY) > 0; } + void headingAccuracy(bool val) { value &= ~HEADING_ACCURACY; if(val) value |= HEADING_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -399,6 +431,12 @@ struct VelEcef ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool velocity() const { return (value & VELOCITY) > 0; } + void velocity(bool val) { value &= ~VELOCITY; if(val) value |= VELOCITY; } + bool velocityAccuracy() const { return (value & VELOCITY_ACCURACY) > 0; } + void velocityAccuracy(bool val) { value &= ~VELOCITY_ACCURACY; if(val) value |= VELOCITY_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -467,6 +505,22 @@ struct Dop ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gdop() const { return (value & GDOP) > 0; } + void gdop(bool val) { value &= ~GDOP; if(val) value |= GDOP; } + bool pdop() const { return (value & PDOP) > 0; } + void pdop(bool val) { value &= ~PDOP; if(val) value |= PDOP; } + bool hdop() const { return (value & HDOP) > 0; } + void hdop(bool val) { value &= ~HDOP; if(val) value |= HDOP; } + bool vdop() const { return (value & VDOP) > 0; } + void vdop(bool val) { value &= ~VDOP; if(val) value |= VDOP; } + bool tdop() const { return (value & TDOP) > 0; } + void tdop(bool val) { value &= ~TDOP; if(val) value |= TDOP; } + bool ndop() const { return (value & NDOP) > 0; } + void ndop(bool val) { value &= ~NDOP; if(val) value |= NDOP; } + bool edop() const { return (value & EDOP) > 0; } + void edop(bool val) { value &= ~EDOP; if(val) value |= EDOP; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -535,6 +589,12 @@ struct UtcTime ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gnssDateTime() const { return (value & GNSS_DATE_TIME) > 0; } + void gnssDateTime(bool val) { value &= ~GNSS_DATE_TIME; if(val) value |= GNSS_DATE_TIME; } + bool leapSecondsKnown() const { return (value & LEAP_SECONDS_KNOWN) > 0; } + void leapSecondsKnown(bool val) { value &= ~LEAP_SECONDS_KNOWN; if(val) value |= LEAP_SECONDS_KNOWN; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -603,6 +663,12 @@ struct GpsTime ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { value &= ~TOW; if(val) value |= TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { value &= ~WEEK_NUMBER; if(val) value |= WEEK_NUMBER; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -667,6 +733,14 @@ struct ClockInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool bias() const { return (value & BIAS) > 0; } + void bias(bool val) { value &= ~BIAS; if(val) value |= BIAS; } + bool drift() const { return (value & DRIFT) > 0; } + void drift(bool val) { value &= ~DRIFT; if(val) value |= DRIFT; } + bool accuracyEstimate() const { return (value & ACCURACY_ESTIMATE) > 0; } + void accuracyEstimate(bool val) { value &= ~ACCURACY_ESTIMATE; if(val) value |= ACCURACY_ESTIMATE; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -742,6 +816,10 @@ struct FixInfo FixFlags& operator|=(uint16_t val) { return *this = value | val; } FixFlags& operator&=(uint16_t val) { return *this = value & val; } + bool sbasUsed() const { return (value & SBAS_USED) > 0; } + void sbasUsed(bool val) { value &= ~SBAS_USED; if(val) value |= SBAS_USED; } + bool dgnssUsed() const { return (value & DGNSS_USED) > 0; } + void dgnssUsed(bool val) { value &= ~DGNSS_USED; if(val) value |= DGNSS_USED; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -767,6 +845,14 @@ struct FixInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool fixType() const { return (value & FIX_TYPE) > 0; } + void fixType(bool val) { value &= ~FIX_TYPE; if(val) value |= FIX_TYPE; } + bool numSv() const { return (value & NUM_SV) > 0; } + void numSv(bool val) { value &= ~NUM_SV; if(val) value |= NUM_SV; } + bool fixFlags() const { return (value & FIX_FLAGS) > 0; } + void fixFlags(bool val) { value &= ~FIX_FLAGS; if(val) value |= FIX_FLAGS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -832,6 +918,10 @@ struct SvInfo SVFlags& operator|=(uint16_t val) { return *this = value | val; } SVFlags& operator&=(uint16_t val) { return *this = value & val; } + bool usedForNavigation() const { return (value & USED_FOR_NAVIGATION) > 0; } + void usedForNavigation(bool val) { value &= ~USED_FOR_NAVIGATION; if(val) value |= USED_FOR_NAVIGATION; } + bool healthy() const { return (value & HEALTHY) > 0; } + void healthy(bool val) { value &= ~HEALTHY; if(val) value |= HEALTHY; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -860,6 +950,20 @@ struct SvInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool channel() const { return (value & CHANNEL) > 0; } + void channel(bool val) { value &= ~CHANNEL; if(val) value |= CHANNEL; } + bool svId() const { return (value & SV_ID) > 0; } + void svId(bool val) { value &= ~SV_ID; if(val) value |= SV_ID; } + bool carrierNoiseRatio() const { return (value & CARRIER_NOISE_RATIO) > 0; } + void carrierNoiseRatio(bool val) { value &= ~CARRIER_NOISE_RATIO; if(val) value |= CARRIER_NOISE_RATIO; } + bool azimuth() const { return (value & AZIMUTH) > 0; } + void azimuth(bool val) { value &= ~AZIMUTH; if(val) value |= AZIMUTH; } + bool elevation() const { return (value & ELEVATION) > 0; } + void elevation(bool val) { value &= ~ELEVATION; if(val) value |= ELEVATION; } + bool svFlags() const { return (value & SV_FLAGS) > 0; } + void svFlags(bool val) { value &= ~SV_FLAGS; if(val) value |= SV_FLAGS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -951,6 +1055,14 @@ struct HwStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool sensorState() const { return (value & SENSOR_STATE) > 0; } + void sensorState(bool val) { value &= ~SENSOR_STATE; if(val) value |= SENSOR_STATE; } + bool antennaState() const { return (value & ANTENNA_STATE) > 0; } + void antennaState(bool val) { value &= ~ANTENNA_STATE; if(val) value |= ANTENNA_STATE; } + bool antennaPower() const { return (value & ANTENNA_POWER) > 0; } + void antennaPower(bool val) { value &= ~ANTENNA_POWER; if(val) value |= ANTENNA_POWER; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1029,6 +1141,16 @@ struct DgpsInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool age() const { return (value & AGE) > 0; } + void age(bool val) { value &= ~AGE; if(val) value |= AGE; } + bool baseStationId() const { return (value & BASE_STATION_ID) > 0; } + void baseStationId(bool val) { value &= ~BASE_STATION_ID; if(val) value |= BASE_STATION_ID; } + bool baseStationStatus() const { return (value & BASE_STATION_STATUS) > 0; } + void baseStationStatus(bool val) { value &= ~BASE_STATION_STATUS; if(val) value |= BASE_STATION_STATUS; } + bool numChannels() const { return (value & NUM_CHANNELS) > 0; } + void numChannels(bool val) { value &= ~NUM_CHANNELS; if(val) value |= NUM_CHANNELS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1098,6 +1220,16 @@ struct DgpsChannel ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool id() const { return (value & ID) > 0; } + void id(bool val) { value &= ~ID; if(val) value |= ID; } + bool age() const { return (value & AGE) > 0; } + void age(bool val) { value &= ~AGE; if(val) value |= AGE; } + bool rangeCorrection() const { return (value & RANGE_CORRECTION) > 0; } + void rangeCorrection(bool val) { value &= ~RANGE_CORRECTION; if(val) value |= RANGE_CORRECTION; } + bool rangeRateCorrection() const { return (value & RANGE_RATE_CORRECTION) > 0; } + void rangeRateCorrection(bool val) { value &= ~RANGE_RATE_CORRECTION; if(val) value |= RANGE_RATE_CORRECTION; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1167,6 +1299,16 @@ struct ClockInfo2 ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool bias() const { return (value & BIAS) > 0; } + void bias(bool val) { value &= ~BIAS; if(val) value |= BIAS; } + bool drift() const { return (value & DRIFT) > 0; } + void drift(bool val) { value &= ~DRIFT; if(val) value |= DRIFT; } + bool biasAccuracy() const { return (value & BIAS_ACCURACY) > 0; } + void biasAccuracy(bool val) { value &= ~BIAS_ACCURACY; if(val) value |= BIAS_ACCURACY; } + bool driftAccuracy() const { return (value & DRIFT_ACCURACY) > 0; } + void driftAccuracy(bool val) { value &= ~DRIFT_ACCURACY; if(val) value |= DRIFT_ACCURACY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1230,6 +1372,8 @@ struct GpsLeapSeconds ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool leapSeconds() const { return (value & LEAP_SECONDS) > 0; } + void leapSeconds(bool val) { value &= ~LEAP_SECONDS; if(val) value |= LEAP_SECONDS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1293,6 +1437,14 @@ struct SbasInfo SbasStatus& operator|=(uint8_t val) { return *this = value | val; } SbasStatus& operator&=(uint8_t val) { return *this = value & val; } + bool rangeAvailable() const { return (value & RANGE_AVAILABLE) > 0; } + void rangeAvailable(bool val) { value &= ~RANGE_AVAILABLE; if(val) value |= RANGE_AVAILABLE; } + bool correctionsAvailable() const { return (value & CORRECTIONS_AVAILABLE) > 0; } + void correctionsAvailable(bool val) { value &= ~CORRECTIONS_AVAILABLE; if(val) value |= CORRECTIONS_AVAILABLE; } + bool integrityAvailable() const { return (value & INTEGRITY_AVAILABLE) > 0; } + void integrityAvailable(bool val) { value &= ~INTEGRITY_AVAILABLE; if(val) value |= INTEGRITY_AVAILABLE; } + bool testMode() const { return (value & TEST_MODE) > 0; } + void testMode(bool val) { value &= ~TEST_MODE; if(val) value |= TEST_MODE; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1321,6 +1473,20 @@ struct SbasInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { value &= ~TOW; if(val) value |= TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { value &= ~WEEK_NUMBER; if(val) value |= WEEK_NUMBER; } + bool sbasSystem() const { return (value & SBAS_SYSTEM) > 0; } + void sbasSystem(bool val) { value &= ~SBAS_SYSTEM; if(val) value |= SBAS_SYSTEM; } + bool sbasId() const { return (value & SBAS_ID) > 0; } + void sbasId(bool val) { value &= ~SBAS_ID; if(val) value |= SBAS_ID; } + bool count() const { return (value & COUNT) > 0; } + void count(bool val) { value &= ~COUNT; if(val) value |= COUNT; } + bool sbasStatus() const { return (value & SBAS_STATUS) > 0; } + void sbasStatus(bool val) { value &= ~SBAS_STATUS; if(val) value |= SBAS_STATUS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1411,6 +1577,14 @@ struct SbasCorrection ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool udrei() const { return (value & UDREI) > 0; } + void udrei(bool val) { value &= ~UDREI; if(val) value |= UDREI; } + bool pseudorangeCorrection() const { return (value & PSEUDORANGE_CORRECTION) > 0; } + void pseudorangeCorrection(bool val) { value &= ~PSEUDORANGE_CORRECTION; if(val) value |= PSEUDORANGE_CORRECTION; } + bool ionoCorrection() const { return (value & IONO_CORRECTION) > 0; } + void ionoCorrection(bool val) { value &= ~IONO_CORRECTION; if(val) value |= IONO_CORRECTION; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1506,6 +1680,14 @@ struct RfErrorDetection ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool rfBand() const { return (value & RF_BAND) > 0; } + void rfBand(bool val) { value &= ~RF_BAND; if(val) value |= RF_BAND; } + bool jammingState() const { return (value & JAMMING_STATE) > 0; } + void jammingState(bool val) { value &= ~JAMMING_STATE; if(val) value |= JAMMING_STATE; } + bool spoofingState() const { return (value & SPOOFING_STATE) > 0; } + void spoofingState(bool val) { value &= ~SPOOFING_STATE; if(val) value |= SPOOFING_STATE; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1579,6 +1761,24 @@ struct BaseStationInfo IndicatorFlags& operator|=(uint16_t val) { return *this = value | val; } IndicatorFlags& operator&=(uint16_t val) { return *this = value & val; } + bool gps() const { return (value & GPS) > 0; } + void gps(bool val) { value &= ~GPS; if(val) value |= GPS; } + bool glonass() const { return (value & GLONASS) > 0; } + void glonass(bool val) { value &= ~GLONASS; if(val) value |= GLONASS; } + bool galileo() const { return (value & GALILEO) > 0; } + void galileo(bool val) { value &= ~GALILEO; if(val) value |= GALILEO; } + bool beidou() const { return (value & BEIDOU) > 0; } + void beidou(bool val) { value &= ~BEIDOU; if(val) value |= BEIDOU; } + bool refStation() const { return (value & REF_STATION) > 0; } + void refStation(bool val) { value &= ~REF_STATION; if(val) value |= REF_STATION; } + bool singleReceiver() const { return (value & SINGLE_RECEIVER) > 0; } + void singleReceiver(bool val) { value &= ~SINGLE_RECEIVER; if(val) value |= SINGLE_RECEIVER; } + bool quarterCycleBit1() const { return (value & QUARTER_CYCLE_BIT1) > 0; } + void quarterCycleBit1(bool val) { value &= ~QUARTER_CYCLE_BIT1; if(val) value |= QUARTER_CYCLE_BIT1; } + bool quarterCycleBit2() const { return (value & QUARTER_CYCLE_BIT2) > 0; } + void quarterCycleBit2(bool val) { value &= ~QUARTER_CYCLE_BIT2; if(val) value |= QUARTER_CYCLE_BIT2; } + uint16_t quarterCycleBits() const { return (value & QUARTER_CYCLE_BITS) >> 6; } + void quarterCycleBits(uint16_t val) { value = (value & ~QUARTER_CYCLE_BITS) | (val << 6); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1607,6 +1807,20 @@ struct BaseStationInfo ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { value &= ~TOW; if(val) value |= TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { value &= ~WEEK_NUMBER; if(val) value |= WEEK_NUMBER; } + bool ecefPosition() const { return (value & ECEF_POSITION) > 0; } + void ecefPosition(bool val) { value &= ~ECEF_POSITION; if(val) value |= ECEF_POSITION; } + bool height() const { return (value & HEIGHT) > 0; } + void height(bool val) { value &= ~HEIGHT; if(val) value |= HEIGHT; } + bool stationId() const { return (value & STATION_ID) > 0; } + void stationId(bool val) { value &= ~STATION_ID; if(val) value |= STATION_ID; } + bool indicators() const { return (value & INDICATORS) > 0; } + void indicators(bool val) { value &= ~INDICATORS; if(val) value |= INDICATORS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1679,6 +1893,24 @@ struct RtkCorrectionsStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { value &= ~TOW; if(val) value |= TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { value &= ~WEEK_NUMBER; if(val) value |= WEEK_NUMBER; } + bool epochStatus() const { return (value & EPOCH_STATUS) > 0; } + void epochStatus(bool val) { value &= ~EPOCH_STATUS; if(val) value |= EPOCH_STATUS; } + bool dongleStatus() const { return (value & DONGLE_STATUS) > 0; } + void dongleStatus(bool val) { value &= ~DONGLE_STATUS; if(val) value |= DONGLE_STATUS; } + bool gpsLatency() const { return (value & GPS_LATENCY) > 0; } + void gpsLatency(bool val) { value &= ~GPS_LATENCY; if(val) value |= GPS_LATENCY; } + bool glonassLatency() const { return (value & GLONASS_LATENCY) > 0; } + void glonassLatency(bool val) { value &= ~GLONASS_LATENCY; if(val) value |= GLONASS_LATENCY; } + bool galileoLatency() const { return (value & GALILEO_LATENCY) > 0; } + void galileoLatency(bool val) { value &= ~GALILEO_LATENCY; if(val) value |= GALILEO_LATENCY; } + bool beidouLatency() const { return (value & BEIDOU_LATENCY) > 0; } + void beidouLatency(bool val) { value &= ~BEIDOU_LATENCY; if(val) value |= BEIDOU_LATENCY; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1709,6 +1941,24 @@ struct RtkCorrectionsStatus EpochStatus& operator|=(uint16_t val) { return *this = value | val; } EpochStatus& operator&=(uint16_t val) { return *this = value & val; } + bool antennaLocationReceived() const { return (value & ANTENNA_LOCATION_RECEIVED) > 0; } + void antennaLocationReceived(bool val) { value &= ~ANTENNA_LOCATION_RECEIVED; if(val) value |= ANTENNA_LOCATION_RECEIVED; } + bool antennaDescriptionReceived() const { return (value & ANTENNA_DESCRIPTION_RECEIVED) > 0; } + void antennaDescriptionReceived(bool val) { value &= ~ANTENNA_DESCRIPTION_RECEIVED; if(val) value |= ANTENNA_DESCRIPTION_RECEIVED; } + bool gpsReceived() const { return (value & GPS_RECEIVED) > 0; } + void gpsReceived(bool val) { value &= ~GPS_RECEIVED; if(val) value |= GPS_RECEIVED; } + bool glonassReceived() const { return (value & GLONASS_RECEIVED) > 0; } + void glonassReceived(bool val) { value &= ~GLONASS_RECEIVED; if(val) value |= GLONASS_RECEIVED; } + bool galileoReceived() const { return (value & GALILEO_RECEIVED) > 0; } + void galileoReceived(bool val) { value &= ~GALILEO_RECEIVED; if(val) value |= GALILEO_RECEIVED; } + bool beidouReceived() const { return (value & BEIDOU_RECEIVED) > 0; } + void beidouReceived(bool val) { value &= ~BEIDOU_RECEIVED; if(val) value |= BEIDOU_RECEIVED; } + bool usingGpsMsmMessages() const { return (value & USING_GPS_MSM_MESSAGES) > 0; } + void usingGpsMsmMessages(bool val) { value &= ~USING_GPS_MSM_MESSAGES; if(val) value |= USING_GPS_MSM_MESSAGES; } + bool usingGlonassMsmMessages() const { return (value & USING_GLONASS_MSM_MESSAGES) > 0; } + void usingGlonassMsmMessages(bool val) { value &= ~USING_GLONASS_MSM_MESSAGES; if(val) value |= USING_GLONASS_MSM_MESSAGES; } + bool dongleStatusReadFailed() const { return (value & DONGLE_STATUS_READ_FAILED) > 0; } + void dongleStatusReadFailed(bool val) { value &= ~DONGLE_STATUS_READ_FAILED; if(val) value |= DONGLE_STATUS_READ_FAILED; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1784,6 +2034,22 @@ struct SatelliteStatus ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { value &= ~TOW; if(val) value |= TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { value &= ~WEEK_NUMBER; if(val) value |= WEEK_NUMBER; } + bool gnssId() const { return (value & GNSS_ID) > 0; } + void gnssId(bool val) { value &= ~GNSS_ID; if(val) value |= GNSS_ID; } + bool satelliteId() const { return (value & SATELLITE_ID) > 0; } + void satelliteId(bool val) { value &= ~SATELLITE_ID; if(val) value |= SATELLITE_ID; } + bool elevation() const { return (value & ELEVATION) > 0; } + void elevation(bool val) { value &= ~ELEVATION; if(val) value |= ELEVATION; } + bool azimuth() const { return (value & AZIMUTH) > 0; } + void azimuth(bool val) { value &= ~AZIMUTH; if(val) value |= AZIMUTH; } + bool health() const { return (value & HEALTH) > 0; } + void health(bool val) { value &= ~HEALTH; if(val) value |= HEALTH; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1878,6 +2144,40 @@ struct Raw ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { value &= ~TOW; if(val) value |= TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { value &= ~WEEK_NUMBER; if(val) value |= WEEK_NUMBER; } + bool receiverId() const { return (value & RECEIVER_ID) > 0; } + void receiverId(bool val) { value &= ~RECEIVER_ID; if(val) value |= RECEIVER_ID; } + bool trackingChannel() const { return (value & TRACKING_CHANNEL) > 0; } + void trackingChannel(bool val) { value &= ~TRACKING_CHANNEL; if(val) value |= TRACKING_CHANNEL; } + bool gnssId() const { return (value & GNSS_ID) > 0; } + void gnssId(bool val) { value &= ~GNSS_ID; if(val) value |= GNSS_ID; } + bool satelliteId() const { return (value & SATELLITE_ID) > 0; } + void satelliteId(bool val) { value &= ~SATELLITE_ID; if(val) value |= SATELLITE_ID; } + bool signalId() const { return (value & SIGNAL_ID) > 0; } + void signalId(bool val) { value &= ~SIGNAL_ID; if(val) value |= SIGNAL_ID; } + bool signalStrength() const { return (value & SIGNAL_STRENGTH) > 0; } + void signalStrength(bool val) { value &= ~SIGNAL_STRENGTH; if(val) value |= SIGNAL_STRENGTH; } + bool quality() const { return (value & QUALITY) > 0; } + void quality(bool val) { value &= ~QUALITY; if(val) value |= QUALITY; } + bool pseudorange() const { return (value & PSEUDORANGE) > 0; } + void pseudorange(bool val) { value &= ~PSEUDORANGE; if(val) value |= PSEUDORANGE; } + bool carrierPhase() const { return (value & CARRIER_PHASE) > 0; } + void carrierPhase(bool val) { value &= ~CARRIER_PHASE; if(val) value |= CARRIER_PHASE; } + bool doppler() const { return (value & DOPPLER) > 0; } + void doppler(bool val) { value &= ~DOPPLER; if(val) value |= DOPPLER; } + bool rangeUncertainty() const { return (value & RANGE_UNCERTAINTY) > 0; } + void rangeUncertainty(bool val) { value &= ~RANGE_UNCERTAINTY; if(val) value |= RANGE_UNCERTAINTY; } + bool carrierPhaseUncertainty() const { return (value & CARRIER_PHASE_UNCERTAINTY) > 0; } + void carrierPhaseUncertainty(bool val) { value &= ~CARRIER_PHASE_UNCERTAINTY; if(val) value |= CARRIER_PHASE_UNCERTAINTY; } + bool dopplerUncertainty() const { return (value & DOPPLER_UNCERTAINTY) > 0; } + void dopplerUncertainty(bool val) { value &= ~DOPPLER_UNCERTAINTY; if(val) value |= DOPPLER_UNCERTAINTY; } + bool lockTime() const { return (value & LOCK_TIME) > 0; } + void lockTime(bool val) { value &= ~LOCK_TIME; if(val) value |= LOCK_TIME; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -1957,6 +2257,12 @@ struct GpsEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool ephemeris() const { return (value & EPHEMERIS) > 0; } + void ephemeris(bool val) { value &= ~EPHEMERIS; if(val) value |= EPHEMERIS; } + bool modernData() const { return (value & MODERN_DATA) > 0; } + void modernData(bool val) { value &= ~MODERN_DATA; if(val) value |= MODERN_DATA; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2051,6 +2357,12 @@ struct GalileoEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool ephemeris() const { return (value & EPHEMERIS) > 0; } + void ephemeris(bool val) { value &= ~EPHEMERIS; if(val) value |= EPHEMERIS; } + bool modernData() const { return (value & MODERN_DATA) > 0; } + void modernData(bool val) { value &= ~MODERN_DATA; if(val) value |= MODERN_DATA; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2144,6 +2456,10 @@ struct GloEphemeris ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool ephemeris() const { return (value & EPHEMERIS) > 0; } + void ephemeris(bool val) { value &= ~EPHEMERIS; if(val) value |= EPHEMERIS; } + bool flags() const { return (value & FLAGS) > 0; } + void flags(bool val) { value &= ~FLAGS; if(val) value |= FLAGS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2231,6 +2547,16 @@ struct GpsIonoCorr ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { value &= ~TOW; if(val) value |= TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { value &= ~WEEK_NUMBER; if(val) value |= WEEK_NUMBER; } + bool alpha() const { return (value & ALPHA) > 0; } + void alpha(bool val) { value &= ~ALPHA; if(val) value |= ALPHA; } + bool beta() const { return (value & BETA) > 0; } + void beta(bool val) { value &= ~BETA; if(val) value |= BETA; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -2298,6 +2624,16 @@ struct GalileoIonoCorr ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { value &= ~TOW; if(val) value |= TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { value &= ~WEEK_NUMBER; if(val) value |= WEEK_NUMBER; } + bool alpha() const { return (value & ALPHA) > 0; } + void alpha(bool val) { value &= ~ALPHA; if(val) value |= ALPHA; } + bool disturbanceFlags() const { return (value & DISTURBANCE_FLAGS) > 0; } + void disturbanceFlags(bool val) { value &= ~DISTURBANCE_FLAGS; if(val) value |= DISTURBANCE_FLAGS; } + uint16_t flags() const { return (value & FLAGS) >> 0; } + void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_sensor.hpp b/src/cpp/mip/definitions/data_sensor.hpp index 1c781a76b..832a659ea 100644 --- a/src/cpp/mip/definitions/data_sensor.hpp +++ b/src/cpp/mip/definitions/data_sensor.hpp @@ -765,6 +765,16 @@ struct GpsTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool ppsValid() const { return (value & PPS_VALID) > 0; } + void ppsValid(bool val) { value &= ~PPS_VALID; if(val) value |= PPS_VALID; } + bool timeRefresh() const { return (value & TIME_REFRESH) > 0; } + void timeRefresh(bool val) { value &= ~TIME_REFRESH; if(val) value |= TIME_REFRESH; } + bool timeInitialized() const { return (value & TIME_INITIALIZED) > 0; } + void timeInitialized(bool val) { value &= ~TIME_INITIALIZED; if(val) value |= TIME_INITIALIZED; } + bool towValid() const { return (value & TOW_VALID) > 0; } + void towValid(bool val) { value &= ~TOW_VALID; if(val) value |= TOW_VALID; } + bool weekNumberValid() const { return (value & WEEK_NUMBER_VALID) > 0; } + void weekNumberValid(bool val) { value &= ~WEEK_NUMBER_VALID; if(val) value |= WEEK_NUMBER_VALID; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -960,6 +970,26 @@ struct OverrangeStatus Status& operator|=(uint16_t val) { return *this = value | val; } Status& operator&=(uint16_t val) { return *this = value & val; } + bool accelX() const { return (value & ACCEL_X) > 0; } + void accelX(bool val) { value &= ~ACCEL_X; if(val) value |= ACCEL_X; } + bool accelY() const { return (value & ACCEL_Y) > 0; } + void accelY(bool val) { value &= ~ACCEL_Y; if(val) value |= ACCEL_Y; } + bool accelZ() const { return (value & ACCEL_Z) > 0; } + void accelZ(bool val) { value &= ~ACCEL_Z; if(val) value |= ACCEL_Z; } + bool gyroX() const { return (value & GYRO_X) > 0; } + void gyroX(bool val) { value &= ~GYRO_X; if(val) value |= GYRO_X; } + bool gyroY() const { return (value & GYRO_Y) > 0; } + void gyroY(bool val) { value &= ~GYRO_Y; if(val) value |= GYRO_Y; } + bool gyroZ() const { return (value & GYRO_Z) > 0; } + void gyroZ(bool val) { value &= ~GYRO_Z; if(val) value |= GYRO_Z; } + bool magX() const { return (value & MAG_X) > 0; } + void magX(bool val) { value &= ~MAG_X; if(val) value |= MAG_X; } + bool magY() const { return (value & MAG_Y) > 0; } + void magY(bool val) { value &= ~MAG_Y; if(val) value |= MAG_Y; } + bool magZ() const { return (value & MAG_Z) > 0; } + void magZ(bool val) { value &= ~MAG_Z; if(val) value |= MAG_Z; } + bool press() const { return (value & PRESS) > 0; } + void press(bool val) { value &= ~PRESS; if(val) value |= PRESS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; diff --git a/src/cpp/mip/definitions/data_shared.hpp b/src/cpp/mip/definitions/data_shared.hpp index 630c4c456..6e3a0c7e5 100644 --- a/src/cpp/mip/definitions/data_shared.hpp +++ b/src/cpp/mip/definitions/data_shared.hpp @@ -206,6 +206,12 @@ struct GpsTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool tow() const { return (value & TOW) > 0; } + void tow(bool val) { value &= ~TOW; if(val) value |= TOW; } + bool weekNumber() const { return (value & WEEK_NUMBER) > 0; } + void weekNumber(bool val) { value &= ~WEEK_NUMBER; if(val) value |= WEEK_NUMBER; } + uint16_t timeValid() const { return (value & TIME_VALID) >> 0; } + void timeValid(uint16_t val) { value = (value & ~TIME_VALID) | (val << 0); } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -411,6 +417,8 @@ struct ExternalTimestamp ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool nanoseconds() const { return (value & NANOSECONDS) > 0; } + void nanoseconds(bool val) { value &= ~NANOSECONDS; if(val) value |= NANOSECONDS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; @@ -483,6 +491,8 @@ struct ExternalTimeDelta ValidFlags& operator|=(uint16_t val) { return *this = value | val; } ValidFlags& operator&=(uint16_t val) { return *this = value & val; } + bool dtNanos() const { return (value & DT_NANOS) > 0; } + void dtNanos(bool val) { value &= ~DT_NANOS; if(val) value |= DT_NANOS; } bool allSet() const { return value == ALL; } void setAll() { value |= ALL; } }; From 10b6dd005d044d6493fa016bcfe5f4c0e1f80b7a Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 22 Aug 2024 14:11:25 -0400 Subject: [PATCH 078/147] Regenerate stale definitions. --- src/c/mip/definitions/commands_3dm.h | 8 +- src/c/mip/definitions/commands_aiding.c | 106 +++---- src/c/mip/definitions/commands_aiding.h | 275 +++++++++--------- src/c/mip/definitions/commands_filter.h | 10 +- src/c/mip/definitions/commands_gnss.h | 15 +- src/c/mip/definitions/data_filter.h | 27 +- src/cpp/mip/definitions/commands_3dm.hpp | 8 +- src/cpp/mip/definitions/commands_aiding.cpp | 66 ++--- src/cpp/mip/definitions/commands_aiding.hpp | 145 ++++----- src/cpp/mip/definitions/commands_filter.hpp | 10 +- src/cpp/mip/definitions/commands_gnss.hpp | 15 +- src/cpp/mip/definitions/data_filter.hpp | 27 +- .../mip/metadata/definitions/commands_3dm.hpp | 10 +- .../metadata/definitions/commands_aiding.hpp | 136 ++++----- .../metadata/definitions/commands_filter.hpp | 8 +- .../metadata/definitions/commands_gnss.hpp | 12 +- .../mip/metadata/definitions/data_filter.hpp | 17 +- .../mip/metadata/definitions/data_sensor.hpp | 2 +- 18 files changed, 461 insertions(+), 436 deletions(-) diff --git a/src/c/mip/definitions/commands_3dm.h b/src/c/mip/definitions/commands_3dm.h index bb94c738a..45da067c4 100644 --- a/src/c/mip/definitions/commands_3dm.h +++ b/src/c/mip/definitions/commands_3dm.h @@ -152,8 +152,8 @@ enum mip_nmea_message_message_id MIP_NMEA_MESSAGE_MESSAGE_ID_VTG = 5, ///< Course over Ground. Source can be the Filter or GNSS1/2 datasets. MIP_NMEA_MESSAGE_MESSAGE_ID_HDT = 6, ///< Heading, True. Source can be the Filter or GNSS1/2 datasets. MIP_NMEA_MESSAGE_MESSAGE_ID_ZDA = 7, ///< Time & Date. Source must be the GNSS1 or GNSS2 datasets. - MIP_NMEA_MESSAGE_MESSAGE_ID_PKRA = 129, ///< Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. - MIP_NMEA_MESSAGE_MESSAGE_ID_PKRR = 130, ///< Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. + MIP_NMEA_MESSAGE_MESSAGE_ID_MSRA = 129, ///< MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. + MIP_NMEA_MESSAGE_MESSAGE_ID_MSRR = 130, ///< MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. }; typedef enum mip_nmea_message_message_id mip_nmea_message_message_id; @@ -2040,7 +2040,7 @@ mip_cmd_result mip_3dm_capture_gyro_bias(mip_interface* device, uint16_t averagi /// /// The values for this offset are determined empirically by external software algorithms /// based on calibration data taken after the device is installed in its application. These values -/// can be obtained and set by using the LORD "MIP Iron Calibration" application. +/// can be obtained and set by using Microstrain software tools. /// Alternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run. /// The offset is applied to the scaled magnetometer vector prior to output. /// @@ -2079,7 +2079,7 @@ mip_cmd_result mip_3dm_default_mag_hard_iron_offset(mip_interface* device); /// /// The values for this matrix are determined empirically by external software algorithms /// based on calibration data taken after the device is installed in its application. These values -/// can be obtained and set by using the LORD "MIP Iron Calibration" application. +/// can be obtained and set by using Microstrain software tools. /// Alternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run. /// The matrix is applied to the scaled magnetometer vector prior to output. /// diff --git a/src/c/mip/definitions/commands_aiding.c b/src/c/mip/definitions/commands_aiding.c index 4f1039c83..4adc03899 100644 --- a/src/c/mip/definitions/commands_aiding.c +++ b/src/c/mip/definitions/commands_aiding.c @@ -262,39 +262,39 @@ mip_cmd_result mip_aiding_default_frame_config(mip_interface* device, uint8_t fr return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self) +void insert_mip_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_echo_control_command* self) { insert_mip_function_selector(serializer, self->function); if( self->function == MIP_FUNCTION_WRITE ) { - insert_mip_aiding_aiding_echo_control_command_mode(serializer, self->mode); + insert_mip_aiding_echo_control_command_mode(serializer, self->mode); } } -void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self) +void extract_mip_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_echo_control_command* self) { extract_mip_function_selector(serializer, &self->function); if( self->function == MIP_FUNCTION_WRITE ) { - extract_mip_aiding_aiding_echo_control_command_mode(serializer, &self->mode); + extract_mip_aiding_echo_control_command_mode(serializer, &self->mode); } } -void insert_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self) +void insert_mip_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_echo_control_response* self) { - insert_mip_aiding_aiding_echo_control_command_mode(serializer, self->mode); + insert_mip_aiding_echo_control_command_mode(serializer, self->mode); } -void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self) +void extract_mip_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_echo_control_response* self) { - extract_mip_aiding_aiding_echo_control_command_mode(serializer, &self->mode); + extract_mip_aiding_echo_control_command_mode(serializer, &self->mode); } -mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode) +mip_cmd_result mip_aiding_write_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode mode) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -302,13 +302,13 @@ mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_a insert_mip_function_selector(&serializer, MIP_FUNCTION_WRITE); - insert_mip_aiding_aiding_echo_control_command_mode(&serializer, mode); + insert_mip_aiding_echo_control_command_mode(&serializer, mode); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out) +mip_cmd_result mip_aiding_read_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode* mode_out) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -327,14 +327,14 @@ mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_ai microstrain_serializer_init_insertion(&deserializer, buffer, responseLength); assert(mode_out); - extract_mip_aiding_aiding_echo_control_command_mode(&deserializer, mode_out); + extract_mip_aiding_echo_control_command_mode(&deserializer, mode_out); if( microstrain_serializer_remaining(&deserializer) != 0 ) result = MIP_STATUS_ERROR; } return result; } -mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device) +mip_cmd_result mip_aiding_save_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -346,7 +346,7 @@ mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device) return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device) +mip_cmd_result mip_aiding_load_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -358,7 +358,7 @@ mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device) return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device) +mip_cmd_result mip_aiding_default_echo_control(mip_interface* device) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -370,7 +370,7 @@ mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device) return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_ECHO_CONTROL, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self) +void insert_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, const mip_aiding_pos_ecef_command* self) { insert_mip_time(serializer, &self->time); @@ -380,10 +380,10 @@ void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, cons insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_ecef_pos_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_pos_ecef_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self) +void extract_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, mip_aiding_pos_ecef_command* self) { extract_mip_time(serializer, &self->time); @@ -393,11 +393,11 @@ void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_ecef_pos_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_pos_ecef_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_pos_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_pos_ecef_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -416,13 +416,13 @@ mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_ecef_pos_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_pos_ecef_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self) +void insert_mip_aiding_pos_llh_command(microstrain_serializer* serializer, const mip_aiding_pos_llh_command* self) { insert_mip_time(serializer, &self->time); @@ -436,10 +436,10 @@ void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_llh_pos_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_pos_llh_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self) +void extract_mip_aiding_pos_llh_command(microstrain_serializer* serializer, mip_aiding_pos_llh_command* self) { extract_mip_time(serializer, &self->time); @@ -453,11 +453,11 @@ void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_ extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_llh_pos_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_pos_llh_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_pos_llh(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_pos_llh_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -478,13 +478,13 @@ mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, u for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_llh_pos_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_pos_llh_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self) +void insert_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, const mip_aiding_height_above_ellipsoid_command* self) { insert_mip_time(serializer, &self->time); @@ -497,7 +497,7 @@ void insert_mip_aiding_height_command(microstrain_serializer* serializer, const microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self) +void extract_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, mip_aiding_height_above_ellipsoid_command* self) { extract_mip_time(serializer, &self->time); @@ -511,7 +511,7 @@ void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_a } -mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) +mip_cmd_result mip_aiding_height_above_ellipsoid(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -530,9 +530,9 @@ mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, ui assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABS, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEIGHT_ABOVE_ELLIPSOID, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self) +void insert_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, const mip_aiding_vel_ecef_command* self) { insert_mip_time(serializer, &self->time); @@ -542,10 +542,10 @@ void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, cons insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_ecef_vel_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_vel_ecef_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self) +void extract_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, mip_aiding_vel_ecef_command* self) { extract_mip_time(serializer, &self->time); @@ -555,11 +555,11 @@ void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_ecef_vel_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_vel_ecef_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_vel_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ecef_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -578,13 +578,13 @@ mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_ecef_vel_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_vel_ecef_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ECEF, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self) +void insert_mip_aiding_vel_ned_command(microstrain_serializer* serializer, const mip_aiding_vel_ned_command* self) { insert_mip_time(serializer, &self->time); @@ -594,10 +594,10 @@ void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_ned_vel_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_vel_ned_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self) +void extract_mip_aiding_vel_ned_command(microstrain_serializer* serializer, mip_aiding_vel_ned_command* self) { extract_mip_time(serializer, &self->time); @@ -607,11 +607,11 @@ void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_ extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_ned_vel_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_vel_ned_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_vel_ned(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ned_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -630,13 +630,13 @@ mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, u for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_ned_vel_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_vel_ned_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self) +void insert_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, const mip_aiding_vel_body_frame_command* self) { insert_mip_time(serializer, &self->time); @@ -646,10 +646,10 @@ void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializ insert_mip_vector3f(serializer, self->uncertainty); - insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, self->valid_flags); + insert_mip_aiding_vel_body_frame_command_valid_flags(serializer, self->valid_flags); } -void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self) +void extract_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, mip_aiding_vel_body_frame_command* self) { extract_mip_time(serializer, &self->time); @@ -659,11 +659,11 @@ void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_seriali extract_mip_vector3f(serializer, self->uncertainty); - extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(serializer, &self->valid_flags); + extract_mip_aiding_vel_body_frame_command_valid_flags(serializer, &self->valid_flags); } -mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags) +mip_cmd_result mip_aiding_vel_body_frame(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_body_frame_command_valid_flags valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; @@ -682,13 +682,13 @@ mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, co for(unsigned int i=0; i < 3; i++) microstrain_insert_float(&serializer, uncertainty[i]); - insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(&serializer, valid_flags); + insert_mip_aiding_vel_body_frame_command_valid_flags(&serializer, valid_flags); assert(microstrain_serializer_is_ok(&serializer)); - return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_ODOM, buffer, (uint8_t)microstrain_serializer_length(&serializer)); + return mip_interface_run_command(device, MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_BODY_FRAME, buffer, (uint8_t)microstrain_serializer_length(&serializer)); } -void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self) +void insert_mip_aiding_heading_true_command(microstrain_serializer* serializer, const mip_aiding_heading_true_command* self) { insert_mip_time(serializer, &self->time); @@ -701,7 +701,7 @@ void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, microstrain_insert_u16(serializer, self->valid_flags); } -void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self) +void extract_mip_aiding_heading_true_command(microstrain_serializer* serializer, mip_aiding_heading_true_command* self) { extract_mip_time(serializer, &self->time); @@ -715,7 +715,7 @@ void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, } -mip_cmd_result mip_aiding_true_heading(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) +mip_cmd_result mip_aiding_heading_true(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags) { microstrain_serializer serializer; uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; diff --git a/src/c/mip/definitions/commands_aiding.h b/src/c/mip/definitions/commands_aiding.h index 8fde01071..760bda29b 100644 --- a/src/c/mip/definitions/commands_aiding.h +++ b/src/c/mip/definitions/commands_aiding.h @@ -29,29 +29,29 @@ extern "C" { enum { - MIP_AIDING_CMD_DESC_SET = 0x13, + MIP_AIDING_CMD_DESC_SET = 0x13, - MIP_CMD_DESC_AIDING_FRAME_CONFIG = 0x01, - MIP_CMD_DESC_AIDING_LOCAL_FRAME = 0x03, - MIP_CMD_DESC_AIDING_ECHO_CONTROL = 0x1F, - MIP_CMD_DESC_AIDING_POS_LOCAL = 0x20, - MIP_CMD_DESC_AIDING_POS_ECEF = 0x21, - MIP_CMD_DESC_AIDING_POS_LLH = 0x22, - MIP_CMD_DESC_AIDING_HEIGHT_ABS = 0x23, - MIP_CMD_DESC_AIDING_HEIGHT_REL = 0x24, - MIP_CMD_DESC_AIDING_VEL_ECEF = 0x28, - MIP_CMD_DESC_AIDING_VEL_NED = 0x29, - MIP_CMD_DESC_AIDING_VEL_ODOM = 0x2A, - MIP_CMD_DESC_AIDING_WHEELSPEED = 0x2B, - MIP_CMD_DESC_AIDING_HEADING_TRUE = 0x31, - MIP_CMD_DESC_AIDING_MAGNETIC_FIELD = 0x32, - MIP_CMD_DESC_AIDING_PRESSURE = 0x33, - MIP_CMD_DESC_AIDING_DELTA_POSITION = 0x38, - MIP_CMD_DESC_AIDING_DELTA_ATTITUDE = 0x39, - MIP_CMD_DESC_AIDING_LOCAL_ANGULAR_RATE = 0x3A, + MIP_CMD_DESC_AIDING_FRAME_CONFIG = 0x01, + MIP_CMD_DESC_AIDING_LOCAL_FRAME = 0x03, + MIP_CMD_DESC_AIDING_ECHO_CONTROL = 0x1F, + MIP_CMD_DESC_AIDING_POS_LOCAL = 0x20, + MIP_CMD_DESC_AIDING_POS_ECEF = 0x21, + MIP_CMD_DESC_AIDING_POS_LLH = 0x22, + MIP_CMD_DESC_AIDING_HEIGHT_ABOVE_ELLIPSOID = 0x23, + MIP_CMD_DESC_AIDING_HEIGHT_REL = 0x24, + MIP_CMD_DESC_AIDING_VEL_ECEF = 0x28, + MIP_CMD_DESC_AIDING_VEL_NED = 0x29, + MIP_CMD_DESC_AIDING_VEL_BODY_FRAME = 0x2A, + MIP_CMD_DESC_AIDING_WHEELSPEED = 0x2B, + MIP_CMD_DESC_AIDING_HEADING_TRUE = 0x31, + MIP_CMD_DESC_AIDING_MAGNETIC_FIELD = 0x32, + MIP_CMD_DESC_AIDING_PRESSURE = 0x33, + MIP_CMD_DESC_AIDING_DELTA_POSITION = 0x38, + MIP_CMD_DESC_AIDING_DELTA_ATTITUDE = 0x39, + MIP_CMD_DESC_AIDING_ANGULAR_RATE_LOCAL = 0x3A, - MIP_REPLY_DESC_AIDING_FRAME_CONFIG = 0x81, - MIP_REPLY_DESC_AIDING_ECHO_CONTROL = 0x9F, + MIP_REPLY_DESC_AIDING_FRAME_CONFIG = 0x81, + MIP_REPLY_DESC_AIDING_ECHO_CONTROL = 0x9F, }; //////////////////////////////////////////////////////////////////////////////// @@ -96,8 +96,9 @@ void extract_mip_time(microstrain_serializer* serializer, mip_time* self); //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_aiding_frame_config (0x13,0x01) Frame Config [C] -/// Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command -/// should mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame) +/// Defines an aiding frame associated with a specific sensor frame ID. +/// The frame ID used in this command should mirror the frame ID used in the aiding command +/// (if that aiding measurement is measured in this reference frame). /// /// This transform satisfies the following relationship: /// @@ -184,24 +185,24 @@ mip_cmd_result mip_aiding_default_frame_config(mip_interface* device, uint8_t fr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_aiding_echo_control (0x13,0x1F) Aiding Echo Control [C] +///@defgroup c_aiding_echo_control (0x13,0x1F) Echo Control [C] /// Controls command response behavior to external aiding commands /// ///@{ -enum mip_aiding_aiding_echo_control_command_mode +enum mip_aiding_echo_control_command_mode { - MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_SUPPRESS_ACK = 0, ///< Suppresses the usual command ack field for aiding messages. - MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_STANDARD = 1, ///< Normal ack/nack behavior. - MIP_AIDING_AIDING_ECHO_CONTROL_COMMAND_MODE_RESPONSE = 2, ///< Echo the data back as a response. + MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_SUPPRESS_ACK = 0, ///< Suppresses the usual command ack field for aiding messages. + MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_STANDARD = 1, ///< Normal ack/nack behavior. + MIP_AIDING_ECHO_CONTROL_COMMAND_MODE_RESPONSE = 2, ///< Echo the data back as a response. }; -typedef enum mip_aiding_aiding_echo_control_command_mode mip_aiding_aiding_echo_control_command_mode; +typedef enum mip_aiding_echo_control_command_mode mip_aiding_echo_control_command_mode; -static inline void insert_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command_mode self) +static inline void insert_mip_aiding_echo_control_command_mode(microstrain_serializer* serializer, const mip_aiding_echo_control_command_mode self) { microstrain_insert_u8(serializer, (uint8_t)(self)); } -static inline void extract_mip_aiding_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command_mode* self) +static inline void extract_mip_aiding_echo_control_command_mode(microstrain_serializer* serializer, mip_aiding_echo_control_command_mode* self) { uint8_t tmp = 0; microstrain_extract_u8(serializer, &tmp); @@ -209,50 +210,50 @@ static inline void extract_mip_aiding_aiding_echo_control_command_mode(microstra } -struct mip_aiding_aiding_echo_control_command +struct mip_aiding_echo_control_command { mip_function_selector function; - mip_aiding_aiding_echo_control_command_mode mode; ///< Controls data echoing. + mip_aiding_echo_control_command_mode mode; ///< Controls data echoing. }; -typedef struct mip_aiding_aiding_echo_control_command mip_aiding_aiding_echo_control_command; +typedef struct mip_aiding_echo_control_command mip_aiding_echo_control_command; -void insert_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_command* self); -void extract_mip_aiding_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_command* self); +void insert_mip_aiding_echo_control_command(microstrain_serializer* serializer, const mip_aiding_echo_control_command* self); +void extract_mip_aiding_echo_control_command(microstrain_serializer* serializer, mip_aiding_echo_control_command* self); -struct mip_aiding_aiding_echo_control_response +struct mip_aiding_echo_control_response { - mip_aiding_aiding_echo_control_command_mode mode; ///< Controls data echoing. + mip_aiding_echo_control_command_mode mode; ///< Controls data echoing. }; -typedef struct mip_aiding_aiding_echo_control_response mip_aiding_aiding_echo_control_response; +typedef struct mip_aiding_echo_control_response mip_aiding_echo_control_response; -void insert_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_aiding_echo_control_response* self); -void extract_mip_aiding_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_aiding_echo_control_response* self); +void insert_mip_aiding_echo_control_response(microstrain_serializer* serializer, const mip_aiding_echo_control_response* self); +void extract_mip_aiding_echo_control_response(microstrain_serializer* serializer, mip_aiding_echo_control_response* self); -mip_cmd_result mip_aiding_write_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode mode); -mip_cmd_result mip_aiding_read_aiding_echo_control(mip_interface* device, mip_aiding_aiding_echo_control_command_mode* mode_out); -mip_cmd_result mip_aiding_save_aiding_echo_control(mip_interface* device); -mip_cmd_result mip_aiding_load_aiding_echo_control(mip_interface* device); -mip_cmd_result mip_aiding_default_aiding_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_write_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode mode); +mip_cmd_result mip_aiding_read_echo_control(mip_interface* device, mip_aiding_echo_control_command_mode* mode_out); +mip_cmd_result mip_aiding_save_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_load_echo_control(mip_interface* device); +mip_cmd_result mip_aiding_default_echo_control(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_ecef_pos (0x13,0x21) Ecef Pos [C] +///@defgroup c_aiding_pos_ecef (0x13,0x21) Pos Ecef [C] /// Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system. /// ///@{ -typedef uint16_t mip_aiding_ecef_pos_command_valid_flags; -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_ecef_pos_command_valid_flags MIP_AIDING_ECEF_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command_valid_flags self) +typedef uint16_t mip_aiding_pos_ecef_command_valid_flags; +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_pos_ecef_command_valid_flags MIP_AIDING_POS_ECEF_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_pos_ecef_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_pos_ecef_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_pos_command_valid_flags* self) +static inline void extract_mip_aiding_pos_ecef_command_valid_flags(microstrain_serializer* serializer, mip_aiding_pos_ecef_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -260,41 +261,42 @@ static inline void extract_mip_aiding_ecef_pos_command_valid_flags(microstrain_s } -struct mip_aiding_ecef_pos_command +struct mip_aiding_pos_ecef_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3d position; ///< ECEF position [m]. mip_vector3f uncertainty; ///< ECEF position uncertainty [m]. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_ecef_pos_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_pos_ecef_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_ecef_pos_command mip_aiding_ecef_pos_command; +typedef struct mip_aiding_pos_ecef_command mip_aiding_pos_ecef_command; -void insert_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, const mip_aiding_ecef_pos_command* self); -void extract_mip_aiding_ecef_pos_command(microstrain_serializer* serializer, mip_aiding_ecef_pos_command* self); +void insert_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, const mip_aiding_pos_ecef_command* self); +void extract_mip_aiding_pos_ecef_command(microstrain_serializer* serializer, mip_aiding_pos_ecef_command* self); -mip_cmd_result mip_aiding_ecef_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_ecef_pos_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_pos_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const double* position, const float* uncertainty, mip_aiding_pos_ecef_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_llh_pos (0x13,0x22) Llh Pos [C] -/// Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. +///@defgroup c_aiding_pos_llh (0x13,0x22) Pos Llh [C] +/// Geodetic position aiding command. +/// Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. /// Uncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height. /// ///@{ -typedef uint16_t mip_aiding_llh_pos_command_valid_flags; -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_LATITUDE = 0x0001; ///< -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_LONGITUDE = 0x0002; ///< -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_HEIGHT = 0x0004; ///< -static const mip_aiding_llh_pos_command_valid_flags MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_llh_pos_command_valid_flags self) +typedef uint16_t mip_aiding_pos_llh_command_valid_flags; +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_LATITUDE = 0x0001; ///< +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_LONGITUDE = 0x0002; ///< +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_HEIGHT = 0x0004; ///< +static const mip_aiding_pos_llh_command_valid_flags MIP_AIDING_POS_LLH_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_pos_llh_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_pos_llh_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_serializer* serializer, mip_aiding_llh_pos_command_valid_flags* self) +static inline void extract_mip_aiding_pos_llh_command_valid_flags(microstrain_serializer* serializer, mip_aiding_pos_llh_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -302,7 +304,7 @@ static inline void extract_mip_aiding_llh_pos_command_valid_flags(microstrain_se } -struct mip_aiding_llh_pos_command +struct mip_aiding_pos_llh_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). @@ -310,24 +312,24 @@ struct mip_aiding_llh_pos_command double longitude; ///< [deg] double height; ///< [m] mip_vector3f uncertainty; ///< NED position uncertainty. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_llh_pos_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_pos_llh_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_llh_pos_command mip_aiding_llh_pos_command; +typedef struct mip_aiding_pos_llh_command mip_aiding_pos_llh_command; -void insert_mip_aiding_llh_pos_command(microstrain_serializer* serializer, const mip_aiding_llh_pos_command* self); -void extract_mip_aiding_llh_pos_command(microstrain_serializer* serializer, mip_aiding_llh_pos_command* self); +void insert_mip_aiding_pos_llh_command(microstrain_serializer* serializer, const mip_aiding_pos_llh_command* self); +void extract_mip_aiding_pos_llh_command(microstrain_serializer* serializer, mip_aiding_pos_llh_command* self); -mip_cmd_result mip_aiding_llh_pos(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_llh_pos_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_pos_llh(mip_interface* device, const mip_time* time, uint8_t frame_id, double latitude, double longitude, double height, const float* uncertainty, mip_aiding_pos_llh_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_height (0x13,0x23) Height [C] -/// Estimated value of height. +///@defgroup c_aiding_height_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [C] +/// Estimated value of the height above ellipsoid. /// ///@{ -struct mip_aiding_height_command +struct mip_aiding_height_above_ellipsoid_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). @@ -335,32 +337,32 @@ struct mip_aiding_height_command float uncertainty; ///< [m] uint16_t valid_flags; }; -typedef struct mip_aiding_height_command mip_aiding_height_command; +typedef struct mip_aiding_height_above_ellipsoid_command mip_aiding_height_above_ellipsoid_command; -void insert_mip_aiding_height_command(microstrain_serializer* serializer, const mip_aiding_height_command* self); -void extract_mip_aiding_height_command(microstrain_serializer* serializer, mip_aiding_height_command* self); +void insert_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, const mip_aiding_height_above_ellipsoid_command* self); +void extract_mip_aiding_height_above_ellipsoid_command(microstrain_serializer* serializer, mip_aiding_height_above_ellipsoid_command* self); -mip_cmd_result mip_aiding_height(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); +mip_cmd_result mip_aiding_height_above_ellipsoid(mip_interface* device, const mip_time* time, uint8_t frame_id, float height, float uncertainty, uint16_t valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_ecef_vel (0x13,0x28) Ecef Vel [C] +///@defgroup c_aiding_vel_ecef (0x13,0x28) Vel Ecef [C] /// ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame. /// ///@{ -typedef uint16_t mip_aiding_ecef_vel_command_valid_flags; -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_ecef_vel_command_valid_flags MIP_AIDING_ECEF_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command_valid_flags self) +typedef uint16_t mip_aiding_vel_ecef_command_valid_flags; +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_vel_ecef_command_valid_flags MIP_AIDING_VEL_ECEF_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_vel_ecef_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vel_ecef_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ecef_vel_command_valid_flags* self) +static inline void extract_mip_aiding_vel_ecef_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vel_ecef_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -368,40 +370,40 @@ static inline void extract_mip_aiding_ecef_vel_command_valid_flags(microstrain_s } -struct mip_aiding_ecef_vel_command +struct mip_aiding_vel_ecef_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3f velocity; ///< ECEF velocity [m/s]. mip_vector3f uncertainty; ///< ECEF velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_ecef_vel_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_vel_ecef_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_ecef_vel_command mip_aiding_ecef_vel_command; +typedef struct mip_aiding_vel_ecef_command mip_aiding_vel_ecef_command; -void insert_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, const mip_aiding_ecef_vel_command* self); -void extract_mip_aiding_ecef_vel_command(microstrain_serializer* serializer, mip_aiding_ecef_vel_command* self); +void insert_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, const mip_aiding_vel_ecef_command* self); +void extract_mip_aiding_vel_ecef_command(microstrain_serializer* serializer, mip_aiding_vel_ecef_command* self); -mip_cmd_result mip_aiding_ecef_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ecef_vel_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_vel_ecef(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ecef_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_ned_vel (0x13,0x29) Ned Vel [C] +///@defgroup c_aiding_vel_ned (0x13,0x29) Vel Ned [C] /// NED velocity aiding command. Coordinates are given in the local North-East-Down frame. /// ///@{ -typedef uint16_t mip_aiding_ned_vel_command_valid_flags; -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_ned_vel_command_valid_flags MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_ned_vel_command_valid_flags self) +typedef uint16_t mip_aiding_vel_ned_command_valid_flags; +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_vel_ned_command_valid_flags MIP_AIDING_VEL_NED_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_vel_ned_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vel_ned_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_serializer* serializer, mip_aiding_ned_vel_command_valid_flags* self) +static inline void extract_mip_aiding_vel_ned_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vel_ned_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -409,41 +411,40 @@ static inline void extract_mip_aiding_ned_vel_command_valid_flags(microstrain_se } -struct mip_aiding_ned_vel_command +struct mip_aiding_vel_ned_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3f velocity; ///< NED velocity [m/s]. mip_vector3f uncertainty; ///< NED velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_ned_vel_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_vel_ned_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_ned_vel_command mip_aiding_ned_vel_command; +typedef struct mip_aiding_vel_ned_command mip_aiding_vel_ned_command; -void insert_mip_aiding_ned_vel_command(microstrain_serializer* serializer, const mip_aiding_ned_vel_command* self); -void extract_mip_aiding_ned_vel_command(microstrain_serializer* serializer, mip_aiding_ned_vel_command* self); +void insert_mip_aiding_vel_ned_command(microstrain_serializer* serializer, const mip_aiding_vel_ned_command* self); +void extract_mip_aiding_vel_ned_command(microstrain_serializer* serializer, mip_aiding_vel_ned_command* self); -mip_cmd_result mip_aiding_ned_vel(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_ned_vel_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_vel_ned(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_ned_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_vehicle_fixed_frame_velocity (0x13,0x2A) Vehicle Fixed Frame Velocity [C] -/// Estimate of velocity of the vehicle in the frame associated -/// with the given sensor ID. +///@defgroup c_aiding_vel_body_frame (0x13,0x2A) Vel Body Frame [C] +/// Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame. /// ///@{ -typedef uint16_t mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags; -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_NONE = 0x0000; -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_X = 0x0001; ///< -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Y = 0x0002; ///< -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_Z = 0x0004; ///< -static const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags MIP_AIDING_VEHICLE_FIXED_FRAME_VELOCITY_COMMAND_VALID_FLAGS_ALL = 0x0007; -static inline void insert_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags self) +typedef uint16_t mip_aiding_vel_body_frame_command_valid_flags; +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_NONE = 0x0000; +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_X = 0x0001; ///< +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_Y = 0x0002; ///< +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_Z = 0x0004; ///< +static const mip_aiding_vel_body_frame_command_valid_flags MIP_AIDING_VEL_BODY_FRAME_COMMAND_VALID_FLAGS_ALL = 0x0007; +static inline void insert_mip_aiding_vel_body_frame_command_valid_flags(microstrain_serializer* serializer, const mip_aiding_vel_body_frame_command_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); } -static inline void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags* self) +static inline void extract_mip_aiding_vel_body_frame_command_valid_flags(microstrain_serializer* serializer, mip_aiding_vel_body_frame_command_valid_flags* self) { uint16_t tmp = 0; microstrain_extract_u16(serializer, &tmp); @@ -451,29 +452,29 @@ static inline void extract_mip_aiding_vehicle_fixed_frame_velocity_command_valid } -struct mip_aiding_vehicle_fixed_frame_velocity_command +struct mip_aiding_vel_body_frame_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). mip_vector3f velocity; ///< [m/s] mip_vector3f uncertainty; ///< [m/s] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0. - mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. + mip_aiding_vel_body_frame_command_valid_flags valid_flags; ///< Valid flags. Axes with 0 will be completely ignored. }; -typedef struct mip_aiding_vehicle_fixed_frame_velocity_command mip_aiding_vehicle_fixed_frame_velocity_command; +typedef struct mip_aiding_vel_body_frame_command mip_aiding_vel_body_frame_command; -void insert_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, const mip_aiding_vehicle_fixed_frame_velocity_command* self); -void extract_mip_aiding_vehicle_fixed_frame_velocity_command(microstrain_serializer* serializer, mip_aiding_vehicle_fixed_frame_velocity_command* self); +void insert_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, const mip_aiding_vel_body_frame_command* self); +void extract_mip_aiding_vel_body_frame_command(microstrain_serializer* serializer, mip_aiding_vel_body_frame_command* self); -mip_cmd_result mip_aiding_vehicle_fixed_frame_velocity(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vehicle_fixed_frame_velocity_command_valid_flags valid_flags); +mip_cmd_result mip_aiding_vel_body_frame(mip_interface* device, const mip_time* time, uint8_t frame_id, const float* velocity, const float* uncertainty, mip_aiding_vel_body_frame_command_valid_flags valid_flags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_true_heading (0x13,0x31) True Heading [C] +///@defgroup c_aiding_heading_true (0x13,0x31) Heading True [C] /// ///@{ -struct mip_aiding_true_heading_command +struct mip_aiding_heading_true_command { mip_time time; ///< Timestamp of the measurement. uint8_t frame_id; ///< Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate). @@ -481,12 +482,12 @@ struct mip_aiding_true_heading_command float uncertainty; ///< Cannot be 0 unless the valid flags are 0. uint16_t valid_flags; }; -typedef struct mip_aiding_true_heading_command mip_aiding_true_heading_command; +typedef struct mip_aiding_heading_true_command mip_aiding_heading_true_command; -void insert_mip_aiding_true_heading_command(microstrain_serializer* serializer, const mip_aiding_true_heading_command* self); -void extract_mip_aiding_true_heading_command(microstrain_serializer* serializer, mip_aiding_true_heading_command* self); +void insert_mip_aiding_heading_true_command(microstrain_serializer* serializer, const mip_aiding_heading_true_command* self); +void extract_mip_aiding_heading_true_command(microstrain_serializer* serializer, mip_aiding_heading_true_command* self); -mip_cmd_result mip_aiding_true_heading(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); +mip_cmd_result mip_aiding_heading_true(mip_interface* device, const mip_time* time, uint8_t frame_id, float heading, float uncertainty, uint16_t valid_flags); ///@} /// diff --git a/src/c/mip/definitions/commands_filter.h b/src/c/mip/definitions/commands_filter.h index 7c26898fd..7a8510e88 100644 --- a/src/c/mip/definitions/commands_filter.h +++ b/src/c/mip/definitions/commands_filter.h @@ -761,9 +761,13 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(mip_interface* device /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup c_filter_antenna_offset (0x0D,0x13) Antenna Offset [C] -/// Set the sensor to GNSS antenna offset. +/// Configure the GNSS antenna offset. /// -/// This is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. +/// For 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. +/// +/// For 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center. +/// +/// This command should also be used for CV7 / GV7-INS NMEA Input over GPIO. /// /// The magnitude of the offset vector is limited to 10 meters /// @@ -1879,7 +1883,7 @@ enum mip_filter_aiding_measurement_enable_command_aiding_source MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_HEADING = 5, ///< External heading input MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_ALTIMETER = 6, ///< External pressure altimeter input MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_MAGNETOMETER = 7, ///< External magnetomer input - MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_VEHICLE_FRAME_VEL = 8, ///< External vehicle frame velocity input + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_BODY_FRAME_VEL = 8, ///< External body frame velocity input MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_ALL = 65535, ///< Save/load/reset all options }; typedef enum mip_filter_aiding_measurement_enable_command_aiding_source mip_filter_aiding_measurement_enable_command_aiding_source; diff --git a/src/c/mip/definitions/commands_gnss.h b/src/c/mip/definitions/commands_gnss.h index 5713de72a..7ff3c7fe5 100644 --- a/src/c/mip/definitions/commands_gnss.h +++ b/src/c/mip/definitions/commands_gnss.h @@ -46,12 +46,15 @@ enum enum { MIP_GNSS_GPS_ENABLE_L1CA = 0x0001 }; enum { MIP_GNSS_GPS_ENABLE_L2C = 0x0002 }; +enum { MIP_GNSS_GPS_ENABLE_L5 = 0x0004 }; enum { MIP_GNSS_GLONASS_ENABLE_L1OF = 0x0001 }; enum { MIP_GNSS_GLONASS_ENABLE_L2OF = 0x0002 }; enum { MIP_GNSS_GALILEO_ENABLE_E1 = 0x0001 }; enum { MIP_GNSS_GALILEO_ENABLE_E5B = 0x0002 }; +enum { MIP_GNSS_GALILEO_ENABLE_E5A = 0x0004 }; enum { MIP_GNSS_BEIDOU_ENABLE_B1 = 0x0001 }; enum { MIP_GNSS_BEIDOU_ENABLE_B2 = 0x0002 }; +enum { MIP_GNSS_BEIDOU_ENABLE_B2A = 0x0004 }; //////////////////////////////////////////////////////////////////////////////// // Mip Fields @@ -102,10 +105,10 @@ mip_cmd_result mip_gnss_receiver_info(mip_interface* device, uint8_t* num_receiv struct mip_gnss_signal_configuration_command { mip_function_selector function; - uint8_t gps_enable; ///< Bitfield 0: Enable L1CA, 1: Enable L2C + uint8_t gps_enable; ///< Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5 uint8_t glonass_enable; ///< Bitfield 0: Enable L1OF, 1: Enable L2OF - uint8_t galileo_enable; ///< Bitfield 0: Enable E1, 1: Enable E5B - uint8_t beidou_enable; ///< Bitfield 0: Enable B1, 1: Enable B2 + uint8_t galileo_enable; ///< Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A + uint8_t beidou_enable; ///< Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A uint8_t reserved[4]; }; typedef struct mip_gnss_signal_configuration_command mip_gnss_signal_configuration_command; @@ -115,10 +118,10 @@ void extract_mip_gnss_signal_configuration_command(microstrain_serializer* seria struct mip_gnss_signal_configuration_response { - uint8_t gps_enable; ///< Bitfield 0: Enable L1CA, 1: Enable L2C + uint8_t gps_enable; ///< Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5 uint8_t glonass_enable; ///< Bitfield 0: Enable L1OF, 1: Enable L2OF - uint8_t galileo_enable; ///< Bitfield 0: Enable E1, 1: Enable E5B - uint8_t beidou_enable; ///< Bitfield 0: Enable B1, 1: Enable B2 + uint8_t galileo_enable; ///< Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A + uint8_t beidou_enable; ///< Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A uint8_t reserved[4]; }; typedef struct mip_gnss_signal_configuration_response mip_gnss_signal_configuration_response; diff --git a/src/c/mip/definitions/data_filter.h b/src/c/mip/definitions/data_filter.h index 9b3de23bb..96c0890f6 100644 --- a/src/c/mip/definitions/data_filter.h +++ b/src/c/mip/definitions/data_filter.h @@ -188,18 +188,21 @@ static inline void extract_mip_filter_status_flags(microstrain_serializer* seria enum mip_filter_aiding_measurement_type { - MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_DUAL_ANTENNA = 2, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING = 3, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_PRESSURE = 4, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_MAGNETOMETER = 5, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_SPEED = 6, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_ECEF = 33, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_POS_LLH = 34, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_ECEF = 40, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_NED = 41, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_VEL_VEHICLE_FRAME = 42, ///< - MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING_TRUE = 49, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_GNSS = 1, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_DUAL_ANTENNA = 2, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_HEADING = 3, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_PRESSURE = 4, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_MAGNETOMETER = 5, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_SPEED = 6, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_POS_ECEF = 33, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_POS_LLH = 34, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_HEIGHT_ABOVE_ELLIPSOID = 35, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_ECEF = 40, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_NED = 41, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_VEL_BODY_FRAME = 42, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_HEADING_TRUE = 49, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_MAGNETIC_FIELD = 50, ///< + MIP_FILTER_AIDING_MEASUREMENT_TYPE_AIDING_PRESSURE = 51, ///< }; typedef enum mip_filter_aiding_measurement_type mip_filter_aiding_measurement_type; diff --git a/src/cpp/mip/definitions/commands_3dm.hpp b/src/cpp/mip/definitions/commands_3dm.hpp index 0243505f5..8a335d16e 100644 --- a/src/cpp/mip/definitions/commands_3dm.hpp +++ b/src/cpp/mip/definitions/commands_3dm.hpp @@ -153,8 +153,8 @@ struct NmeaMessage VTG = 5, ///< Course over Ground. Source can be the Filter or GNSS1/2 datasets. HDT = 6, ///< Heading, True. Source can be the Filter or GNSS1/2 datasets. ZDA = 7, ///< Time & Date. Source must be the GNSS1 or GNSS2 datasets. - PKRA = 129, ///< Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. - PKRR = 130, ///< Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. + MSRA = 129, ///< MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED. + MSRR = 130, ///< MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED. }; enum class TalkerID : uint8_t @@ -3291,7 +3291,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t /// /// The values for this offset are determined empirically by external software algorithms /// based on calibration data taken after the device is installed in its application. These values -/// can be obtained and set by using the LORD "MIP Iron Calibration" application. +/// can be obtained and set by using Microstrain software tools. /// Alternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run. /// The offset is applied to the scaled magnetometer vector prior to output. /// @@ -3375,7 +3375,7 @@ TypedResult defaultMagHardIronOffset(C::mip_interface& device /// /// The values for this matrix are determined empirically by external software algorithms /// based on calibration data taken after the device is installed in its application. These values -/// can be obtained and set by using the LORD "MIP Iron Calibration" application. +/// can be obtained and set by using Microstrain software tools. /// Alternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run. /// The matrix is applied to the scaled magnetometer vector prior to output. /// diff --git a/src/cpp/mip/definitions/commands_aiding.cpp b/src/cpp/mip/definitions/commands_aiding.cpp index 7a80059a0..6168a4014 100644 --- a/src/cpp/mip/definitions/commands_aiding.cpp +++ b/src/cpp/mip/definitions/commands_aiding.cpp @@ -252,7 +252,7 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); } -void AidingEchoControl::insert(Serializer& serializer) const +void EchoControl::insert(Serializer& serializer) const { serializer.insert(function); @@ -262,7 +262,7 @@ void AidingEchoControl::insert(Serializer& serializer) const } } -void AidingEchoControl::extract(Serializer& serializer) +void EchoControl::extract(Serializer& serializer) { serializer.extract(function); @@ -273,18 +273,18 @@ void AidingEchoControl::extract(Serializer& serializer) } } -void AidingEchoControl::Response::insert(Serializer& serializer) const +void EchoControl::Response::insert(Serializer& serializer) const { serializer.insert(mode); } -void AidingEchoControl::Response::extract(Serializer& serializer) +void EchoControl::Response::extract(Serializer& serializer) { serializer.extract(mode); } -TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode) +TypedResult writeEchoControl(C::mip_interface& device, EchoControl::Mode mode) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -296,7 +296,7 @@ TypedResult writeAidingEchoControl(C::mip_interface& device, return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut) +TypedResult readEchoControl(C::mip_interface& device, EchoControl::Mode* modeOut) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -305,7 +305,7 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -319,7 +319,7 @@ TypedResult readAidingEchoControl(C::mip_interface& device, A } return result; } -TypedResult saveAidingEchoControl(C::mip_interface& device) +TypedResult saveEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -329,7 +329,7 @@ TypedResult saveAidingEchoControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -TypedResult loadAidingEchoControl(C::mip_interface& device) +TypedResult loadEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -339,7 +339,7 @@ TypedResult loadAidingEchoControl(C::mip_interface& device) return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -TypedResult defaultAidingEchoControl(C::mip_interface& device) +TypedResult defaultEchoControl(C::mip_interface& device) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -349,7 +349,7 @@ TypedResult defaultAidingEchoControl(C::mip_interface& device return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); } -void EcefPos::insert(Serializer& serializer) const +void PosEcef::insert(Serializer& serializer) const { serializer.insert(time); @@ -362,7 +362,7 @@ void EcefPos::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void EcefPos::extract(Serializer& serializer) +void PosEcef::extract(Serializer& serializer) { serializer.extract(time); @@ -376,7 +376,7 @@ void EcefPos::extract(Serializer& serializer) } -TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags) +TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, PosEcef::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -399,7 +399,7 @@ TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)serializer.length()); } -void LlhPos::insert(Serializer& serializer) const +void PosLlh::insert(Serializer& serializer) const { serializer.insert(time); @@ -416,7 +416,7 @@ void LlhPos::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void LlhPos::extract(Serializer& serializer) +void PosLlh::extract(Serializer& serializer) { serializer.extract(time); @@ -434,7 +434,7 @@ void LlhPos::extract(Serializer& serializer) } -TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags) +TypedResult posLlh(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, PosLlh::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -459,7 +459,7 @@ TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)serializer.length()); } -void Height::insert(Serializer& serializer) const +void HeightAboveEllipsoid::insert(Serializer& serializer) const { serializer.insert(time); @@ -472,7 +472,7 @@ void Height::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void Height::extract(Serializer& serializer) +void HeightAboveEllipsoid::extract(Serializer& serializer) { serializer.extract(time); @@ -486,7 +486,7 @@ void Height::extract(Serializer& serializer) } -TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) +TypedResult heightAboveEllipsoid(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -503,9 +503,9 @@ TypedResult height(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABOVE_ELLIPSOID, buffer, (uint8_t)serializer.length()); } -void EcefVel::insert(Serializer& serializer) const +void VelEcef::insert(Serializer& serializer) const { serializer.insert(time); @@ -518,7 +518,7 @@ void EcefVel::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void EcefVel::extract(Serializer& serializer) +void VelEcef::extract(Serializer& serializer) { serializer.extract(time); @@ -532,7 +532,7 @@ void EcefVel::extract(Serializer& serializer) } -TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags) +TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelEcef::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -555,7 +555,7 @@ TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)serializer.length()); } -void NedVel::insert(Serializer& serializer) const +void VelNed::insert(Serializer& serializer) const { serializer.insert(time); @@ -568,7 +568,7 @@ void NedVel::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void NedVel::extract(Serializer& serializer) +void VelNed::extract(Serializer& serializer) { serializer.extract(time); @@ -582,7 +582,7 @@ void NedVel::extract(Serializer& serializer) } -TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags) +TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelNed::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -605,7 +605,7 @@ TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t f return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)serializer.length()); } -void VehicleFixedFrameVelocity::insert(Serializer& serializer) const +void VelBodyFrame::insert(Serializer& serializer) const { serializer.insert(time); @@ -618,7 +618,7 @@ void VehicleFixedFrameVelocity::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void VehicleFixedFrameVelocity::extract(Serializer& serializer) +void VelBodyFrame::extract(Serializer& serializer) { serializer.extract(time); @@ -632,7 +632,7 @@ void VehicleFixedFrameVelocity::extract(Serializer& serializer) } -TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags) +TypedResult velBodyFrame(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelBodyFrame::ValidFlags validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); @@ -653,9 +653,9 @@ TypedResult vehicleFixedFrameVelocity(C::mip_interfac assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ODOM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_BODY_FRAME, buffer, (uint8_t)serializer.length()); } -void TrueHeading::insert(Serializer& serializer) const +void HeadingTrue::insert(Serializer& serializer) const { serializer.insert(time); @@ -668,7 +668,7 @@ void TrueHeading::insert(Serializer& serializer) const serializer.insert(valid_flags); } -void TrueHeading::extract(Serializer& serializer) +void HeadingTrue::extract(Serializer& serializer) { serializer.extract(time); @@ -682,7 +682,7 @@ void TrueHeading::extract(Serializer& serializer) } -TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) +TypedResult headingTrue(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags) { uint8_t buffer[MIP_FIELD_PAYLOAD_LENGTH_MAX]; Serializer serializer(buffer, sizeof(buffer)); diff --git a/src/cpp/mip/definitions/commands_aiding.hpp b/src/cpp/mip/definitions/commands_aiding.hpp index d09ed6a77..827981656 100644 --- a/src/cpp/mip/definitions/commands_aiding.hpp +++ b/src/cpp/mip/definitions/commands_aiding.hpp @@ -28,29 +28,29 @@ namespace commands_aiding { enum { - DESCRIPTOR_SET = 0x13, - - CMD_FRAME_CONFIG = 0x01, - CMD_LOCAL_FRAME = 0x03, - CMD_ECHO_CONTROL = 0x1F, - CMD_POS_LOCAL = 0x20, - CMD_POS_ECEF = 0x21, - CMD_POS_LLH = 0x22, - CMD_HEIGHT_ABS = 0x23, - CMD_HEIGHT_REL = 0x24, - CMD_VEL_ECEF = 0x28, - CMD_VEL_NED = 0x29, - CMD_VEL_ODOM = 0x2A, - CMD_WHEELSPEED = 0x2B, - CMD_HEADING_TRUE = 0x31, - CMD_MAGNETIC_FIELD = 0x32, - CMD_PRESSURE = 0x33, - CMD_DELTA_POSITION = 0x38, - CMD_DELTA_ATTITUDE = 0x39, - CMD_LOCAL_ANGULAR_RATE = 0x3A, - - REPLY_FRAME_CONFIG = 0x81, - REPLY_ECHO_CONTROL = 0x9F, + DESCRIPTOR_SET = 0x13, + + CMD_FRAME_CONFIG = 0x01, + CMD_LOCAL_FRAME = 0x03, + CMD_ECHO_CONTROL = 0x1F, + CMD_POS_LOCAL = 0x20, + CMD_POS_ECEF = 0x21, + CMD_POS_LLH = 0x22, + CMD_HEIGHT_ABOVE_ELLIPSOID = 0x23, + CMD_HEIGHT_REL = 0x24, + CMD_VEL_ECEF = 0x28, + CMD_VEL_NED = 0x29, + CMD_VEL_BODY_FRAME = 0x2A, + CMD_WHEELSPEED = 0x2B, + CMD_HEADING_TRUE = 0x31, + CMD_MAGNETIC_FIELD = 0x32, + CMD_PRESSURE = 0x33, + CMD_DELTA_POSITION = 0x38, + CMD_DELTA_ATTITUDE = 0x39, + CMD_ANGULAR_RATE_LOCAL = 0x3A, + + REPLY_FRAME_CONFIG = 0x81, + REPLY_ECHO_CONTROL = 0x9F, }; //////////////////////////////////////////////////////////////////////////////// @@ -83,8 +83,9 @@ struct Time //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_aiding_frame_config (0x13,0x01) Frame Config [CPP] -/// Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command -/// should mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame) +/// Defines an aiding frame associated with a specific sensor frame ID. +/// The frame ID used in this command should mirror the frame ID used in the aiding command +/// (if that aiding measurement is measured in this reference frame). /// /// This transform satisfies the following relationship: /// @@ -205,12 +206,12 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_aiding_echo_control (0x13,0x1F) Aiding Echo Control [CPP] +///@defgroup cpp_aiding_echo_control (0x13,0x1F) Echo Control [CPP] /// Controls command response behavior to external aiding commands /// ///@{ -struct AidingEchoControl +struct EchoControl { enum class Mode : uint8_t { @@ -227,7 +228,7 @@ struct AidingEchoControl static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_ECHO_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "AidingEchoControl"; + static constexpr const char* NAME = "EchoControl"; static constexpr const char* DOC_NAME = "Aiding Command Echo Control"; static constexpr const bool HAS_FUNCTION_SELECTOR = true; @@ -241,9 +242,9 @@ struct AidingEchoControl return std::make_tuple(std::ref(mode)); } - static AidingEchoControl create_sld_all(::mip::FunctionSelector function) + static EchoControl create_sld_all(::mip::FunctionSelector function) { - AidingEchoControl cmd; + EchoControl cmd; cmd.function = function; return cmd; } @@ -261,7 +262,7 @@ struct AidingEchoControl static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::REPLY_ECHO_CONTROL; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "AidingEchoControl::Response"; + static constexpr const char* NAME = "EchoControl::Response"; static constexpr const char* DOC_NAME = "Aiding Command Echo Control Response"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -281,21 +282,21 @@ struct AidingEchoControl }; }; -TypedResult writeAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode mode); -TypedResult readAidingEchoControl(C::mip_interface& device, AidingEchoControl::Mode* modeOut); -TypedResult saveAidingEchoControl(C::mip_interface& device); -TypedResult loadAidingEchoControl(C::mip_interface& device); -TypedResult defaultAidingEchoControl(C::mip_interface& device); +TypedResult writeEchoControl(C::mip_interface& device, EchoControl::Mode mode); +TypedResult readEchoControl(C::mip_interface& device, EchoControl::Mode* modeOut); +TypedResult saveEchoControl(C::mip_interface& device); +TypedResult loadEchoControl(C::mip_interface& device); +TypedResult defaultEchoControl(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_ecef_pos (0x13,0x21) Ecef Pos [CPP] +///@defgroup cpp_aiding_pos_ecef (0x13,0x21) Pos Ecef [CPP] /// Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system. /// ///@{ -struct EcefPos +struct PosEcef { struct ValidFlags : Bitfield { @@ -338,7 +339,7 @@ struct EcefPos static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_POS_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "EcefPos"; + static constexpr const char* NAME = "PosEcef"; static constexpr const char* DOC_NAME = "ECEF Position"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -358,18 +359,19 @@ struct EcefPos typedef void Response; }; -TypedResult ecefPos(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, EcefPos::ValidFlags validFlags); +TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const double* position, const float* uncertainty, PosEcef::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_llh_pos (0x13,0x22) Llh Pos [CPP] -/// Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. +///@defgroup cpp_aiding_pos_llh (0x13,0x22) Pos Llh [CPP] +/// Geodetic position aiding command. +/// Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. /// Uncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height. /// ///@{ -struct LlhPos +struct PosLlh { struct ValidFlags : Bitfield { @@ -414,7 +416,7 @@ struct LlhPos static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_POS_LLH; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "LlhPos"; + static constexpr const char* NAME = "PosLlh"; static constexpr const char* DOC_NAME = "LLH Position"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -434,17 +436,17 @@ struct LlhPos typedef void Response; }; -TypedResult llhPos(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, LlhPos::ValidFlags validFlags); +TypedResult posLlh(C::mip_interface& device, const Time& time, uint8_t frameId, double latitude, double longitude, double height, const float* uncertainty, PosLlh::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_height (0x13,0x23) Height [CPP] -/// Estimated value of height. +///@defgroup cpp_aiding_height_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [CPP] +/// Estimated value of the height above ellipsoid. /// ///@{ -struct Height +struct HeightAboveEllipsoid { /// Parameters Time time; ///< Timestamp of the measurement. @@ -455,10 +457,10 @@ struct Height /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEIGHT_ABS; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEIGHT_ABOVE_ELLIPSOID; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "Height"; - static constexpr const char* DOC_NAME = "Height"; + static constexpr const char* NAME = "HeightAboveEllipsoid"; + static constexpr const char* DOC_NAME = "Height Above Ellipsoid"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; auto asTuple() const @@ -477,17 +479,17 @@ struct Height typedef void Response; }; -TypedResult height(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags); +TypedResult heightAboveEllipsoid(C::mip_interface& device, const Time& time, uint8_t frameId, float height, float uncertainty, uint16_t validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_ecef_vel (0x13,0x28) Ecef Vel [CPP] +///@defgroup cpp_aiding_vel_ecef (0x13,0x28) Vel Ecef [CPP] /// ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame. /// ///@{ -struct EcefVel +struct VelEcef { struct ValidFlags : Bitfield { @@ -530,7 +532,7 @@ struct EcefVel static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_ECEF; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "EcefVel"; + static constexpr const char* NAME = "VelEcef"; static constexpr const char* DOC_NAME = "ECEF Velocity"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -550,17 +552,17 @@ struct EcefVel typedef void Response; }; -TypedResult ecefVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, EcefVel::ValidFlags validFlags); +TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelEcef::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_ned_vel (0x13,0x29) Ned Vel [CPP] +///@defgroup cpp_aiding_vel_ned (0x13,0x29) Vel Ned [CPP] /// NED velocity aiding command. Coordinates are given in the local North-East-Down frame. /// ///@{ -struct NedVel +struct VelNed { struct ValidFlags : Bitfield { @@ -603,7 +605,7 @@ struct NedVel static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_NED; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "NedVel"; + static constexpr const char* NAME = "VelNed"; static constexpr const char* DOC_NAME = "NED Velocity"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -623,18 +625,17 @@ struct NedVel typedef void Response; }; -TypedResult nedVel(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, NedVel::ValidFlags validFlags); +TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelNed::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_vehicle_fixed_frame_velocity (0x13,0x2A) Vehicle Fixed Frame Velocity [CPP] -/// Estimate of velocity of the vehicle in the frame associated -/// with the given sensor ID. +///@defgroup cpp_aiding_vel_body_frame (0x13,0x2A) Vel Body Frame [CPP] +/// Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame. /// ///@{ -struct VehicleFixedFrameVelocity +struct VelBodyFrame { struct ValidFlags : Bitfield { @@ -675,10 +676,10 @@ struct VehicleFixedFrameVelocity /// Descriptors static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; - static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_ODOM; + static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_VEL_BODY_FRAME; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "VehicleFixedFrameVelocity"; - static constexpr const char* DOC_NAME = "Vehicle Frame Velocity"; + static constexpr const char* NAME = "VelBodyFrame"; + static constexpr const char* DOC_NAME = "Body Frame Velocity"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; auto asTuple() const @@ -697,16 +698,16 @@ struct VehicleFixedFrameVelocity typedef void Response; }; -TypedResult vehicleFixedFrameVelocity(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VehicleFixedFrameVelocity::ValidFlags validFlags); +TypedResult velBodyFrame(C::mip_interface& device, const Time& time, uint8_t frameId, const float* velocity, const float* uncertainty, VelBodyFrame::ValidFlags validFlags); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_true_heading (0x13,0x31) True Heading [CPP] +///@defgroup cpp_aiding_heading_true (0x13,0x31) Heading True [CPP] /// ///@{ -struct TrueHeading +struct HeadingTrue { /// Parameters Time time; ///< Timestamp of the measurement. @@ -719,7 +720,7 @@ struct TrueHeading static constexpr const uint8_t DESCRIPTOR_SET = ::mip::commands_aiding::DESCRIPTOR_SET; static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::commands_aiding::CMD_HEADING_TRUE; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; - static constexpr const char* NAME = "TrueHeading"; + static constexpr const char* NAME = "HeadingTrue"; static constexpr const char* DOC_NAME = "True Heading"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; @@ -739,7 +740,7 @@ struct TrueHeading typedef void Response; }; -TypedResult trueHeading(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); +TypedResult headingTrue(C::mip_interface& device, const Time& time, uint8_t frameId, float heading, float uncertainty, uint16_t validFlags); ///@} /// diff --git a/src/cpp/mip/definitions/commands_filter.hpp b/src/cpp/mip/definitions/commands_filter.hpp index 7eb355be8..1a62baeee 100644 --- a/src/cpp/mip/definitions/commands_filter.hpp +++ b/src/cpp/mip/definitions/commands_filter.hpp @@ -1162,9 +1162,13 @@ TypedResult defaultSensorToVehicleOffset(C::mip_interface /// //////////////////////////////////////////////////////////////////////////////// ///@defgroup cpp_filter_antenna_offset (0x0D,0x13) Antenna Offset [CPP] -/// Set the sensor to GNSS antenna offset. +/// Configure the GNSS antenna offset. /// -/// This is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. +/// For 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. +/// +/// For 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center. +/// +/// This command should also be used for CV7 / GV7-INS NMEA Input over GPIO. /// /// The magnitude of the offset vector is limited to 10 meters /// @@ -3385,7 +3389,7 @@ struct AidingMeasurementEnable EXTERNAL_HEADING = 5, ///< External heading input EXTERNAL_ALTIMETER = 6, ///< External pressure altimeter input EXTERNAL_MAGNETOMETER = 7, ///< External magnetomer input - VEHICLE_FRAME_VEL = 8, ///< External vehicle frame velocity input + BODY_FRAME_VEL = 8, ///< External body frame velocity input ALL = 65535, ///< Save/load/reset all options }; diff --git a/src/cpp/mip/definitions/commands_gnss.hpp b/src/cpp/mip/definitions/commands_gnss.hpp index 6af23e2ae..9d01cd366 100644 --- a/src/cpp/mip/definitions/commands_gnss.hpp +++ b/src/cpp/mip/definitions/commands_gnss.hpp @@ -45,12 +45,15 @@ enum static constexpr const uint16_t GNSS_GPS_ENABLE_L1CA = 0x0001; static constexpr const uint16_t GNSS_GPS_ENABLE_L2C = 0x0002; +static constexpr const uint16_t GNSS_GPS_ENABLE_L5 = 0x0004; static constexpr const uint16_t GNSS_GLONASS_ENABLE_L1OF = 0x0001; static constexpr const uint16_t GNSS_GLONASS_ENABLE_L2OF = 0x0002; static constexpr const uint16_t GNSS_GALILEO_ENABLE_E1 = 0x0001; static constexpr const uint16_t GNSS_GALILEO_ENABLE_E5B = 0x0002; +static constexpr const uint16_t GNSS_GALILEO_ENABLE_E5A = 0x0004; static constexpr const uint16_t GNSS_BEIDOU_ENABLE_B1 = 0x0001; static constexpr const uint16_t GNSS_BEIDOU_ENABLE_B2 = 0x0002; +static constexpr const uint16_t GNSS_BEIDOU_ENABLE_B2A = 0x0004; //////////////////////////////////////////////////////////////////////////////// // Mip Fields @@ -144,10 +147,10 @@ struct SignalConfiguration { /// Parameters FunctionSelector function = static_cast(0); - uint8_t gps_enable = 0; ///< Bitfield 0: Enable L1CA, 1: Enable L2C + uint8_t gps_enable = 0; ///< Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5 uint8_t glonass_enable = 0; ///< Bitfield 0: Enable L1OF, 1: Enable L2OF - uint8_t galileo_enable = 0; ///< Bitfield 0: Enable E1, 1: Enable E5B - uint8_t beidou_enable = 0; ///< Bitfield 0: Enable B1, 1: Enable B2 + uint8_t galileo_enable = 0; ///< Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A + uint8_t beidou_enable = 0; ///< Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A uint8_t reserved[4] = {0}; /// Descriptors @@ -182,10 +185,10 @@ struct SignalConfiguration struct Response { /// Parameters - uint8_t gps_enable = 0; ///< Bitfield 0: Enable L1CA, 1: Enable L2C + uint8_t gps_enable = 0; ///< Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5 uint8_t glonass_enable = 0; ///< Bitfield 0: Enable L1OF, 1: Enable L2OF - uint8_t galileo_enable = 0; ///< Bitfield 0: Enable E1, 1: Enable E5B - uint8_t beidou_enable = 0; ///< Bitfield 0: Enable B1, 1: Enable B2 + uint8_t galileo_enable = 0; ///< Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A + uint8_t beidou_enable = 0; ///< Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A uint8_t reserved[4] = {0}; /// Descriptors diff --git a/src/cpp/mip/definitions/data_filter.hpp b/src/cpp/mip/definitions/data_filter.hpp index 2edfc45f1..f2ef29d4c 100644 --- a/src/cpp/mip/definitions/data_filter.hpp +++ b/src/cpp/mip/definitions/data_filter.hpp @@ -226,18 +226,21 @@ struct FilterStatusFlags : Bitfield }; enum class FilterAidingMeasurementType : uint8_t { - GNSS = 1, ///< - DUAL_ANTENNA = 2, ///< - HEADING = 3, ///< - PRESSURE = 4, ///< - MAGNETOMETER = 5, ///< - SPEED = 6, ///< - POS_ECEF = 33, ///< - POS_LLH = 34, ///< - VEL_ECEF = 40, ///< - VEL_NED = 41, ///< - VEL_VEHICLE_FRAME = 42, ///< - HEADING_TRUE = 49, ///< + GNSS = 1, ///< + DUAL_ANTENNA = 2, ///< + HEADING = 3, ///< + PRESSURE = 4, ///< + MAGNETOMETER = 5, ///< + SPEED = 6, ///< + AIDING_POS_ECEF = 33, ///< + AIDING_POS_LLH = 34, ///< + AIDING_HEIGHT_ABOVE_ELLIPSOID = 35, ///< + AIDING_VEL_ECEF = 40, ///< + AIDING_VEL_NED = 41, ///< + AIDING_VEL_BODY_FRAME = 42, ///< + AIDING_HEADING_TRUE = 49, ///< + AIDING_MAGNETIC_FIELD = 50, ///< + AIDING_PRESSURE = 51, ///< }; struct FilterMeasurementIndicator : Bitfield diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index df5f7dd75..5205ee054 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -751,8 +751,8 @@ struct MetadataFor { 5, "VTG", "Course over Ground. Source can be the Filter or GNSS1/2 datasets." }, { 6, "HDT", "Heading, True. Source can be the Filter or GNSS1/2 datasets." }, { 7, "ZDA", "Time & Date. Source must be the GNSS1 or GNSS2 datasets." }, - { 129, "PKRA", "Parker proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED." }, - { 130, "PKRR", "Parker proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED." }, + { 129, "MSRA", "MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED." }, + { 130, "MSRR", "MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED." }, }; static constexpr inline EnumInfo value = { @@ -3632,7 +3632,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagHardIronOffset", /* .title = */ "Magnetometer Hard Iron Offset", - /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", + /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using Microstrain software tools.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3691,7 +3691,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagSoftIronMatrix", /* .title = */ "Magnetometer Soft Iron Matrix", - /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \begin{bmatrix} 0 & 1 & 2 \\ 3 & 4 & 5 \\ 6 & 7 & 8 \end{bmatrix} EQEND\n", + /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using Microstrain software tools.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \\begin{bmatrix} 0 & 1 & 2 \\\ 3 & 4 & 5 \\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3963,7 +3963,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformDcm", /* .title = */ "Sensor to Vehicle Frame Transformation Direction Cosine Matrix", - /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.\n\nThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
\nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
\n\nWhere:
\n\nEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND\nThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not\nbe exactly equal to array used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", + /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.\n\nThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
\nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
\n\nWhere:
\n\nEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND\nThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not\nbe exactly equal to array used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, diff --git a/src/cpp/mip/metadata/definitions/commands_aiding.hpp b/src/cpp/mip/metadata/definitions/commands_aiding.hpp index 7c289a55d..a0f98d3d1 100644 --- a/src/cpp/mip/metadata/definitions/commands_aiding.hpp +++ b/src/cpp/mip/metadata/definitions/commands_aiding.hpp @@ -185,7 +185,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_aiding::FrameConfig", /* .title = */ "Frame Configuration", - /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID. The frame ID used in this command\nshould mirror the frame ID used in the aiding command (if that aiding measurement is measured in this reference frame)\n\nThis transform satisfies the following relationship:\n\nEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
\n\nWhere:
\nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

\nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
\nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
\n\nRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element\nin the rotation vector is ignored and should be set to 0.\n\nWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.\n\nExample: GNSS antenna lever arm\n\nFrame ID: 1\nFormat: 1 (Euler)\nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)\nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)\n", + /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID.\nThe frame ID used in this command should mirror the frame ID used in the aiding command\n(if that aiding measurement is measured in this reference frame).\n\nThis transform satisfies the following relationship:\n\nEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
\n\nWhere:
\nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

\nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
\nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
\n\nRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element\nin the rotation vector is ignored and should be set to 0.\n\nWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.\n\nExample: GNSS antenna lever arm\n\nFrame ID: 1\nFormat: 1 (Euler)\nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)\nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -195,9 +195,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::AidingEchoControl::Mode; + using type = commands_aiding::EchoControl::Mode; static constexpr inline EnumInfo::Entry entries[] = { { 0, "SUPPRESS_ACK", "Suppresses the usual command ack field for aiding messages." }, @@ -215,16 +215,16 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::AidingEchoControl::Response; + using type = commands_aiding::EchoControl::Response; static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "mode", /* .docs = */ "Controls data echoing.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -232,7 +232,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::AidingEchoControl::Response", + /* .name = */ "commands_aiding::EchoControl::Response", /* .title = */ "None", /* .docs = */ "", /* .parameters = */ parameters, @@ -244,17 +244,17 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::AidingEchoControl; + using type = commands_aiding::EchoControl; static constexpr inline ParameterInfo parameters[] = { FUNCTION_SELECTOR_PARAM, { /* .name = */ "mode", /* .docs = */ "Controls data echoing.", - /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::ENUM, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -262,7 +262,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::AidingEchoControl", + /* .name = */ "commands_aiding::EchoControl", /* .title = */ "Aiding Command Echo Control", /* .docs = */ "Controls command response behavior to external aiding commands", /* .parameters = */ parameters, @@ -337,9 +337,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EcefPos::ValidFlags; + using type = commands_aiding::PosEcef::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -357,9 +357,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EcefPos; + using type = commands_aiding::PosEcef; static constexpr inline ParameterInfo parameters[] = { { @@ -401,8 +401,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -410,7 +410,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::EcefPos", + /* .name = */ "commands_aiding::PosEcef", /* .title = */ "ECEF Position", /* .docs = */ "Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system.", /* .parameters = */ parameters, @@ -422,9 +422,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::LlhPos::ValidFlags; + using type = commands_aiding::PosLlh::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "Latitude", "" }, @@ -442,9 +442,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::LlhPos; + using type = commands_aiding::PosLlh; static constexpr inline ParameterInfo parameters[] = { { @@ -504,8 +504,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -513,9 +513,9 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::LlhPos", + /* .name = */ "commands_aiding::PosLlh", /* .title = */ "LLH Position", - /* .docs = */ "Geodetic position aiding command. Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid.\nUncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height.", + /* .docs = */ "Geodetic position aiding command.\nCoordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid.\nUncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -525,9 +525,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::Height; + using type = commands_aiding::HeightAboveEllipsoid; static constexpr inline ParameterInfo parameters[] = { { @@ -578,9 +578,9 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::Height", - /* .title = */ "Height", - /* .docs = */ "Estimated value of height.", + /* .name = */ "commands_aiding::HeightAboveEllipsoid", + /* .title = */ "Height Above Ellipsoid", + /* .docs = */ "Estimated value of the height above ellipsoid.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -590,9 +590,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EcefVel::ValidFlags; + using type = commands_aiding::VelEcef::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -610,9 +610,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::EcefVel; + using type = commands_aiding::VelEcef; static constexpr inline ParameterInfo parameters[] = { { @@ -654,8 +654,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -663,7 +663,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::EcefVel", + /* .name = */ "commands_aiding::VelEcef", /* .title = */ "ECEF Velocity", /* .docs = */ "ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame.", /* .parameters = */ parameters, @@ -675,9 +675,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::NedVel::ValidFlags; + using type = commands_aiding::VelNed::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -695,9 +695,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::NedVel; + using type = commands_aiding::VelNed; static constexpr inline ParameterInfo parameters[] = { { @@ -739,8 +739,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -748,7 +748,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::NedVel", + /* .name = */ "commands_aiding::VelNed", /* .title = */ "NED Velocity", /* .docs = */ "NED velocity aiding command. Coordinates are given in the local North-East-Down frame.", /* .parameters = */ parameters, @@ -760,9 +760,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VehicleFixedFrameVelocity::ValidFlags; + using type = commands_aiding::VelBodyFrame::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { { 1, "X", "" }, @@ -780,9 +780,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::VehicleFixedFrameVelocity; + using type = commands_aiding::VelBodyFrame; static constexpr inline ParameterInfo parameters[] = { { @@ -824,8 +824,8 @@ struct MetadataFor { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, /* .count = */ 1, /* .condition = */ {}, @@ -833,9 +833,9 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::VehicleFixedFrameVelocity", - /* .title = */ "Vehicle Frame Velocity", - /* .docs = */ "Estimate of velocity of the vehicle in the frame associated\nwith the given sensor ID.", + /* .name = */ "commands_aiding::VelBodyFrame", + /* .title = */ "Body Frame Velocity", + /* .docs = */ "Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -845,9 +845,9 @@ struct MetadataFor }; template<> -struct MetadataFor +struct MetadataFor { - using type = commands_aiding::TrueHeading; + using type = commands_aiding::HeadingTrue; static constexpr inline ParameterInfo parameters[] = { { @@ -898,7 +898,7 @@ struct MetadataFor }; static constexpr inline FieldInfo value = { - /* .name = */ "commands_aiding::TrueHeading", + /* .name = */ "commands_aiding::HeadingTrue", /* .title = */ "True Heading", /* .docs = */ "", /* .parameters = */ parameters, @@ -1063,15 +1063,15 @@ struct MetadataFor static constexpr inline std::initializer_list ALL_COMMANDS_AIDING = { &MetadataFor::value, &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, - &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, + &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, }; diff --git a/src/cpp/mip/metadata/definitions/commands_filter.hpp b/src/cpp/mip/metadata/definitions/commands_filter.hpp index 00e1db970..0dba5bcd6 100644 --- a/src/cpp/mip/metadata/definitions/commands_filter.hpp +++ b/src/cpp/mip/metadata/definitions/commands_filter.hpp @@ -665,7 +665,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationDcm", /* .title = */ "Sensor to Vehicle Frame Rotation DCM", - /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \begin{bmatrix} 0 & 1 & 2\\ 3 & 4 & 5\\ 6 & 7 & 8 \end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \\begin{bmatrix} 0 & 1 & 2\\\ 3 & 4 & 5\\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -724,7 +724,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationQuaternion", /* .title = */ "Sensor to Vehicle Frame Rotation Quaternion", - /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.\n\nNote: This is the rotation, the inverse of the transformation.\nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may not\nbe equivalent in value to the quaternion used to set the rotation, due to normalization.
\n
\nQuaternion element definition:

\n
\nEQSTART Q_{SEN}^{VEH} = \begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \end{bmatrix} EQEND\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.\n\nNote: This is the rotation, the inverse of the transformation.\nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may not\nbe equivalent in value to the quaternion used to set the rotation, due to normalization.
\n
\nQuaternion element definition:

\n
\nEQSTART Q_{SEN}^{VEH} = \\begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \\end{bmatrix} EQEND\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -842,7 +842,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AntennaOffset", /* .title = */ "GNSS Antenna Offset Control", - /* .docs = */ "Set the sensor to GNSS antenna offset.\n\nThis is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.\n\nThe magnitude of the offset vector is limited to 10 meters\n", + /* .docs = */ "Configure the GNSS antenna offset.\n\nFor 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.\n\nFor 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center.\n\nThis command should also be used for CV7 / GV7-INS NMEA Input over GPIO.\n\nThe magnitude of the offset vector is limited to 10 meters\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -2870,7 +2870,7 @@ struct MetadataFor { 5, "EXTERNAL_HEADING", "External heading input" }, { 6, "EXTERNAL_ALTIMETER", "External pressure altimeter input" }, { 7, "EXTERNAL_MAGNETOMETER", "External magnetomer input" }, - { 8, "VEHICLE_FRAME_VEL", "External vehicle frame velocity input" }, + { 8, "BODY_FRAME_VEL", "External body frame velocity input" }, { 65535, "ALL", "Save/load/reset all options" }, }; diff --git a/src/cpp/mip/metadata/definitions/commands_gnss.hpp b/src/cpp/mip/metadata/definitions/commands_gnss.hpp index dbfdecfba..5d0d1139c 100644 --- a/src/cpp/mip/metadata/definitions/commands_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/commands_gnss.hpp @@ -116,7 +116,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "gps_enable", - /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C", + /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -134,7 +134,7 @@ struct MetadataFor }, { /* .name = */ "galileo_enable", - /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B", + /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -143,7 +143,7 @@ struct MetadataFor }, { /* .name = */ "beidou_enable", - /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2", + /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -182,7 +182,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "gps_enable", - /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C", + /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -200,7 +200,7 @@ struct MetadataFor }, { /* .name = */ "galileo_enable", - /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B", + /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -209,7 +209,7 @@ struct MetadataFor }, { /* .name = */ "beidou_enable", - /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2", + /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, diff --git a/src/cpp/mip/metadata/definitions/data_filter.hpp b/src/cpp/mip/metadata/definitions/data_filter.hpp index 58ba47315..f50c4e187 100644 --- a/src/cpp/mip/metadata/definitions/data_filter.hpp +++ b/src/cpp/mip/metadata/definitions/data_filter.hpp @@ -189,7 +189,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AttitudeDcm", /* .title = */ "None", - /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, @@ -2431,12 +2431,15 @@ struct MetadataFor { 4, "PRESSURE", "" }, { 5, "MAGNETOMETER", "" }, { 6, "SPEED", "" }, - { 33, "POS_ECEF", "" }, - { 34, "POS_LLH", "" }, - { 40, "VEL_ECEF", "" }, - { 41, "VEL_NED", "" }, - { 42, "VEL_VEHICLE_FRAME", "" }, - { 49, "HEADING_TRUE", "" }, + { 33, "AIDING_POS_ECEF", "" }, + { 34, "AIDING_POS_LLH", "" }, + { 35, "AIDING_HEIGHT_ABOVE_ELLIPSOID", "" }, + { 40, "AIDING_VEL_ECEF", "" }, + { 41, "AIDING_VEL_NED", "" }, + { 42, "AIDING_VEL_BODY_FRAME", "" }, + { 49, "AIDING_HEADING_TRUE", "" }, + { 50, "AIDING_MAGNETIC_FIELD", "" }, + { 51, "AIDING_PRESSURE", "" }, }; static constexpr inline EnumInfo value = { diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index cf7d8052c..727311874 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -320,7 +320,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::CompOrientationMatrix", /* .title = */ "Complementary Filter Orientation Matrix", - /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND", + /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ NO_FUNCTIONS, From a419e3adaf0fa5a8a78783cd6f4f3ddb02c3f3e5 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 15:49:49 -0400 Subject: [PATCH 079/147] - Update includes in examples. --- examples/CV7/CV7_example.c | 2 +- examples/CX5_GX5_45/CX5_GX5_45_example.c | 2 +- examples/GQ7/GQ7_example.c | 2 +- examples/example_utils.cpp | 2 +- examples/watch_imu.c | 20 +++----------------- examples/watch_imu.cpp | 5 ----- 6 files changed, 7 insertions(+), 26 deletions(-) diff --git a/examples/CV7/CV7_example.c b/examples/CV7/CV7_example.c index f39aa25a8..55370977b 100644 --- a/examples/CV7/CV7_example.c +++ b/examples/CV7/CV7_example.c @@ -28,7 +28,7 @@ //////////////////////////////////////////////////////////////////////////////// #include -#include "microstrain/connections/serial/serial_port.h" +#include #include #include #include diff --git a/examples/CX5_GX5_45/CX5_GX5_45_example.c b/examples/CX5_GX5_45/CX5_GX5_45_example.c index c544cb818..7d1a33fb1 100644 --- a/examples/CX5_GX5_45/CX5_GX5_45_example.c +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.c @@ -28,7 +28,7 @@ //////////////////////////////////////////////////////////////////////////////// #include -#include "microstrain/connections/serial/serial_port.h" +#include #include #include #include diff --git a/examples/GQ7/GQ7_example.c b/examples/GQ7/GQ7_example.c index b2fc479d4..39bac16f2 100644 --- a/examples/GQ7/GQ7_example.c +++ b/examples/GQ7/GQ7_example.c @@ -28,7 +28,7 @@ //////////////////////////////////////////////////////////////////////////////// #include -#include "microstrain/connections/serial/serial_port.h" +#include #include #include #include diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index 6bd5264fe..05e8bb4da 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -3,7 +3,7 @@ #include -#include "microstrain/common/logging.h" +#include #include "example_utils.hpp" diff --git a/examples/watch_imu.c b/examples/watch_imu.c index 2280a9f87..1416c4d3c 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -1,34 +1,20 @@ #include -#include #include -#include -#include -#include "microstrain/common/logging.h" -#include "microstrain/common/serialization.h" +#include +#include -#include "mip/mip_descriptors.h" #include #include #include -#include "microstrain/connections/serial/serial_port.h" - -#include "microstrain/common/logging.h" - #include #include -#include #include -#include -#include -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WIN32 #else #include -#include -#include -#include #endif serial_port port; diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index 41bed2956..b933f7a7f 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -1,14 +1,9 @@ #include "example_utils.hpp" -#include -#include -#include "microstrain/common/serialization.hpp" - #include #include #include -#include #include #include From 5b7d47fa55010a4e6a53e94816a975f0d09e4fe1 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 18:14:43 -0400 Subject: [PATCH 080/147] - Address a bunch of PR comments. --- CMakeLists.txt | 4 +- README.md | 24 ++- cmake/check_metadata.cmake | 38 ++-- examples/CMakeLists.txt | 43 ++--- src/c/microstrain/common/CMakeLists.txt | 18 +- src/c/microstrain/common/serialization.h | 182 ------------------ src/c/microstrain/connections/CMakeLists.txt | 5 - .../connections/serial/CMakeLists.txt | 7 +- .../connections/tcp/CMakeLists.txt | 7 +- src/c/mip/CMakeLists.txt | 3 - src/c/mip/mip_dispatch.h | 32 +-- src/c/mip/mip_field.h | 2 +- src/c/mip/mip_interface.h | 2 +- src/c/mip/mip_parser.h | 2 +- src/c/mip/mip_serialization.c | 4 +- src/c/mip/mip_serialization.h | 2 +- src/cpp/microstrain/common/platform.hpp | 10 +- src/cpp/microstrain/common/serialization.hpp | 5 - .../common/serialization/serializer.hpp | 12 +- .../microstrain/connections/connection.hpp | 5 +- .../connections/serial/serial_connection.cpp | 4 +- .../connections/tcp/tcp_connection.cpp | 6 +- .../connections/tcp/tcp_connection.hpp | 10 +- src/cpp/mip/definitions/common.hpp | 4 - src/cpp/mip/metadata/mip_all_definitions.hpp | 10 +- src/cpp/mip/mip_interface.hpp | 4 +- src/cpp/mip/mip_serialization.hpp | 3 +- test/CMakeLists.txt | 7 - 28 files changed, 127 insertions(+), 328 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f32a7fe14..de3959ec4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -379,8 +379,8 @@ endif() if(BUILD_PACKAGE) # NOTE: CPack requires all these variables to be set before importing the module. Do not move them after the include(CPack) line set(CPACK_GENERATOR "${FOUND_CPACK_GENERATORS}") - set(CPACK_PACKAGE_VENDOR "Parker Hanifin") - set(CPACK_PACKAGE_CONTACT "Rob Fisher ") + set(CPACK_PACKAGE_VENDOR "MicroStrain by HBK") + set(CPACK_PACKAGE_CONTACT "MicroStrain Support ") set(CPACK_COMPONENTS_ALL "mip") set(CPACK_PACKAGE_VERSION ${MIP_GIT_VERSION_CLEAN}) diff --git a/README.md b/README.md index 1a33574f1..efdaa9fa2 100644 --- a/README.md +++ b/README.md @@ -79,7 +79,7 @@ See the documentation page for [Command Results](https://lord-microstrain.github In order to implement command timeouts and provide time of arrival information, this library requires applications to provide the time of received data. The time must be provided as an unsigned integral value with a reasonable precision, typically milliseconds since program startup. By default the timestamp type is set to `uint64_t`, but some embedded -applications may which to change this to `uint32_t` via the `MICROSTRAIN_TIMESTAMP_TYPE` define. Note that wraparound is +applications may wish to change this to `uint32_t` via the `MICROSTRAIN_TIMESTAMP_TYPE` define. Note that wraparound is permissible if the wraparound period is longer than twice the longest timeout used by the application. See the documentation page for [Timestamps](https://lord-microstrain.github.io/mip_sdk_documentation/latest/timestamps.html). @@ -114,11 +114,11 @@ How to Build * A working C compiler * C11 or later required -* A working C++ compiler, if using any C++ features. +* A working C++ compiler, if using any C++ features * Define `MICROSTRAIN_ENABLE_CPP=OFF` if you don't want to use any C++. Note that some features are only available in C++. * C++11 or later required for the mip library * C++14 or later for the examples - * C++20 or later for metadata and associated examples. + * C++20 or later for metadata and associated examples * CMake version 3.10 or later (technically this is optional, see below) * Doxygen, if building documentation @@ -129,7 +129,7 @@ The following options may be specified when configuring the build with CMake (e. * MICROSTRAIN_ENABLE_TCP - Builds the included socket library (default enabled). * MICROSTRAIN_ENABLE_LOGGING - Builds logging functionality into the library. The user is responsible for configuring a logging callback (default enabled) * MICROSTRAIN_LOGGING_MAX_LEVEL - Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration. Useful if you want some logs, but do not want the overhead compiled into the code. -* MICROSTRAIN_TIMESTAMP_TYPE - Overrides the default timestamp type. See the timestamps section in the documentation. +* MICROSTRAIN_TIMESTAMP_TYPE - Overrides the default timestamp type. See [Timestamps](https://lord-microstrain.github.io/mip_sdk_documentation/latest/timestamps.html) in the documentation. * MICROSTRAIN_ENABLE_CPP - Causes the src/cpp directory to be included in the build (default enabled). Disable to turn off the C++ api. * MIP_ENABLE_EXTRAS - Builds some higher level utility classes and functions that may use dynamic memory. * MIP_ENABLE_DIAGNOSTICS - Adds some counters to various entities which can serve as a debugging aid. @@ -156,10 +156,18 @@ If your target platform doesn't support CMake, you can build the project without include all the necessary files and define a few options. #### Minimum Required Files for building without CMake -* Everything in `src/mip/definitions` (or at least all the descriptor sets you require) -* All the .c, .h, .cpp, and .hpp files in `src/mip` (exclude the c++ files if you're using plain C) -* The `byte_ring` and `serialization` .c/.h files in `src/mip/utils` -* You may optionally include the platform-related connection files (`serial_port.h/.c`) as desired. +##### C only +* All source files in `src/c/microstrain/common`, except logging.c if logging is disabled +* Source files in `src/c/microstrain/connections` for your required connection types +* All source files in `src/c/mip` and `src/c/mip/utils` +* All source files in `src/c/mip/definitions` (or at least all the required descriptor sets) +##### C++ +* The C files indicated above, except those in `definitions` (they can be added too but aren't required) +* Source files in `src/cpp/microstrain/connections` for your required connection types +* All source files in `src/cpp/microstrain` +* All source files in `src/cpp/mip/definitions` (or at least the required descriptor sets) +* Source files in `src/cpp/mip/extras` as needed for your project +* Source files in `src/cpp/mip/metadata` if using metadata #### Required #defines for building without CMake diff --git a/cmake/check_metadata.cmake b/cmake/check_metadata.cmake index 621e73d7b..9ed17af9c 100644 --- a/cmake/check_metadata.cmake +++ b/cmake/check_metadata.cmake @@ -1,21 +1,25 @@ -include(CheckCXXSourceCompiles) +#include(CheckCXXSourceCompiles) -check_cxx_source_compiles(" -#include +#check_cxx_source_compiles(" +##include +# +#struct Foo +#{ +# int i = 0; +# const char* s = nullptr; +#}; +# +#static inline constexpr Foo foo = {5, \"12345\"}; +# +#int main() +#{ +# static_assert(foo.i == 5 && foo.s != nullptr, \"foo has wrong value\"); +# return 0; +#} +# +#" MIP_COMPILER_SUPPORTS_METADATA) -struct Foo -{ - int i = 0; - const char* s = nullptr; -}; +include(CheckIncludeFileCXX) -static inline constexpr Foo foo = {5, \"12345\"}; - -int main() -{ - static_assert(foo.i == 5 && foo.s != nullptr, \"foo has wrong value\"); - return 0; -} - -" MIP_COMPILER_SUPPORTS_METADATA) +CHECK_INCLUDE_FILE_CXX("span" MIP_COMPILER_SUPPORTS_METADATA) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index a403e3ea5..d8fe59d64 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -53,30 +53,27 @@ macro(add_mip_example name sources) endmacro() # C++ examples need either serial or TCP support -if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) - - if(MICROSTRAIN_ENABLE_CPP) - - # Generic examples - add_mip_example(DeviceInfo "${EXAMPLE_DIR}/device_info.cpp") - add_mip_example(WatchImu "${EXAMPLE_DIR}/watch_imu.cpp") - add_mip_example(Threads "${EXAMPLE_DIR}/threading.cpp") - if(UNIX) - target_link_libraries(Threads PUBLIC pthread) - endif() - if(MIP_ENABLE_METADATA) - add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") - target_link_libraries(CsvExample PRIVATE mip_metadata) - endif() - - # Product-specific examples - add_mip_example(GQ7_Example "${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") - add_mip_example(CV7_Example "${EXAMPLE_DIR}/CV7/CV7_example.cpp") - add_mip_example(CV7_INS_Simple_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_example.cpp") - add_mip_example(CV7_INS_Simple_Ublox_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_ublox_example.cpp") - add_mip_example(CX5_GX5_45_Example "${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.cpp") - add_mip_example(CX5_GX5_CV5_15_25_Example "${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp") +if(MICROSTRAIN_ENABLE_CPP AND (MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP)) + + # Generic examples + add_mip_example(DeviceInfo "${EXAMPLE_DIR}/device_info.cpp") + add_mip_example(WatchImu "${EXAMPLE_DIR}/watch_imu.cpp") + add_mip_example(Threads "${EXAMPLE_DIR}/threading.cpp") + if(UNIX) + target_link_libraries(Threads PUBLIC pthread) endif() + if(MIP_ENABLE_METADATA) + add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") + target_link_libraries(CsvExample PRIVATE mip_metadata) + endif() + + # Product-specific examples + add_mip_example(GQ7_Example "${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") + add_mip_example(CV7_Example "${EXAMPLE_DIR}/CV7/CV7_example.cpp") + add_mip_example(CV7_INS_Simple_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_example.cpp") + add_mip_example(CV7_INS_Simple_Ublox_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_ublox_example.cpp") + add_mip_example(CX5_GX5_45_Example "${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.cpp") + add_mip_example(CX5_GX5_CV5_15_25_Example "${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp") endif() diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index cfa8901b6..eb22dbeff 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -3,27 +3,25 @@ set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any call to logging functions with a higher level than this will be compiled out.") set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") - -set(SOURCES - logging.h - platform.h - serialization.c - serialization.h +add_library(microstrain_common + "logging.h" + "platform.h" + "serialization.c" + "serialization.h" ) -add_library(microstrain_common ${SOURCES}) target_compile_features(microstrain_common PUBLIC c_std_11) -target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") # TODO rename +target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") # Logging is a little weird since we need to install the header no matter what if(MICROSTRAIN_ENABLE_LOGGING) if(MICROSTRAIN_LOGGING_MAX_LEVEL STREQUAL "") message(FATAL_ERROR "MICROSTRAIN_LOGGING_MAX_LEVEL must be MICROSTRAIN_LOG_LEVEL_* or a number") endif() - target_sources(microstrain_common PRIVATE "../../../c/microstrain/common/logging.c") + target_sources(microstrain_common PRIVATE "${CMAKE_CURRENT_LIST_DIR}/logging.c") message("MicroStrain logging is enabled. Max level = '${MICROSTRAIN_LOGGING_MAX_LEVEL}'") - target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") # TODO rename + target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") endif() target_include_directories(microstrain_common INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) diff --git a/src/c/microstrain/common/serialization.h b/src/c/microstrain/common/serialization.h index bc99f80e4..eab5cf224 100644 --- a/src/c/microstrain/common/serialization.h +++ b/src/c/microstrain/common/serialization.h @@ -1,9 +1,5 @@ #pragma once -//#include "mip/mip_field.h" -//#include "mip/mip_packet.h" -//#include "mip/mip_types.h" - #include #include #include @@ -102,184 +98,6 @@ void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* coun #ifdef __cplusplus } // extern "C" } // namespace C - - - -#if 0 - -//////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_cpp -///@{ - -//////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_serialization_cpp -/// -///@brief (De)serialization in C++. -/// -/// There are two overloaded functions defined in the mip namespace, insert and -/// extract. The signature for each is as follows: -///@code{.cpp} -/// void mip::insert(Buffer& serializer, Type value); -/// voie mip::extract(Buffer& serializer, Type value); -///@endcode -/// Where `Type` is a struct or numeric type. -/// -/// There are overloads for all of the MIP definition types: -///@li Command, response, and data fields -///@li Enums, bitfields, and nested structs for commands -/// -/// Additionally, there are overloads with a different signature which allow -/// one to avoid creating a Buffer object every time. These overloads -/// create a serializer internally and pass it on to the regular version. -///@code{.cpp} -/// template bool mip::insert(const T& value, uint8_t* buffer, size_t bufferSize); -/// template bool mip::Field::extract(T& value); -///@endcode -/// This makes it easy to extract data from a field: -///@code{.cpp} -/// data_sensor::ScaledAccel accel; -/// MipField field(...); -/// if( field.extract(accel) ) -/// { -/// // Do something with accel data -/// printf("Accel X=%f\n", accel.scaled_accel[0]); -/// } -///@endcode -/// -///@{ - -//////////////////////////////////////////////////////////////////////////////// -///@brief Serialization class. -/// -class Buffer : public C::microstrain_serializer -{ -public: - // Buffer(C::mip_packet_view& packet, uint8_t newFieldDescriptor) { C::microstrain_serializer_init_new_field(this, &packet, newFieldDescriptor); } - Buffer(uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_insertion(this, buffer, size); this->_offset = offset; } - Buffer(const uint8_t* buffer, size_t size, size_t offset=0) { C::microstrain_serializer_init_extraction(this, const_cast(buffer), size); this->_offset = offset; } - - size_t capacity() const { return C::microstrain_serializer_capacity(this); } - size_t length() const { return C::microstrain_serializer_length(this); } - int remaining() const { return C::microstrain_serializer_remaining(this); } - - bool isOk() const { return C::microstrain_serializer_is_ok(this); } - bool isComplete() const { return C::microstrain_serializer_is_complete(this); } - - operator const void*() const { return isOk() ? this : nullptr; } - bool operator!() const { return !isOk(); } -}; - - - -inline void insert(Buffer& serializer, bool value) { return C::microstrain_insert_bool(&serializer, value); } -inline void insert(Buffer& serializer, char value) { return C::microstrain_insert_char(&serializer, value); } -inline void insert(Buffer& serializer, uint8_t value) { return C::microstrain_insert_u8(&serializer, value); } -inline void insert(Buffer& serializer, uint16_t value) { return C::microstrain_insert_u16(&serializer, value); } -inline void insert(Buffer& serializer, uint32_t value) { return C::microstrain_insert_u32(&serializer, value); } -inline void insert(Buffer& serializer, uint64_t value) { return C::microstrain_insert_u64(&serializer, value); } -inline void insert(Buffer& serializer, int8_t value) { return C::microstrain_insert_s8(&serializer, value); } -inline void insert(Buffer& serializer, int16_t value) { return C::microstrain_insert_s16(&serializer, value); } -inline void insert(Buffer& serializer, int32_t value) { return C::microstrain_insert_s32(&serializer, value); } -inline void insert(Buffer& serializer, int64_t value) { return C::microstrain_insert_s64(&serializer, value); } -inline void insert(Buffer& serializer, float value) { return C::microstrain_insert_float(&serializer, value); } -inline void insert(Buffer& serializer, double value) { return C::microstrain_insert_double(&serializer, value); } - -//////////////////////////////////////////////////////////////////////////////// -///@brief Inserts an enum into the buffer. -/// -///@tparam Enum The type of the enum to serialize. Must be a c++ typed enum. -/// -///@param serializer The serialization instance. -///@param value The enum to insert. -/// -template -typename std::enable_if< std::is_enum::value, void>::type -/*void*/ insert(Buffer& serializer, Enum value) { return insert(serializer, static_cast< typename std::underlying_type::type >(value) ); } - -//////////////////////////////////////////////////////////////////////////////// -///@brief Insert the given value into the buffer. -/// -/// If the buffer has insufficient space, this function returns false and the -/// contents of buffer may be partially modified. -/// -///@param value Value to insert. -///@param buffer Buffer to udpate with the value. -///@param bufferSize Size of the buffer. -///@param offset Starting offset into the buffer. -/// -///@returns true if sufficient space was available, false otherwise. -/// -template -bool insert(const T& value, uint8_t* buffer, size_t bufferSize, size_t offset=0) -{ - ::microstrain::Buffer serializer(buffer, bufferSize, offset); - insert(serializer, value); - return !!serializer; -} - -inline void extract(Buffer& serializer, bool& value) { return C::microstrain_extract_bool(&serializer, &value); } -inline void extract(Buffer& serializer, char& value) { return C::microstrain_extract_char(&serializer, &value); } -inline void extract(Buffer& serializer, uint8_t& value) { return C::microstrain_extract_u8(&serializer, &value); } -inline void extract(Buffer& serializer, uint16_t& value) { return C::microstrain_extract_u16(&serializer, &value); } -inline void extract(Buffer& serializer, uint32_t& value) { return C::microstrain_extract_u32(&serializer, &value); } -inline void extract(Buffer& serializer, uint64_t& value) { return C::microstrain_extract_u64(&serializer, &value); } -inline void extract(Buffer& serializer, int8_t& value) { return C::microstrain_extract_s8(&serializer, &value); } -inline void extract(Buffer& serializer, int16_t& value) { return C::microstrain_extract_s16(&serializer, &value); } -inline void extract(Buffer& serializer, int32_t& value) { return C::microstrain_extract_s32(&serializer, &value); } -inline void extract(Buffer& serializer, int64_t& value) { return C::microstrain_extract_s64(&serializer, &value); } -inline void extract(Buffer& serializer, float& value) { return C::microstrain_extract_float(&serializer, &value); } -inline void extract(Buffer& serializer, double& value) { return C::microstrain_extract_double(&serializer, &value); } - -//////////////////////////////////////////////////////////////////////////////// -///@brief Extract an enum from the buffer. -/// -///@tparam Enum The type of the enum to deserialize. Must be a c++ typed enum. -/// -///@param serializer The serialization instance. -///@param[out] value The enum to populate. -/// -template -typename std::enable_if< std::is_enum::value, void>::type -/*void*/ extract(Buffer& serializer, Enum& value) { - typename std::underlying_type::type tmp; - extract(serializer, tmp); - value = static_cast(tmp); -} - -//////////////////////////////////////////////////////////////////////////////// -///@brief Extract the value given a buffer, size, and starting offset. -/// -///@param[out] value_out -/// This parameter will be filled with the extracted value. -///@param buffer -/// A pointer to the raw data. -///@param bufferSize -/// Length of the buffer, or the relevant data within the buffer. -///@param offset -/// Start reading from this offset in the buffer. Default 0. -///@param exact_size -/// If true, exactly bufferSize bytes must be used in order for the return -/// value to be true. -/// -///@returns True if the extraction was successful, false otherwise. "Success" -/// means the supplied data was sufficient. If exact_size is true, then -/// this function only returns true if exactly bufferSize bytes were -/// consumed. -/// -template -bool extract(T& value_out, const uint8_t* buffer, size_t bufferSize, size_t offset=0, bool exact_size=false) -{ - ::microstrain::Buffer serializer(buffer, bufferSize, offset); - extract(serializer, value_out); - return exact_size ? serializer.isComplete() : serializer.isOk(); -} - -///@} -///@} -//////////////////////////////////////////////////////////////////////////////// - -#endif // 0 - } // namespace microstrain #endif // __cplusplus diff --git a/src/c/microstrain/connections/CMakeLists.txt b/src/c/microstrain/connections/CMakeLists.txt index 5a1143190..cf2e19efa 100644 --- a/src/c/microstrain/connections/CMakeLists.txt +++ b/src/c/microstrain/connections/CMakeLists.txt @@ -1,9 +1,4 @@ - -#option(MICROSTRAIN_ENABLE_SERIAL "Build serial connection support into the library and examples" ON) -#option(MICROSTRAIN_ENABLE_TCP "Build TCP connection support into the library and exampels" ON) - - if(MICROSTRAIN_ENABLE_SERIAL) add_subdirectory(serial) endif() diff --git a/src/c/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt index cb2926e35..68be9d772 100644 --- a/src/c/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -1,10 +1,9 @@ -set(SOURCES - serial_port.h - serial_port.c +add_library(microstrain_serial + "serial_port.h" + "serial_port.c" ) -add_library(microstrain_serial ${SOURCES}) target_compile_features(microstrain_serial PUBLIC c_std_11) target_include_directories(microstrain_serial INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) diff --git a/src/c/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt index b9721f3da..95d298077 100644 --- a/src/c/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -1,10 +1,9 @@ -set(SOURCES - tcp_socket.h - tcp_socket.c +add_library(microstrain_socket + "tcp_socket.h" + "tcp_socket.c" ) -add_library(microstrain_socket ${SOURCES}) target_compile_features(microstrain_socket PUBLIC c_std_11) target_include_directories(microstrain_socket INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index 54774a823..c9f916dc2 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -1,7 +1,4 @@ - -#option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) - set(MIP_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") set(MIP_SOURCES diff --git a/src/c/mip/mip_dispatch.h b/src/c/mip/mip_dispatch.h index 37fe6978c..5af7350ed 100644 --- a/src/c/mip/mip_dispatch.h +++ b/src/c/mip/mip_dispatch.h @@ -36,7 +36,7 @@ extern "C" { ///@param packet The MIP packet triggering this callback. ///@param timestamp The approximate parse time of the packet. /// -typedef void (*mip_dispatch_packet_callback)(void *context, const mip_packet_view *packet, mip_timestamp timestamp); +typedef void (*mip_dispatch_packet_callback)(void* context, const mip_packet_view* packet, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// ///@brief Signature for field-level callbacks. @@ -45,7 +45,7 @@ typedef void (*mip_dispatch_packet_callback)(void *context, const mip_packet_vie ///@param field The MIP field triggering this callback. ///@param timestamp The approximate parse time of the packet. /// -typedef void (*mip_dispatch_field_callback )(void *context, const mip_field_view *field, mip_timestamp timestamp); +typedef void (*mip_dispatch_field_callback)(void* context, const mip_field_view* field, mip_timestamp timestamp); //////////////////////////////////////////////////////////////////////////////// ///@brief Signature for extraction callbacks. @@ -53,7 +53,7 @@ typedef void (*mip_dispatch_field_callback )(void *context, const mip_field_view ///@param field A valid mip_field. ///@param ptr A pointer to the destination field structure. /// -typedef bool (*mip_dispatch_extractor)(const mip_field_view *field, void *ptr); +typedef bool (*mip_dispatch_extractor)(const mip_field_view* field, void *ptr); enum { @@ -87,14 +87,14 @@ enum { /// typedef struct mip_dispatch_handler { - struct mip_dispatch_handler *_next; ///<@private Pointer to the next handler in the list. + struct mip_dispatch_handler* _next; ///<@private Pointer to the next handler in the list. union { mip_dispatch_packet_callback _packet_callback; ///<@private User function for packets. Valid if _type is MIP_DISPATCH_TYPE_PACKET_*. mip_dispatch_field_callback _field_callback; ///<@private User callback for data fields. Valid if _type is MIP_DISPATCH_TYPE_FIELD. mip_dispatch_extractor _extract_callback; ///<@private User callback for data fields. Valid if _type is MIP_DISPATCH_TYPE_EXTRACT. }; - void *_user_data; ///<@private User-provided pointer which is passed directly to the callback. + void* _user_data; ///<@private User-provided pointer which is passed directly to the callback. uint8_t _type; ///<@private Type of the callback. (Using u8 for better struct packing.) @see mip_dispatch_type uint8_t _descriptor_set; ///<@private MIP descriptor set for this callback. uint8_t _field_descriptor; ///<@private MIP field descriptor for this callback. If 0x00, the callback is a packet callback. @@ -102,12 +102,12 @@ typedef struct mip_dispatch_handler } mip_dispatch_handler; -void mip_dispatch_handler_init_packet_handler(mip_dispatch_handler *handler, uint8_t descriptor_set, bool after_fields, mip_dispatch_packet_callback callback, void *context); -void mip_dispatch_handler_init_field_handler(mip_dispatch_handler *handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_field_callback callback, void *context); -void mip_dispatch_handler_init_extractor(mip_dispatch_handler *handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_extractor extractor, void *field_ptr); +void mip_dispatch_handler_init_packet_handler(mip_dispatch_handler* handler, uint8_t descriptor_set, bool after_fields, mip_dispatch_packet_callback callback, void* context); +void mip_dispatch_handler_init_field_handler(mip_dispatch_handler* handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_field_callback callback, void* context); +void mip_dispatch_handler_init_extractor(mip_dispatch_handler* handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_extractor extractor, void* field_ptr); -void mip_dispatch_handler_set_enabled(mip_dispatch_handler *handler, bool enable); -bool mip_dispatch_handler_is_enabled(mip_dispatch_handler *handler); +void mip_dispatch_handler_set_enabled(mip_dispatch_handler* handler, bool enable); +bool mip_dispatch_handler_is_enabled(mip_dispatch_handler* handler); ///@} @@ -121,16 +121,16 @@ bool mip_dispatch_handler_is_enabled(mip_dispatch_handler *handler); /// typedef struct mip_dispatcher { - mip_dispatch_handler *_first_handler; ///<@private Pointer to the first dispatch handler. May be NULL. + mip_dispatch_handler* _first_handler; ///<@private Pointer to the first dispatch handler. May be NULL. } mip_dispatcher; -void mip_dispatcher_init(mip_dispatcher *self); -void mip_dispatcher_add_handler(mip_dispatcher *self, mip_dispatch_handler *handler); -void mip_dispatcher_remove_handler(mip_dispatcher *self, mip_dispatch_handler *handler); -void mip_dispatcher_remove_all_handlers(mip_dispatcher *self); +void mip_dispatcher_init(mip_dispatcher* self); +void mip_dispatcher_add_handler(mip_dispatcher* self, mip_dispatch_handler* handler); +void mip_dispatcher_remove_handler(mip_dispatcher* self, mip_dispatch_handler* handler); +void mip_dispatcher_remove_all_handlers(mip_dispatcher* self); -void mip_dispatcher_dispatch_packet(mip_dispatcher *self, const mip_packet_view *packet, mip_timestamp timestamp); +void mip_dispatcher_dispatch_packet(mip_dispatcher* self, const mip_packet_view* packet, mip_timestamp timestamp); ///@} ///@} diff --git a/src/c/mip/mip_field.h b/src/c/mip/mip_field.h index 9b06d62de..aa949905e 100644 --- a/src/c/mip/mip_field.h +++ b/src/c/mip/mip_field.h @@ -5,7 +5,7 @@ #include "mip_packet.h" #ifdef __cplusplus -namespace mip{ +namespace mip { namespace C { extern "C" { #endif diff --git a/src/c/mip/mip_interface.h b/src/c/mip/mip_interface.h index 5f469af19..eb7d146e8 100644 --- a/src/c/mip/mip_interface.h +++ b/src/c/mip/mip_interface.h @@ -8,7 +8,7 @@ #include #ifdef __cplusplus -namespace mip{ +namespace mip { namespace C { extern "C" { #endif diff --git a/src/c/mip/mip_parser.h b/src/c/mip/mip_parser.h index b25c21f74..964ecb2f9 100644 --- a/src/c/mip/mip_parser.h +++ b/src/c/mip/mip_parser.h @@ -7,7 +7,7 @@ #include "mip_types.h" #ifdef __cplusplus -namespace mip{ +namespace mip { namespace C { extern "C" { #endif diff --git a/src/c/mip/mip_serialization.c b/src/c/mip/mip_serialization.c index bade7a119..54f0fc2ca 100644 --- a/src/c/mip/mip_serialization.c +++ b/src/c/mip/mip_serialization.c @@ -4,10 +4,10 @@ //////////////////////////////////////////////////////////////////////////////// -///@brief Initializer a serialization struct for creation of a new field at the +///@brief Initialize a serialization struct for creation of a new field at the /// end of the packet. /// -///@note Call microstrain_serializer_finiish_new_field after the data has been serialized. +///@note Call microstrain_serializer_finish_new_field after the data has been serialized. /// ///@note Only one new field per packet can be in progress at a time. /// diff --git a/src/c/mip/mip_serialization.h b/src/c/mip/mip_serialization.h index 0d813fd2a..49a38526e 100644 --- a/src/c/mip/mip_serialization.h +++ b/src/c/mip/mip_serialization.h @@ -6,7 +6,7 @@ #ifdef __cplusplus -namespace mip{ +namespace mip { namespace C { extern "C" { #endif diff --git a/src/cpp/microstrain/common/platform.hpp b/src/cpp/microstrain/common/platform.hpp index 9b3ddd85e..2365f1a0d 100644 --- a/src/cpp/microstrain/common/platform.hpp +++ b/src/cpp/microstrain/common/platform.hpp @@ -3,9 +3,9 @@ #include #ifdef __has_include -# if __has_include() -# include -# endif +#if __has_include() +#include +#endif #endif #if __cpp_inline_variables >= 201606L @@ -22,8 +22,8 @@ #endif #if __cpp_lib_optional >= 201606L || __cplusplus >= 201703L -#define HAS_OPTIONAL +#define MICROSTRAIN_HAS_OPTIONAL #endif #if __cpp_lib_span >= 202002L -#define HAS_SPAN +#define MICROSTRAIN_HAS_SPAN #endif diff --git a/src/cpp/microstrain/common/serialization.hpp b/src/cpp/microstrain/common/serialization.hpp index 0c3a900ae..6655334c8 100644 --- a/src/cpp/microstrain/common/serialization.hpp +++ b/src/cpp/microstrain/common/serialization.hpp @@ -8,8 +8,3 @@ #include #include #include - -namespace microstrain -{ - -} // namespace microstrain diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index 59717a07e..3a019c9a4 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -7,7 +7,7 @@ #include #include -#ifdef HAS_OPTIONAL +#ifdef MICROSTRAIN_HAS_OPTIONAL #include #endif #ifdef HAS_SPAN @@ -18,12 +18,9 @@ #include #endif - - namespace microstrain { - class SerializerBase { public: @@ -201,6 +198,7 @@ typename std::enable_if::value , size_t>::type return serializer.offset() - offset; } + // // Arrays of runtime length // @@ -264,6 +262,7 @@ size_t extract(Serializer& serializer, std::span values) } #endif + // // Arrays of fixed size // @@ -375,15 +374,13 @@ bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offse } - // // Special Deserialization // - // Deserialize and return by value -#ifdef HAS_OPTIONAL +#ifdef MICROSTRAIN_HAS_OPTIONAL template std::optional extract(Serializer& serializer) { @@ -450,4 +447,5 @@ bool Serializer::extract_count(T& count, S max_count) return false; } + } // namespace microstrain diff --git a/src/cpp/microstrain/connections/connection.hpp b/src/cpp/microstrain/connections/connection.hpp index e79cd9ef0..60bd1af41 100644 --- a/src/cpp/microstrain/connections/connection.hpp +++ b/src/cpp/microstrain/connections/connection.hpp @@ -1,11 +1,12 @@ #pragma once #include +#include #include #include -#if __cpp_lib_span >= 202002L +#if MICROSTRAIN_HAS_SPAN #include #endif @@ -33,7 +34,7 @@ class Connection virtual bool sendToDevice(const uint8_t* data, size_t length) = 0; virtual bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) = 0; -#if __cpp_lib_span >= 202002L +#if MICROSTRAIN_HAS_SPAN bool sendToDevice(std::span data) { return sendToDevice(data.data(), data.size()); } bool recvFromDevice(std::span& buffer, unsigned int wait_time_ms, EmbeddedTimestamp* timestamp_out) { size_t length = 0; diff --git a/src/cpp/microstrain/connections/serial/serial_connection.cpp b/src/cpp/microstrain/connections/serial/serial_connection.cpp index baf66caf4..e34973e8e 100644 --- a/src/cpp/microstrain/connections/serial/serial_connection.cpp +++ b/src/cpp/microstrain/connections/serial/serial_connection.cpp @@ -54,7 +54,7 @@ bool SerialConnection::disconnect() -///@copydoc mip::Connection::recvFromDevice +///@copydoc microstrain::Connection::recvFromDevice bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, EmbeddedTimestamp* timestamp) { *timestamp = std::chrono::duration_cast(std::chrono::steady_clock::now().time_since_epoch()).count(); @@ -62,7 +62,7 @@ bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsign return serial_port_read(&mPort, buffer, max_length, wait_time, length_out); } -///@copydoc mip::Connection::sendToDevice +///@copydoc microstrain::Connection::sendToDevice bool SerialConnection::sendToDevice(const uint8_t* data, size_t length) { size_t length_out; diff --git a/src/cpp/microstrain/connections/tcp/tcp_connection.cpp b/src/cpp/microstrain/connections/tcp/tcp_connection.cpp index fe3b348da..9a4a3d9cb 100644 --- a/src/cpp/microstrain/connections/tcp/tcp_connection.cpp +++ b/src/cpp/microstrain/connections/tcp/tcp_connection.cpp @@ -12,7 +12,7 @@ namespace connections ///@brief Creates a TcpConnection that will communicate with a device over TCP /// -///@param hostName Host name or IP address to connect to +///@param hostname Host name or IP address to connect to ///@param port Port on hostName to connect to TcpConnection::TcpConnection(const std::string& hostname, uint16_t port) { @@ -55,7 +55,7 @@ bool TcpConnection::disconnect() return tcp_socket_close(&mSocket); } -///@copydoc mip::Connection::sendToDevice +///@copydoc microstrain::Connection::sendToDevice bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) { (void)wait_time_ms; // Not used, timeout is always fixed @@ -65,7 +65,7 @@ bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned return tcp_socket_recv(&mSocket, buffer, max_length, length_out); } -///@copydoc mip::Connection::recvFromDevice +///@copydoc microstrain::Connection::recvFromDevice bool TcpConnection::sendToDevice(const uint8_t* data, size_t length) { size_t length_out; diff --git a/src/cpp/microstrain/connections/tcp/tcp_connection.hpp b/src/cpp/microstrain/connections/tcp/tcp_connection.hpp index 52bee90e1..9ea3e4678 100644 --- a/src/cpp/microstrain/connections/tcp/tcp_connection.hpp +++ b/src/cpp/microstrain/connections/tcp/tcp_connection.hpp @@ -29,12 +29,12 @@ class TcpConnection : public microstrain::Connection TcpConnection(const TcpConnection&) = delete; TcpConnection& operator=(const TcpConnection&) = delete; - bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, EmbeddedTimestamp* timestamp_out) final; - bool sendToDevice(const uint8_t* data, size_t length) final; + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, EmbeddedTimestamp* timestamp_out) override; + bool sendToDevice(const uint8_t* data, size_t length) override; - bool isConnected() const final; - bool connect() final; - bool disconnect() final; + bool isConnected() const override; + bool connect() override; + bool disconnect() override; void connectionInfo(std::string &host_name, uint32_t &port) const { diff --git a/src/cpp/mip/definitions/common.hpp b/src/cpp/mip/definitions/common.hpp index 2f8817382..1ba3eca87 100644 --- a/src/cpp/mip/definitions/common.hpp +++ b/src/cpp/mip/definitions/common.hpp @@ -100,10 +100,6 @@ struct Vector /// Get the size of the array size_t size() const { return N; } - ///// Pack vector into a raw byte buffer. - //size_t insert(Serializer& serializer) const { return serializer.insert(m_data); } - //size_t extract(Serializer& serializer) { return serializer.extract(m_data); } - private: T m_data[N]; }; diff --git a/src/cpp/mip/metadata/mip_all_definitions.hpp b/src/cpp/mip/metadata/mip_all_definitions.hpp index 3979191b1..bbb20b482 100644 --- a/src/cpp/mip/metadata/mip_all_definitions.hpp +++ b/src/cpp/mip/metadata/mip_all_definitions.hpp @@ -8,11 +8,11 @@ #include #include -#include -#include -#include -#include -#include +#include "definitions/data_filter.hpp" +#include "definitions/data_gnss.hpp" +#include "definitions/data_sensor.hpp" +#include "definitions/data_shared.hpp" +#include "definitions/data_system.hpp" namespace mip::metadata diff --git a/src/cpp/mip/mip_interface.hpp b/src/cpp/mip/mip_interface.hpp index 141ed6d40..799b75d55 100644 --- a/src/cpp/mip/mip_interface.hpp +++ b/src/cpp/mip/mip_interface.hpp @@ -236,7 +236,7 @@ void Interface::setSendFunction() //////////////////////////////////////////////////////////////////////////////// ///@brief Sets the receive callback function (free function version). /// -///@tparam Send A compile-time pointer to the callback function. +///@tparam Recv A compile-time pointer to the callback function. /// template void Interface::setRecvFunction() @@ -249,7 +249,7 @@ void Interface::setRecvFunction() //////////////////////////////////////////////////////////////////////////////// ///@brief Sets the update callback function (free function version). /// -///@tparam Send A compile-time pointer to the callback function. +///@tparam Update A compile-time pointer to the callback function. /// template void Interface::setUpdateFunction() diff --git a/src/cpp/mip/mip_serialization.hpp b/src/cpp/mip/mip_serialization.hpp index 5a3a78be0..002c26cd4 100644 --- a/src/cpp/mip/mip_serialization.hpp +++ b/src/cpp/mip/mip_serialization.hpp @@ -15,7 +15,8 @@ namespace serialization { using namespace microstrain::serialization; using namespace microstrain::serialization::big_endian; -} + +} // namespace serialization using microstrain::insert; using microstrain::extract; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 8ec25a0d1..5ca50fad7 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -22,10 +22,3 @@ add_mip_test(TestMipRandom "${TEST_DIR}/mip/test_mip_random.c" TestMipRa add_mip_test(TestMipFields "${TEST_DIR}/mip/test_mip_fields.c" TestMipFields) add_mip_test(TestMipCpp "${TEST_DIR}/mip/test_mip.cpp" TestMipCpp) add_mip_test(TestMipPerf "${TEST_DIR}/mip/mip_parser_performance.cpp" TestMipPerf) - -#if(MICROSTRAIN_ENABLE_SERIAL) -# add_executable(TestSerial "${TEST_DIR}/test_serial.cpp") -# target_include_directories(TestSerial PUBLIC "${SRC_DIR}") -# target_link_libraries(TestSerial PUBLIC "serial") -# add_test(TestSerial TestSerial) -#endif() From 762a64bb6a8128ca802fc33781581dceed481506 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 18:23:25 -0400 Subject: [PATCH 081/147] - Remove a bunch of mip references in microstrain. --- src/c/microstrain/common/logging.c | 2 +- src/c/microstrain/common/serialization.h | 10 +-- .../connections/serial/serial_port.h | 4 +- .../microstrain/connections/tcp/tcp_socket.h | 6 +- src/c/mip/CMakeLists.txt | 48 +++++------ .../mip_device_models.c} | 2 +- .../mip_device_models.h} | 0 .../microstrain/connections/connection.hpp | 8 +- .../recording/recording_connection.cpp | 4 +- .../recording/recording_connection.hpp | 2 +- .../connections/serial/serial_connection.hpp | 2 +- .../connections/tcp/tcp_connection.hpp | 2 +- src/cpp/microstrain/extras/scope_helper.cpp | 42 +++++----- src/cpp/microstrain/extras/scope_helper.hpp | 80 ++++++++++--------- 14 files changed, 109 insertions(+), 103 deletions(-) rename src/c/{microstrain/common/device_models.c => mip/mip_device_models.c} (99%) rename src/c/{microstrain/common/device_models.h => mip/mip_device_models.h} (100%) diff --git a/src/c/microstrain/common/logging.c b/src/c/microstrain/common/logging.c index 27a1c0bd8..c38d53a98 100644 --- a/src/c/microstrain/common/logging.c +++ b/src/c/microstrain/common/logging.c @@ -63,7 +63,7 @@ void* microstrain_logging_user_data() //////////////////////////////////////////////////////////////////////////////// ///@brief Internal log function called by logging macros. -/// Call MIP_LOG_* macros instead of using this function directly +/// Call MICROSTRAIN_LOG_* macros instead of using this function directly ///@copydetails microstrain::C::microstrain_log_callback /// void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...) diff --git a/src/c/microstrain/common/serialization.h b/src/c/microstrain/common/serialization.h index eab5cf224..401ce11c8 100644 --- a/src/c/microstrain/common/serialization.h +++ b/src/c/microstrain/common/serialization.h @@ -5,12 +5,12 @@ #include //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_serialization MIP Serialization +///@defgroup microstrain_serialization MicroStrain Serialization /// -///@brief Serialization Functions for reading and writing to byte buffers. +///@brief Serialization functions for reading and writing to byte buffers. ///@{ -///@defgroup mip_serialization_c MIP Serialization [C] -///@defgroup mip_serialization_cpp MIP Serialization [CPP] +///@defgroup microstrain_serialization_c MicroStrain Serialization [C] +///@defgroup microstrain_serialization_cpp MicroStrain Serialization [CPP] ///@} #ifdef __cplusplus @@ -24,7 +24,7 @@ extern "C" { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_serialization_c +///@addtogroup microstrain_serialization_c /// ///@brief (De)serialization in C. /// diff --git a/src/c/microstrain/connections/serial/serial_port.h b/src/c/microstrain/connections/serial/serial_port.h index b4d5d3332..4c5a810f2 100644 --- a/src/c/microstrain/connections/serial/serial_port.h +++ b/src/c/microstrain/connections/serial/serial_port.h @@ -28,12 +28,12 @@ extern "C" { #endif //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_platform Platform specific utilities +///@addtogroup microstrain_platform Platform specific utilities /// ///@{ //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_serial Serial Port +///@defgroup microstrain_serial Serial Port /// ///@brief A simple implementation for reading and writing to/from a serial port. /// diff --git a/src/c/microstrain/connections/tcp/tcp_socket.h b/src/c/microstrain/connections/tcp/tcp_socket.h index 5d3adf33c..c604271e3 100644 --- a/src/c/microstrain/connections/tcp/tcp_socket.h +++ b/src/c/microstrain/connections/tcp/tcp_socket.h @@ -21,12 +21,12 @@ extern "C" { #endif //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_platform +///@addtogroup microstrain_platform /// ///@{ //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_tcp TCP Client +///@defgroup microstrain_tcp TCP Client /// ///@brief Simple implementation for reading and writing to a tcp client socket /// @@ -34,7 +34,7 @@ extern "C" { typedef struct tcp_socket { -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS SOCKET handle; #else int handle; diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index c9f916dc2..219b36404 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -3,29 +3,31 @@ set(MIP_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") set(MIP_SOURCES "${VERSION_OUT_FILE}" - mip_cmdqueue.c - mip_cmdqueue.h - mip_descriptors.c - mip_descriptors.h - mip_dispatch.c - mip_dispatch.h - mip_field.c - mip_field.h - mip_interface.c - mip_interface.h - mip_offsets.h - mip_packet.c - mip_packet.h - mip_parser.c - mip_parser.h - mip_result.c - mip_result.h - mip_types.h - mip_serialization.c - mip_serialization.h - definitions/common.c - definitions/common.h - mip_all.h + "mip_cmdqueue.c" + "mip_cmdqueue.h" + "mip_descriptors.c" + "mip_descriptors.h" + "mip_device_models.c" + "mip_device_models.h" + "mip_dispatch.c" + "mip_dispatch.h" + "mip_field.c" + "mip_field.h" + "mip_interface.c" + "mip_interface.h" + "mip_offsets.h" + "mip_packet.c" + "mip_packet.h" + "mip_parser.c" + "mip_parser.h" + "mip_result.c" + "mip_result.h" + "mip_types.h" + "mip_serialization.c" + "mip_serialization.h" + "definitions/common.c" + "definitions/common.h" + "mip_all.h" "utils/byte_ring.c" "utils/byte_ring.h" diff --git a/src/c/microstrain/common/device_models.c b/src/c/mip/mip_device_models.c similarity index 99% rename from src/c/microstrain/common/device_models.c rename to src/c/mip/mip_device_models.c index 8566c0958..cd0f00d5a 100644 --- a/src/c/microstrain/common/device_models.c +++ b/src/c/mip/mip_device_models.c @@ -1,5 +1,5 @@ -#include "device_models.h" +#include "mip_device_models.h" #include #include diff --git a/src/c/microstrain/common/device_models.h b/src/c/mip/mip_device_models.h similarity index 100% rename from src/c/microstrain/common/device_models.h rename to src/c/mip/mip_device_models.h diff --git a/src/cpp/microstrain/connections/connection.hpp b/src/cpp/microstrain/connections/connection.hpp index 60bd1af41..bf0ce29f9 100644 --- a/src/cpp/microstrain/connections/connection.hpp +++ b/src/cpp/microstrain/connections/connection.hpp @@ -15,12 +15,12 @@ namespace microstrain { //////////////////////////////////////////////////////////////////////////////// -///@brief Represents a type of connection to a MIP device. +///@brief Represents a type of connection. /// /// The following methods are pure virtual and must be implemented by a derived -/// class. These functions map to the corresponding C functions. -///@li `bool sendToDevice(const uint8_t* data, size_t length)` - corresponds to mip_interface_user_send_to_device. -///@li `bool recvFromDevice(uint8_t* buffer, size_t maxLength, size_t* lengthOut, Timestamp* timestampOut)` - corresponds to mip_interface_user_recv_from_device. +/// class: +///@li `bool sendToDevice(const uint8_t* data, size_t length)` +///@li `bool recvFromDevice(uint8_t* buffer, size_t maxLength, unsigned int wait_time_ms, size_t* lengthOut, EmbeddedTimestamp* timestampOut)` /// class Connection { diff --git a/src/cpp/microstrain/connections/recording/recording_connection.cpp b/src/cpp/microstrain/connections/recording/recording_connection.cpp index 5ab0add89..351cb7035 100644 --- a/src/cpp/microstrain/connections/recording/recording_connection.cpp +++ b/src/cpp/microstrain/connections/recording/recording_connection.cpp @@ -18,7 +18,7 @@ RecordingConnection::RecordingConnection(Connection* connection, std::ostream* r mType = TYPE; } -///@copydoc mip::Connection::sendToDevice +///@copydoc microstrain::Connection::sendToDevice bool RecordingConnection::sendToDevice(const uint8_t* data, size_t length) { const bool ok = mConnection->sendToDevice(data, length); @@ -32,7 +32,7 @@ bool RecordingConnection::sendToDevice(const uint8_t* data, size_t length) return ok; } -///@copydoc mip::Connection::recvFromDevice +///@copydoc microstrain::Connection::recvFromDevice bool RecordingConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* count_out, EmbeddedTimestamp* timestamp_out) { const bool ok = mConnection->recvFromDevice(buffer, max_length, wait_time_ms, count_out, timestamp_out); diff --git a/src/cpp/microstrain/connections/recording/recording_connection.hpp b/src/cpp/microstrain/connections/recording/recording_connection.hpp index ead3a5aa8..68c121a16 100644 --- a/src/cpp/microstrain/connections/recording/recording_connection.hpp +++ b/src/cpp/microstrain/connections/recording/recording_connection.hpp @@ -12,7 +12,7 @@ namespace connections { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_extras Extra utilities +///@addtogroup microstrain_extras Extra utilities ///@{ //////////////////////////////////////////////////////////////////////////////// diff --git a/src/cpp/microstrain/connections/serial/serial_connection.hpp b/src/cpp/microstrain/connections/serial/serial_connection.hpp index 42d438c7b..b68d2fb6e 100644 --- a/src/cpp/microstrain/connections/serial/serial_connection.hpp +++ b/src/cpp/microstrain/connections/serial/serial_connection.hpp @@ -12,7 +12,7 @@ namespace connections { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_platform +///@addtogroup microstrain_platform ///@{ //////////////////////////////////////////////////////////////////////////////// diff --git a/src/cpp/microstrain/connections/tcp/tcp_connection.hpp b/src/cpp/microstrain/connections/tcp/tcp_connection.hpp index 9ea3e4678..67cf5f407 100644 --- a/src/cpp/microstrain/connections/tcp/tcp_connection.hpp +++ b/src/cpp/microstrain/connections/tcp/tcp_connection.hpp @@ -12,7 +12,7 @@ namespace connections { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_platform +///@addtogroup microstrain_platform ///@{ //////////////////////////////////////////////////////////////////////////////// diff --git a/src/cpp/microstrain/extras/scope_helper.cpp b/src/cpp/microstrain/extras/scope_helper.cpp index 75c574262..ac51f5e82 100644 --- a/src/cpp/microstrain/extras/scope_helper.cpp +++ b/src/cpp/microstrain/extras/scope_helper.cpp @@ -1,26 +1,28 @@ #include "scope_helper.hpp" -namespace mip +namespace microstrain { - namespace extras +namespace extras +{ + +ScopeHelper::ScopeHelper(std::function scopeFunction) : + m_outOfScopeFunction(scopeFunction), + m_canceled(false) +{ +} + +ScopeHelper::~ScopeHelper() +{ + if (!m_canceled) { - ScopeHelper::ScopeHelper(std::function scopeFunction) : - m_outOfScopeFunction(scopeFunction), - m_canceled(false) - { - } + m_outOfScopeFunction(); + } +} - ScopeHelper::~ScopeHelper() - { - if (!m_canceled) - { - m_outOfScopeFunction(); - } - } +void ScopeHelper::cancel() +{ + m_canceled = true; +} - void ScopeHelper::cancel() - { - m_canceled = true; - } - } //namespace extras -} //namespace mip \ No newline at end of file +} //namespace extras +} //namespace microstrain diff --git a/src/cpp/microstrain/extras/scope_helper.hpp b/src/cpp/microstrain/extras/scope_helper.hpp index ab2386a8d..f766f4de1 100644 --- a/src/cpp/microstrain/extras/scope_helper.hpp +++ b/src/cpp/microstrain/extras/scope_helper.hpp @@ -3,43 +3,45 @@ #include #include -namespace mip +namespace microstrain { - namespace extras - { - //Class: ScopeHelper - // Class that allows a function to be run when this object goes out of scope. - class ScopeHelper - { - private: - //Variable: m_outOfScopeFunction - // The function to run when the ScopeHelper goes out of scope. - std::function m_outOfScopeFunction; - - //Variable: m_canceled - // Whether the scope function has been canceled or not. - bool m_canceled; - - ScopeHelper(); //default constructor disabled - ScopeHelper(const ScopeHelper&); //copy constructor disabled - ScopeHelper& operator=(const ScopeHelper&); //assignment operator disabled - - public: - //Constructor: ScopeHelper - // Creates a ScopeHelper object. - // - //Parameters: - // scopeFunction - The function to run when the ScopeHelper object is destroyed. - ScopeHelper(std::function scopeFunction); - - //Destructor: ScopeHelper - // Runs whatever function was assigned in the creation of the ScopeHelper. - ~ScopeHelper(); - - //Function: cancel - // Sets a flag that indicates the originally set function should NOT be run when - // the ScopeHelper is destroyed. - void cancel(); - }; - } //namespace extras -} //namespace mip \ No newline at end of file +namespace extras +{ + +//Class: ScopeHelper +// Class that allows a function to be run when this object goes out of scope. +class ScopeHelper +{ +private: + //Variable: m_outOfScopeFunction + // The function to run when the ScopeHelper goes out of scope. + std::function m_outOfScopeFunction; + + //Variable: m_canceled + // Whether the scope function has been canceled or not. + bool m_canceled; + + ScopeHelper(); //default constructor disabled + ScopeHelper(const ScopeHelper&); //copy constructor disabled + ScopeHelper& operator=(const ScopeHelper&); //assignment operator disabled + +public: + //Constructor: ScopeHelper + // Creates a ScopeHelper object. + // + //Parameters: + // scopeFunction - The function to run when the ScopeHelper object is destroyed. + ScopeHelper(std::function scopeFunction); + + //Destructor: ScopeHelper + // Runs whatever function was assigned in the creation of the ScopeHelper. + ~ScopeHelper(); + + //Function: cancel + // Sets a flag that indicates the originally set function should NOT be run when + // the ScopeHelper is destroyed. + void cancel(); +}; + +} //namespace extras +} //namespace microstrain From c3636548976ab88ca1e60af3583ef09eaf5a590d Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 18:31:25 -0400 Subject: [PATCH 082/147] - Standardize include paths. --- .../connections/microstrain_connections_all.hpp | 8 ++++---- src/cpp/mip/extras/CMakeLists.txt | 4 ++-- src/cpp/mip/extras/composite_result.hpp | 8 ++++---- src/cpp/mip/extras/descriptor_id.hpp | 2 +- src/cpp/mip/extras/{version.cpp => firmware_version.cpp} | 2 +- src/cpp/mip/extras/{version.hpp => firmware_version.hpp} | 0 src/cpp/mip/extras/mip_extras_all.hpp | 2 +- src/cpp/mip/metadata/mip_definitions.hpp | 3 ++- src/cpp/mip/mip_all.hpp | 4 +++- 9 files changed, 18 insertions(+), 15 deletions(-) rename src/cpp/mip/extras/{version.cpp => firmware_version.cpp} (98%) rename src/cpp/mip/extras/{version.hpp => firmware_version.hpp} (100%) diff --git a/src/cpp/microstrain/connections/microstrain_connections_all.hpp b/src/cpp/microstrain/connections/microstrain_connections_all.hpp index c1854be61..f20776609 100644 --- a/src/cpp/microstrain/connections/microstrain_connections_all.hpp +++ b/src/cpp/microstrain/connections/microstrain_connections_all.hpp @@ -1,7 +1,7 @@ #pragma once // MicroStrain Connections -#include "microstrain/connections/connection.hpp" -#include "microstrain/connections/recording/recording_connection.hpp" -#include "microstrain/connections/serial/serial_connection.hpp" -#include "microstrain/connections/tcp/tcp_connection.hpp" +#include "connection.hpp" +#include "recording/recording_connection.hpp" +#include "serial/serial_connection.hpp" +#include "tcp/tcp_connection.hpp" diff --git a/src/cpp/mip/extras/CMakeLists.txt b/src/cpp/mip/extras/CMakeLists.txt index 1e43049ca..6e204afbd 100644 --- a/src/cpp/mip/extras/CMakeLists.txt +++ b/src/cpp/mip/extras/CMakeLists.txt @@ -2,8 +2,8 @@ set(SOURCES composite_result.hpp descriptor_id.hpp - version.cpp - version.hpp + firmware_version.cpp + firmware_version.hpp ) add_library(mip_extras ${SOURCES}) diff --git a/src/cpp/mip/extras/composite_result.hpp b/src/cpp/mip/extras/composite_result.hpp index 5f7acc09f..26028725f 100644 --- a/src/cpp/mip/extras/composite_result.hpp +++ b/src/cpp/mip/extras/composite_result.hpp @@ -2,9 +2,9 @@ #include "descriptor_id.hpp" -#include "mip/mip_interface.hpp" -#include "mip/mip_result.h" -#include "mip/mip_descriptors.h" +#include +#include +#include #include @@ -123,7 +123,7 @@ namespace mip template - CompositeResult::Entry runCommandEx(DeviceInterface& device, const Cmd& cmd, Args&&... args) + CompositeResult::Entry runCommandEx(Interface& device, const Cmd& cmd, Args&&... args) { CmdResult result = device.runCommand(cmd, std::forward(args)...); diff --git a/src/cpp/mip/extras/descriptor_id.hpp b/src/cpp/mip/extras/descriptor_id.hpp index 5762c404d..ed27eaeea 100644 --- a/src/cpp/mip/extras/descriptor_id.hpp +++ b/src/cpp/mip/extras/descriptor_id.hpp @@ -1,6 +1,6 @@ #pragma once -#include "../mip_descriptors.hpp" +#include namespace mip diff --git a/src/cpp/mip/extras/version.cpp b/src/cpp/mip/extras/firmware_version.cpp similarity index 98% rename from src/cpp/mip/extras/version.cpp rename to src/cpp/mip/extras/firmware_version.cpp index d5b63c57c..f59ef8e3d 100644 --- a/src/cpp/mip/extras/version.cpp +++ b/src/cpp/mip/extras/firmware_version.cpp @@ -1,5 +1,5 @@ -#include "version.hpp" +#include "firmware_version.hpp" #include diff --git a/src/cpp/mip/extras/version.hpp b/src/cpp/mip/extras/firmware_version.hpp similarity index 100% rename from src/cpp/mip/extras/version.hpp rename to src/cpp/mip/extras/firmware_version.hpp diff --git a/src/cpp/mip/extras/mip_extras_all.hpp b/src/cpp/mip/extras/mip_extras_all.hpp index c5659aaaf..5f5f73979 100644 --- a/src/cpp/mip/extras/mip_extras_all.hpp +++ b/src/cpp/mip/extras/mip_extras_all.hpp @@ -3,4 +3,4 @@ // MIP Extras Core #include "composite_result.hpp" #include "descriptor_id.hpp" -#include "version.hpp" +#include "firmware_version.hpp" diff --git a/src/cpp/mip/metadata/mip_definitions.hpp b/src/cpp/mip/metadata/mip_definitions.hpp index 93f16cb63..785236d57 100644 --- a/src/cpp/mip/metadata/mip_definitions.hpp +++ b/src/cpp/mip/metadata/mip_definitions.hpp @@ -1,7 +1,8 @@ #pragma once #include "mip_metadata.hpp" -#include "../mip_descriptors.hpp" + +#include #include #include diff --git a/src/cpp/mip/mip_all.hpp b/src/cpp/mip/mip_all.hpp index bd41594ed..749d26265 100644 --- a/src/cpp/mip/mip_all.hpp +++ b/src/cpp/mip/mip_all.hpp @@ -1,5 +1,8 @@ #pragma once +// mip_version from C +#include + // MIP Core #include "mip_cmdqueue.hpp" #include "mip_descriptors.hpp" @@ -8,7 +11,6 @@ #include "mip_packet.hpp" #include "mip_parser.hpp" #include "mip_result.hpp" -#include "mip/mip_version.h" // MIP Commands #include "definitions/commands_3dm.hpp" From 1dd264c48d93310f64493083755fe20c35e1c0d6 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 21 Aug 2024 18:34:40 -0400 Subject: [PATCH 083/147] - Update company name in example license text. --- examples/CV7/CV7_example.c | 2 +- examples/CV7/CV7_example.cpp | 2 +- examples/CV7_INS/CV7_INS_simple_example.cpp | 2 +- examples/CV7_INS/CV7_INS_simple_ublox_example.cpp | 2 +- examples/CV7_INS/simple_ublox_parser.hpp | 2 +- examples/CV7_INS/ublox_device.hpp | 2 +- examples/CX5_GX5_45/CX5_GX5_45_example.c | 2 +- examples/CX5_GX5_45/CX5_GX5_45_example.cpp | 2 +- examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c | 2 +- examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp | 2 +- examples/GQ7/GQ7_example.c | 2 +- examples/GQ7/GQ7_example.cpp | 2 +- examples/device_info.cpp | 2 +- examples/threading.cpp | 2 +- 14 files changed, 14 insertions(+), 14 deletions(-) diff --git a/examples/CV7/CV7_example.c b/examples/CV7/CV7_example.c index 55370977b..bb308bddc 100644 --- a/examples/CV7/CV7_example.c +++ b/examples/CV7/CV7_example.c @@ -15,7 +15,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/CV7/CV7_example.cpp b/examples/CV7/CV7_example.cpp index fce98c469..627270c43 100644 --- a/examples/CV7/CV7_example.cpp +++ b/examples/CV7/CV7_example.cpp @@ -15,7 +15,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/CV7_INS/CV7_INS_simple_example.cpp b/examples/CV7_INS/CV7_INS_simple_example.cpp index 357346037..53f940d68 100644 --- a/examples/CV7_INS/CV7_INS_simple_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_example.cpp @@ -14,7 +14,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp index e63566799..74c674213 100644 --- a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp @@ -11,7 +11,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/CV7_INS/simple_ublox_parser.hpp b/examples/CV7_INS/simple_ublox_parser.hpp index 5c54b9b85..c86aef1e5 100644 --- a/examples/CV7_INS/simple_ublox_parser.hpp +++ b/examples/CV7_INS/simple_ublox_parser.hpp @@ -11,7 +11,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/CV7_INS/ublox_device.hpp b/examples/CV7_INS/ublox_device.hpp index f6ea7440c..23d48da81 100644 --- a/examples/CV7_INS/ublox_device.hpp +++ b/examples/CV7_INS/ublox_device.hpp @@ -11,7 +11,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/CX5_GX5_45/CX5_GX5_45_example.c b/examples/CX5_GX5_45/CX5_GX5_45_example.c index 7d1a33fb1..5b81301c7 100644 --- a/examples/CX5_GX5_45/CX5_GX5_45_example.c +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.c @@ -15,7 +15,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/CX5_GX5_45/CX5_GX5_45_example.cpp b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp index 242c4e08f..354e2d864 100644 --- a/examples/CX5_GX5_45/CX5_GX5_45_example.cpp +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp @@ -15,7 +15,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c index 293d618f3..20cc7db4e 100644 --- a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c @@ -15,7 +15,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp index 31e060489..ab38cd072 100644 --- a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp @@ -15,7 +15,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/GQ7/GQ7_example.c b/examples/GQ7/GQ7_example.c index 39bac16f2..5a56bff73 100644 --- a/examples/GQ7/GQ7_example.c +++ b/examples/GQ7/GQ7_example.c @@ -15,7 +15,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/GQ7/GQ7_example.cpp b/examples/GQ7/GQ7_example.cpp index d63f70dfd..235d80902 100644 --- a/examples/GQ7/GQ7_example.cpp +++ b/examples/GQ7/GQ7_example.cpp @@ -15,7 +15,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/device_info.cpp b/examples/device_info.cpp index e4e93d737..2f36d7306 100644 --- a/examples/device_info.cpp +++ b/examples/device_info.cpp @@ -9,7 +9,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. diff --git a/examples/threading.cpp b/examples/threading.cpp index d570f79de..f47c17d86 100644 --- a/examples/threading.cpp +++ b/examples/threading.cpp @@ -9,7 +9,7 @@ //! //! THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING //! CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER -//! FOR THEM TO SAVE TIME. AS A RESULT, HBK MICROSTRAIN SHALL NOT BE HELD +//! FOR THEM TO SAVE TIME. AS A RESULT, MICROSTRAIN BY HBK SHALL NOT BE HELD //! LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY //! CLAIMS ARISING FROM THE CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS //! OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. From 89fac3873835367c6574a1397997ece3977a6389 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 23 Aug 2024 13:41:38 -0400 Subject: [PATCH 084/147] - More PR updates and clean up CMakeLists. --- CMakeLists.txt | 62 +++++-------------- src/c/microstrain/CMakeLists.txt | 2 - src/c/microstrain/common/CMakeLists.txt | 13 +++- .../connections/serial/CMakeLists.txt | 4 +- .../connections/tcp/CMakeLists.txt | 4 +- src/c/mip/CMakeLists.txt | 35 +++++------ src/c/mip/definitions/commands_3dm.c | 2 +- src/c/mip/definitions/commands_3dm.h | 2 +- src/c/mip/definitions/commands_aiding.c | 2 +- src/c/mip/definitions/commands_aiding.h | 2 +- src/c/mip/definitions/commands_base.c | 2 +- src/c/mip/definitions/commands_base.h | 2 +- src/c/mip/definitions/commands_filter.c | 2 +- src/c/mip/definitions/commands_filter.h | 2 +- src/c/mip/definitions/commands_gnss.c | 2 +- src/c/mip/definitions/commands_gnss.h | 2 +- src/c/mip/definitions/commands_rtk.c | 2 +- src/c/mip/definitions/commands_rtk.h | 2 +- src/c/mip/definitions/commands_system.c | 2 +- src/c/mip/definitions/commands_system.h | 2 +- src/c/mip/definitions/data_filter.c | 2 +- src/c/mip/definitions/data_filter.h | 2 +- src/c/mip/definitions/data_gnss.c | 2 +- src/c/mip/definitions/data_gnss.h | 2 +- src/c/mip/definitions/data_sensor.c | 2 +- src/c/mip/definitions/data_sensor.h | 2 +- src/c/mip/definitions/data_shared.c | 2 +- src/c/mip/definitions/data_shared.h | 2 +- src/c/mip/definitions/data_system.c | 2 +- src/c/mip/definitions/data_system.h | 2 +- src/c/mip/mip_cmdqueue.h | 2 +- src/c/mip/mip_descriptors.c | 2 +- src/c/mip/mip_descriptors.h | 2 +- src/c/mip/mip_device_models.h | 2 +- src/c/mip/mip_field.h | 4 +- src/c/mip/mip_interface.h | 4 +- src/c/mip/mip_packet.h | 4 +- src/c/mip/mip_parser.h | 4 +- src/c/mip/mip_result.c | 30 ++++----- src/c/mip/mip_serialization.h | 4 +- src/cpp/microstrain/CMakeLists.txt | 7 ++- src/cpp/microstrain/common/CMakeLists.txt | 3 +- .../connections/recording/CMakeLists.txt | 3 - .../connections/serial/CMakeLists.txt | 4 +- .../connections/tcp/CMakeLists.txt | 5 +- src/cpp/microstrain/extras/CMakeLists.txt | 3 +- src/cpp/mip/CMakeLists.txt | 4 +- src/cpp/mip/extras/CMakeLists.txt | 3 +- src/cpp/mip/metadata/CMakeLists.txt | 5 +- 49 files changed, 110 insertions(+), 153 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index de3959ec4..9e1a0209b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,10 +1,10 @@ cmake_minimum_required(VERSION 3.10) -#set(CMAKE_CXX_STANDARD 14) -#set(CMAKE_CXX_STANDARD_REQUIRED ON) -#set(CMAKE_C_STANDARD 11) -#set(CMAKE_C_STANDARD_REQUIRED ON) +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD_REQUIRED ON) +set(CMAKE_C_STANDARD 11) +set(CMAKE_C_STANDARD_REQUIRED ON) project( "MIP SDK" @@ -27,21 +27,16 @@ set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_INFO" CACHE STRING "Max set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") option(MICROSTRAIN_ENABLE_SERIAL "Build serial connection support into the library and examples" ON) -option(MICROSTRAIN_ENABLE_TCP "Build TCP connection support into the library and exampels" ON) +option(MICROSTRAIN_ENABLE_TCP "Build TCP connection support into the library and examples" ON) option(MICROSTRAIN_ENABLE_CPP "Enables the C++ API. Turn off to avoid compiling the C++ API." ON) -option(MICROSTRAIN_ENABLE_CPP_C_NAMESPACE "Wraps the C api in a C++ namespace to avoid global namespace pollution (e.g. microstrain::C::microstrain_serial_port)" ${MICROSTRAIN_ENABLE_CPP}) +#option(MICROSTRAIN_ENABLE_CPP_C_NAMESPACE "Wraps the C api in a C++ namespace to avoid global namespace pollution (e.g. microstrain::C::microstrain_serial_port)" ${MICROSTRAIN_ENABLE_CPP}) # MIP options option(MIP_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) -# This fails with g++-9.4 as it can't find despite cmake claiming c++20 support. -#if("cxx_std_20" IN_LIST CMAKE_CXX_COMPILE_FEATURES) -# set(MIP_COMPILER_SUPPORTS_METADATA ON) -#else() -# set(MIP_COMPILER_SUPPORTS_METADATA OFF) -#endif() + if(NOT DEFINED MIP_ENABLE_METADATA) include("${MIP_CMAKE_DIR}/check_metadata.cmake") message("MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") @@ -52,7 +47,7 @@ option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requ option(BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) option(BUILD_EXAMPLES "Builds the example programs." ON) # CTest defines this option to ON by default, so override it to OFF here. -option(BUILD_TESTING "Build the testing tree." OFF) +option(BUILD_TESTS "Build the testing tree." OFF) option(BUILD_DOCUMENTATION "Build the documentation." OFF) option(BUILD_DOCUMENTATION_FULL "Build the full (internal) documentation." OFF) option(BUILD_DOCUMENTATION_QUIET "Suppress doxygen standard output." ON) @@ -113,58 +108,33 @@ configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) # Suppress warnings due to adding files with target_sources. cmake_policy(SET CMP0076 NEW) -#include_directories(src/c) -#if(MICROSTRAIN_ENABLE_CPP) -# include_directories(src/cpp) -#endif() # Add all the C files (required even for C++ API) +set(SRC_C_DIR "${CMAKE_CURRENT_LIST_DIR}/src/c") + add_subdirectory(src/c/microstrain) add_subdirectory(src/c/mip) # Add all the C++ files (if C++ enabled) if(MICROSTRAIN_ENABLE_CPP) + set(SRC_CPP_DIR "${CMAKE_CURRENT_LIST_DIR}/src/cpp") + add_subdirectory(src/cpp/microstrain) add_subdirectory(src/cpp/mip) - #target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_CPP=1") - target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_CPP_C_NAMESPACE=${MICROSTRAIN_ENABLE_CPP_C_NAMESPACE}") + #target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_CPP_C_NAMESPACE=${MICROSTRAIN_ENABLE_CPP_C_NAMESPACE}") endif() -if(MIP_ENABLE_EXTRAS) - list(APPEND MIP_DEFINES "MIP_ENABLE_EXTRAS") - set(MIP_EXTRAS_DIR "${MIP_DIR}/extras") - set(MIP_EXTRA_SOURCES - "${MIP_EXTRAS_DIR}/composite_result.hpp" - "${MIP_EXTRAS_DIR}/descriptor_id.hpp" - "${MIP_EXTRAS_DIR}/device_models.h" - "${MIP_EXTRAS_DIR}/device_models.c" - "${MIP_EXTRAS_DIR}/index.hpp" - "${MIP_EXTRAS_DIR}/recording_connection.hpp" - "${MIP_EXTRAS_DIR}/recording_connection.cpp" - "${MIP_EXTRAS_DIR}/scope_helper.hpp" - "${MIP_EXTRAS_DIR}/scope_helper.cpp" - "${MIP_EXTRAS_DIR}/version.hpp" - "${MIP_EXTRAS_DIR}/version.cpp" - ) -endif() - # # Preprocessor definitions # -# Disable windows defined min/max -# Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) -if(WIN32) - add_compile_definitions("NOMINMAX=1" "_WIN32_WINNT=0x0501") -endif() - if(MSVC) - target_compile_options(mip PRIVATE /W4) + add_compile_options(/W4) else() - target_compile_options(mip PRIVATE -Wall -Wextra) + add_compile_options(-Wall -Wextra) endif() @@ -178,7 +148,7 @@ endif() include(CTest) -if(BUILD_TESTING) +if(BUILD_TESTS) add_subdirectory("test") endif() diff --git a/src/c/microstrain/CMakeLists.txt b/src/c/microstrain/CMakeLists.txt index 8fc14a7be..e501bfb7a 100644 --- a/src/c/microstrain/CMakeLists.txt +++ b/src/c/microstrain/CMakeLists.txt @@ -1,5 +1,3 @@ -set(MICROSTRAIN_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") - add_subdirectory(common) add_subdirectory(connections) diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index eb22dbeff..d1ccab161 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -11,7 +11,6 @@ add_library(microstrain_common ) target_compile_features(microstrain_common PUBLIC c_std_11) - target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") # Logging is a little weird since we need to install the header no matter what @@ -24,4 +23,14 @@ if(MICROSTRAIN_ENABLE_LOGGING) target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") endif() -target_include_directories(microstrain_common INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) +target_include_directories(microstrain_common INTERFACE ${SRC_C_DIR}) + +# Disable windows defined min/max +# Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) +if(WIN32) + target_compile_definitions(microstrain_common + PUBLIC + "NOMINMAX=1" + "_WIN32_WINNT=_WIN32_WINNT_WINXP" + ) +endif() diff --git a/src/c/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt index 68be9d772..a15d50227 100644 --- a/src/c/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -5,7 +5,5 @@ add_library(microstrain_serial ) target_compile_features(microstrain_serial PUBLIC c_std_11) - -target_include_directories(microstrain_serial INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) - +target_compile_definitions(microstrain_serial PUBLIC "MICROSTRAIN_ENABLE_SERIAL=1") target_link_libraries(microstrain_serial PUBLIC microstrain_common) diff --git a/src/c/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt index 95d298077..801aab2be 100644 --- a/src/c/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -5,9 +5,7 @@ add_library(microstrain_socket ) target_compile_features(microstrain_socket PUBLIC c_std_11) - -target_include_directories(microstrain_socket INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) - +target_compile_definitions(microstrain_socket PUBLIC "MICROSTRAIN_ENABLE_TCP=1") target_link_libraries(microstrain_socket PUBLIC microstrain_common) if(WIN32) diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index 219b36404..faab57263 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -1,8 +1,11 @@ -set(MIP_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") +# +# Core MIP C library +# -set(MIP_SOURCES +add_library(mip "${VERSION_OUT_FILE}" + "mip_cmdqueue.c" "mip_cmdqueue.h" "mip_descriptors.c" @@ -33,9 +36,17 @@ set(MIP_SOURCES "utils/byte_ring.h" ) -add_library(mip ${MIP_SOURCES}) target_compile_features(mip PUBLIC c_std_11) -target_include_directories(mip INTERFACE ${MIP_INCLUDE_DIR}) +target_link_libraries(mip PUBLIC microstrain_common) + +if(${MIP_ENABLE_DIAGNOSTICS}) + target_compile_definitions(mip PUBLIC "MIP_ENABLE_DIAGNOSTICS=1") +endif() + + +# +# Mip definition files +# set(MIPDEFS commands_3dm @@ -67,19 +78,3 @@ if(MICROSTRAIN_CMAKE_DEBUG) endif() target_sources(mip PRIVATE ${MIPDEF_SOURCES}) - - - -if(${MIP_ENABLE_DIAGNOSTICS}) - list(APPEND MIP_DEFINES "MIP_ENABLE_DIAGNOSTICS") -endif() - -if(${MICROSTRAIN_TIMESTAMP_TYPE}) - list(APPEND MIP_DEFINES "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") -endif() - -target_compile_definitions(mip PUBLIC "${MIP_DEFINES}") - -target_link_libraries(mip PUBLIC microstrain_common) - -#target_include_directories(mip INTERFACE ${CMAKE_CURRENT_LIST_DIR}) diff --git a/src/c/mip/definitions/commands_3dm.c b/src/c/mip/definitions/commands_3dm.c index a9cc6d9a5..d98a9437e 100644 --- a/src/c/mip/definitions/commands_3dm.c +++ b/src/c/mip/definitions/commands_3dm.c @@ -5005,8 +5005,8 @@ mip_cmd_result mip_3dm_default_lowpass_filter(mip_interface* device, uint8_t des } #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_3dm.h b/src/c/mip/definitions/commands_3dm.h index 45da067c4..3e2b5cfa0 100644 --- a/src/c/mip/definitions/commands_3dm.h +++ b/src/c/mip/definitions/commands_3dm.h @@ -2527,8 +2527,8 @@ mip_cmd_result mip_3dm_default_lowpass_filter(mip_interface* device, uint8_t des /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_aiding.c b/src/c/mip/definitions/commands_aiding.c index 4adc03899..36a330757 100644 --- a/src/c/mip/definitions/commands_aiding.c +++ b/src/c/mip/definitions/commands_aiding.c @@ -838,8 +838,8 @@ mip_cmd_result mip_aiding_pressure(mip_interface* device, const mip_time* time, } #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_aiding.h b/src/c/mip/definitions/commands_aiding.h index 760bda29b..daee62020 100644 --- a/src/c/mip/definitions/commands_aiding.h +++ b/src/c/mip/definitions/commands_aiding.h @@ -561,8 +561,8 @@ mip_cmd_result mip_aiding_pressure(mip_interface* device, const mip_time* time, /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_base.c b/src/c/mip/definitions/commands_base.c index 198c536f5..2fdd14628 100644 --- a/src/c/mip/definitions/commands_base.c +++ b/src/c/mip/definitions/commands_base.c @@ -348,8 +348,8 @@ mip_cmd_result mip_base_soft_reset(mip_interface* device) } #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_base.h b/src/c/mip/definitions/commands_base.h index 529714bc0..45bbc7fb5 100644 --- a/src/c/mip/definitions/commands_base.h +++ b/src/c/mip/definitions/commands_base.h @@ -413,8 +413,8 @@ mip_cmd_result mip_base_soft_reset(mip_interface* device); /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_filter.c b/src/c/mip/definitions/commands_filter.c index 4385fdcd5..92440e4d1 100644 --- a/src/c/mip/definitions/commands_filter.c +++ b/src/c/mip/definitions/commands_filter.c @@ -5539,8 +5539,8 @@ mip_cmd_result mip_filter_set_initial_heading(mip_interface* device, float headi } #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_filter.h b/src/c/mip/definitions/commands_filter.h index 7a8510e88..770ce2a60 100644 --- a/src/c/mip/definitions/commands_filter.h +++ b/src/c/mip/definitions/commands_filter.h @@ -2450,8 +2450,8 @@ mip_cmd_result mip_filter_set_initial_heading(mip_interface* device, float headi /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_gnss.c b/src/c/mip/definitions/commands_gnss.c index 352c9eac9..2d78d89aa 100644 --- a/src/c/mip/definitions/commands_gnss.c +++ b/src/c/mip/definitions/commands_gnss.c @@ -361,8 +361,8 @@ mip_cmd_result mip_gnss_default_rtk_dongle_configuration(mip_interface* device) } #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_gnss.h b/src/c/mip/definitions/commands_gnss.h index 7ff3c7fe5..4a26cf700 100644 --- a/src/c/mip/definitions/commands_gnss.h +++ b/src/c/mip/definitions/commands_gnss.h @@ -179,8 +179,8 @@ mip_cmd_result mip_gnss_default_rtk_dongle_configuration(mip_interface* device); /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_rtk.c b/src/c/mip/definitions/commands_rtk.c index f3eaebae1..20d5c29d1 100644 --- a/src/c/mip/definitions/commands_rtk.c +++ b/src/c/mip/definitions/commands_rtk.c @@ -431,8 +431,8 @@ mip_cmd_result mip_rtk_modem_hard_reset(mip_interface* device) } #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_rtk.h b/src/c/mip/definitions/commands_rtk.h index 51df0136d..bd800f5b6 100644 --- a/src/c/mip/definitions/commands_rtk.h +++ b/src/c/mip/definitions/commands_rtk.h @@ -458,8 +458,8 @@ mip_cmd_result mip_rtk_modem_hard_reset(mip_interface* device); /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_system.c b/src/c/mip/definitions/commands_system.c index f42478c3e..731014238 100644 --- a/src/c/mip/definitions/commands_system.c +++ b/src/c/mip/definitions/commands_system.c @@ -105,8 +105,8 @@ mip_cmd_result mip_system_default_comm_mode(mip_interface* device) } #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/commands_system.h b/src/c/mip/definitions/commands_system.h index c30ccfec5..915764830 100644 --- a/src/c/mip/definitions/commands_system.h +++ b/src/c/mip/definitions/commands_system.h @@ -99,8 +99,8 @@ mip_cmd_result mip_system_default_comm_mode(mip_interface* device); /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_filter.c b/src/c/mip/definitions/data_filter.c index 74544ec13..cd2d37b8c 100644 --- a/src/c/mip/definitions/data_filter.c +++ b/src/c/mip/definitions/data_filter.c @@ -1563,8 +1563,8 @@ bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(co #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_filter.h b/src/c/mip/definitions/data_filter.h index 96c0890f6..c1df6518b 100644 --- a/src/c/mip/definitions/data_filter.h +++ b/src/c/mip/definitions/data_filter.h @@ -1585,8 +1585,8 @@ bool extract_mip_filter_aiding_frame_config_error_uncertainty_data_from_field(co /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_gnss.c b/src/c/mip/definitions/data_gnss.c index 4aae568b7..34950b55b 100644 --- a/src/c/mip/definitions/data_gnss.c +++ b/src/c/mip/definitions/data_gnss.c @@ -1445,8 +1445,8 @@ bool extract_mip_gnss_galileo_iono_corr_data_from_field(const mip_field_view* fi #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_gnss.h b/src/c/mip/definitions/data_gnss.h index 4ddd6d1ab..aa45f2947 100644 --- a/src/c/mip/definitions/data_gnss.h +++ b/src/c/mip/definitions/data_gnss.h @@ -1790,8 +1790,8 @@ bool extract_mip_gnss_galileo_iono_corr_data_from_field(const mip_field_view* fi /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_sensor.c b/src/c/mip/definitions/data_sensor.c index 15f3c6cb0..776ad480b 100644 --- a/src/c/mip/definitions/data_sensor.c +++ b/src/c/mip/definitions/data_sensor.c @@ -519,8 +519,8 @@ bool extract_mip_sensor_odometer_data_data_from_field(const mip_field_view* fiel #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_sensor.h b/src/c/mip/definitions/data_sensor.h index c8db3ec26..c1312f828 100644 --- a/src/c/mip/definitions/data_sensor.h +++ b/src/c/mip/definitions/data_sensor.h @@ -611,8 +611,8 @@ bool extract_mip_sensor_odometer_data_data_from_field(const mip_field_view* fiel /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_shared.c b/src/c/mip/definitions/data_shared.c index 6cd1a9faa..1d0413326 100644 --- a/src/c/mip/definitions/data_shared.c +++ b/src/c/mip/definitions/data_shared.c @@ -217,8 +217,8 @@ bool extract_mip_shared_external_time_delta_data_from_field(const mip_field_view #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_shared.h b/src/c/mip/definitions/data_shared.h index 77170fb17..3d25b14e7 100644 --- a/src/c/mip/definitions/data_shared.h +++ b/src/c/mip/definitions/data_shared.h @@ -343,8 +343,8 @@ bool extract_mip_shared_external_time_delta_data_from_field(const mip_field_view /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_system.c b/src/c/mip/definitions/data_system.c index 8099d63ce..81d644ff0 100644 --- a/src/c/mip/definitions/data_system.c +++ b/src/c/mip/definitions/data_system.c @@ -111,8 +111,8 @@ bool extract_mip_system_gpio_analog_value_data_from_field(const mip_field_view* #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/definitions/data_system.h b/src/c/mip/definitions/data_system.h index 11f9c4cf9..89b639987 100644 --- a/src/c/mip/definitions/data_system.h +++ b/src/c/mip/definitions/data_system.h @@ -168,8 +168,8 @@ bool extract_mip_system_gpio_analog_value_data_from_field(const mip_field_view* /// //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif // __cplusplus diff --git a/src/c/mip/mip_cmdqueue.h b/src/c/mip/mip_cmdqueue.h index aec5e14f0..bc860ec35 100644 --- a/src/c/mip/mip_cmdqueue.h +++ b/src/c/mip/mip_cmdqueue.h @@ -136,7 +136,7 @@ uint16_t mip_cmd_queue_diagnostic_cmd_errors(const mip_cmd_queue* queue); //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip -} // extern "C" #endif diff --git a/src/c/mip/mip_descriptors.c b/src/c/mip/mip_descriptors.c index 4a65112b9..51a3d99d6 100644 --- a/src/c/mip/mip_descriptors.c +++ b/src/c/mip/mip_descriptors.c @@ -165,6 +165,6 @@ void extract_mip_function_selector(microstrain_serializer* serializer, enum mip_ #ifdef __cplusplus -} // namespace mip } // extern "C" +} // namespace mip #endif // __cplusplus diff --git a/src/c/mip/mip_descriptors.h b/src/c/mip/mip_descriptors.h index 468c8cf56..3373e1e52 100644 --- a/src/c/mip/mip_descriptors.h +++ b/src/c/mip/mip_descriptors.h @@ -54,6 +54,6 @@ void extract_mip_function_selector(microstrain_serializer* serializer, enum mip_ #ifdef __cplusplus } // extern "C" -} // namespace "C" +} // namespace C } // namespace mip #endif // __cplusplus diff --git a/src/c/mip/mip_device_models.h b/src/c/mip/mip_device_models.h index 5b47ce67b..2fb5f4f27 100644 --- a/src/c/mip/mip_device_models.h +++ b/src/c/mip/mip_device_models.h @@ -62,7 +62,7 @@ const char* get_model_name_from_number(mip_model_number model); using ModelNumber = C::mip_model_number; inline ModelNumber getModelFromString(const char* model_or_serial) { return C::get_model_from_string(model_or_serial); } -inline const char* getModelNameFromNumber(ModelNumber model) { return get_model_name_from_number(model); } +inline const char* getModelNameFromNumber(ModelNumber model) { return C::get_model_name_from_number(model); } } // namespace mip diff --git a/src/c/mip/mip_field.h b/src/c/mip/mip_field.h index aa949905e..6c1dbb8d3 100644 --- a/src/c/mip/mip_field.h +++ b/src/c/mip/mip_field.h @@ -119,7 +119,7 @@ bool mip_field_next_in_packet(mip_field_view* field, const mip_packet_view* pack /// #ifdef __cplusplus -} // namespace mip -} // namespace C } // extern "C" +} // namespace C +} // namespace mip #endif diff --git a/src/c/mip/mip_interface.h b/src/c/mip/mip_interface.h index eb7d146e8..0da725613 100644 --- a/src/c/mip/mip_interface.h +++ b/src/c/mip/mip_interface.h @@ -118,7 +118,7 @@ mip_cmd_queue* mip_interface_cmd_queue(mip_interface* device); ///@} #ifdef __cplusplus -} // namespace mip -} // namespace C } // extern "C" +} // namespace C +} // namespace mip #endif diff --git a/src/c/mip/mip_packet.h b/src/c/mip/mip_packet.h index 5d4e2a3cd..e2ad918f7 100644 --- a/src/c/mip/mip_packet.h +++ b/src/c/mip/mip_packet.h @@ -125,7 +125,7 @@ bool mip_packet_is_data(const mip_packet_view* packet); //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus -} // namespace mip -} // namespace C } // extern "C" +} // namespace C +} // namespace mip #endif diff --git a/src/c/mip/mip_parser.h b/src/c/mip/mip_parser.h index 964ecb2f9..c5c85cc1a 100644 --- a/src/c/mip/mip_parser.h +++ b/src/c/mip/mip_parser.h @@ -130,7 +130,7 @@ mip_timeout mip_timeout_from_baudrate(uint32_t baudrate); //////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus -} // namespace mip -} // namespace C } // extern "C" +} // namespace C +} // namespace mip #endif diff --git a/src/c/mip/mip_result.c b/src/c/mip/mip_result.c index e8c08e438..bf9f74541 100644 --- a/src/c/mip/mip_result.c +++ b/src/c/mip/mip_result.c @@ -3,6 +3,7 @@ #ifdef __cplusplus namespace mip { +namespace C { extern "C" { #endif // __cplusplus @@ -17,24 +18,24 @@ const char* mip_cmd_result_to_string(enum mip_cmd_result result) { switch(result) { - // Status codes - case MIP_STATUS_ERROR: return "Error"; - case MIP_STATUS_CANCELLED: return "Canceled"; - case MIP_STATUS_TIMEDOUT: return "Timed out"; - case MIP_STATUS_WAITING: return "Waiting"; - case MIP_STATUS_PENDING: return "Pending"; - case MIP_STATUS_NONE: return "None"; - // Device replies - case MIP_ACK_OK: return "Ok"; - case MIP_NACK_COMMAND_UNKNOWN: return "Unknown Command"; + // Status codes + case MIP_STATUS_ERROR: return "Error"; + case MIP_STATUS_CANCELLED: return "Canceled"; + case MIP_STATUS_TIMEDOUT: return "Timed out"; + case MIP_STATUS_WAITING: return "Waiting"; + case MIP_STATUS_PENDING: return "Pending"; + case MIP_STATUS_NONE: return "None"; + // Device replies + case MIP_ACK_OK: return "Ok"; + case MIP_NACK_COMMAND_UNKNOWN: return "Unknown Command"; case MIP_NACK_INVALID_CHECKSUM: return "Invalid Checksum"; - case MIP_NACK_INVALID_PARAM: return "Invalid Parameter"; - case MIP_NACK_COMMAND_FAILED: return "Command Failed"; - case MIP_NACK_COMMAND_TIMEOUT: return "Device Error"; + case MIP_NACK_INVALID_PARAM: return "Invalid Parameter"; + case MIP_NACK_COMMAND_FAILED: return "Command Failed"; + case MIP_NACK_COMMAND_TIMEOUT: return "Device Error"; default: if(mip_cmd_result_is_user(result)) return "User Status"; - else return "Unknown"; + else return "Unknown"; } } @@ -81,5 +82,6 @@ bool mip_cmd_result_is_ack(enum mip_cmd_result result) #ifdef __cplusplus } // extern "C" +} // namespace C } // namespace mip #endif // __cplusplus diff --git a/src/c/mip/mip_serialization.h b/src/c/mip/mip_serialization.h index 49a38526e..ed314d21d 100644 --- a/src/c/mip/mip_serialization.h +++ b/src/c/mip/mip_serialization.h @@ -16,7 +16,7 @@ void microstrain_serializer_finish_new_field(const microstrain_serializer* seria void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field_view* field); #ifdef __cplusplus -} // namespace mip -} // namespace C } // extern "C" +} // namespace C +} // namespace mip #endif diff --git a/src/cpp/microstrain/CMakeLists.txt b/src/cpp/microstrain/CMakeLists.txt index 837c329eb..5de3ea426 100644 --- a/src/cpp/microstrain/CMakeLists.txt +++ b/src/cpp/microstrain/CMakeLists.txt @@ -1,6 +1,7 @@ -set(MICROSTRAIN_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") - add_subdirectory(common) add_subdirectory(connections) -add_subdirectory(extras) + +if(MICROSTRAIN_ENABLE_EXTRAS) + add_subdirectory(extras) +endif() diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index 72ce5bde6..eb5ab8ba2 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -11,5 +11,4 @@ target_sources(microstrain_common PRIVATE ) target_compile_features(microstrain_common PUBLIC cxx_std_11) -target_include_directories(microstrain_common INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) - +target_include_directories(microstrain_common INTERFACE ${SRC_CPP_DIR}) diff --git a/src/cpp/microstrain/connections/recording/CMakeLists.txt b/src/cpp/microstrain/connections/recording/CMakeLists.txt index 78edfccc3..36854cdc5 100644 --- a/src/cpp/microstrain/connections/recording/CMakeLists.txt +++ b/src/cpp/microstrain/connections/recording/CMakeLists.txt @@ -7,7 +7,4 @@ add_library(microstrain_recording_connection ) target_link_libraries(microstrain_recording_connection PUBLIC microstrain_common) - target_compile_features(microstrain_recording_connection PUBLIC cxx_std_11) -target_include_directories(microstrain_recording_connection INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) - diff --git a/src/cpp/microstrain/connections/serial/CMakeLists.txt b/src/cpp/microstrain/connections/serial/CMakeLists.txt index 94dca37c2..ec0606ff3 100644 --- a/src/cpp/microstrain/connections/serial/CMakeLists.txt +++ b/src/cpp/microstrain/connections/serial/CMakeLists.txt @@ -1,5 +1,5 @@ - +# Add to existing C library. target_sources(microstrain_serial PRIVATE serial_connection.cpp @@ -8,5 +8,3 @@ target_sources(microstrain_serial ) target_compile_features(microstrain_serial PUBLIC cxx_std_11) -target_include_directories(microstrain_serial INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) - diff --git a/src/cpp/microstrain/connections/tcp/CMakeLists.txt b/src/cpp/microstrain/connections/tcp/CMakeLists.txt index 8f37ddf0c..25b49d1a1 100644 --- a/src/cpp/microstrain/connections/tcp/CMakeLists.txt +++ b/src/cpp/microstrain/connections/tcp/CMakeLists.txt @@ -1,13 +1,10 @@ - +# Add to existing C library. target_sources(microstrain_socket PRIVATE tcp_connection.cpp - PUBLIC tcp_connection.hpp ../connection.hpp ) target_compile_features(microstrain_socket PUBLIC cxx_std_11) -target_include_directories(microstrain_socket INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) - diff --git a/src/cpp/microstrain/extras/CMakeLists.txt b/src/cpp/microstrain/extras/CMakeLists.txt index 2e2fce7b0..e51903bbe 100644 --- a/src/cpp/microstrain/extras/CMakeLists.txt +++ b/src/cpp/microstrain/extras/CMakeLists.txt @@ -6,5 +6,4 @@ set(SOURCES add_library(microstrain_extras ${SOURCES}) target_compile_features(microstrain_extras PUBLIC cxx_std_11) -target_include_directories(microstrain_extras INTERFACE ${MICROSTRAIN_INCLUDE_DIR}) - +target_compile_definitions(microstrain_extras INTERFACE "MICROSTRAIN_ENABLE_EXTRAS=1") diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index a711bef3a..5e93545f3 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -16,7 +16,7 @@ target_sources(mip PRIVATE ) target_compile_features(mip PUBLIC cxx_std_11) -target_include_directories(mip INTERFACE ${MIP_INCLUDE_DIR}) +target_include_directories(mip PRIVATE ${MIP_INCLUDE_DIR}) # Get the mipdef list from the C version get_target_property(MIPDEFS mip definitions) @@ -38,6 +38,6 @@ if(MIP_ENABLE_METADATA) add_subdirectory(metadata) endif() -if(MIP_ENABLE_EXTRAS) +if(MICROSTRAIN_ENABLE_EXTRAS) add_subdirectory(extras) endif() diff --git a/src/cpp/mip/extras/CMakeLists.txt b/src/cpp/mip/extras/CMakeLists.txt index 6e204afbd..e9ff431e5 100644 --- a/src/cpp/mip/extras/CMakeLists.txt +++ b/src/cpp/mip/extras/CMakeLists.txt @@ -8,5 +8,4 @@ set(SOURCES add_library(mip_extras ${SOURCES}) target_compile_features(mip_extras PUBLIC cxx_std_11) -target_include_directories(mip_extras INTERFACE ${MIP_INCLUDE_DIR}) - +target_link_libraries(mip_extras PUBLIC microstrain_extras) diff --git a/src/cpp/mip/metadata/CMakeLists.txt b/src/cpp/mip/metadata/CMakeLists.txt index 59941d7e8..9dcc1bf63 100644 --- a/src/cpp/mip/metadata/CMakeLists.txt +++ b/src/cpp/mip/metadata/CMakeLists.txt @@ -21,9 +21,6 @@ if(MICROSTRAIN_CMAKE_DEBUG) endif() add_library(mip_metadata ${META_SOURCES} ${MIPDEF_HEADERS}) - target_compile_features(mip_metadata PUBLIC cxx_std_20) - -target_include_directories(mip_metadata INTERFACE ${MIP_INCLUDE_DIR}) - target_link_libraries(mip_metadata PUBLIC mip) +target_compile_definitions(mip_metadata PUBLIC "MIP_ENABLE_METADATA=1") From ee2e875de813e19c229ddb0f3c0c71476b9cd8b7 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 23 Aug 2024 14:12:49 -0400 Subject: [PATCH 085/147] Doc cleanup (new names) Fixed MIP CMake option for Extras module include --- docs/docs.c | 24 +++++++------- src/c/microstrain/common/serialization.h | 2 +- .../connections/tcp/tcp_connection.cpp | 2 +- src/cpp/mip/CMakeLists.txt | 2 +- src/cpp/mip/mip_interface.hpp | 32 +++++++++---------- 5 files changed, 31 insertions(+), 31 deletions(-) diff --git a/docs/docs.c b/docs/docs.c index 82cba0c54..537940e6a 100644 --- a/docs/docs.c +++ b/docs/docs.c @@ -22,12 +22,12 @@ /// All C++ functions and classes reside within the mip namespace. /// The C functions can be accessed via the mip::C namespace. /// -///@li @ref mip::DeviceInterface Top-level MIP interface class. -///@li @ref mip::PacketRef An interface to a MIP packet for either transmission or reception. -///@li @ref mip::PacketBuf Similar to PacketRef but includes the data buffer. -///@li @ref mip::Field An interface to a MIP field within a packet. -///@li @ref mip::Parser MIP parser class for converting received bytes into packets. -///@li @ref mip::CmdResult Stores the status or result of a MIP command. +///@li @ref mip::Interface Top-level MIP interface class. +///@li @ref mip::PacketView An interface to a MIP packet for either transmission or reception. +///@li @ref mip::PacketBuf Similar to PacketRef but includes the data buffer. +///@li @ref mip::FieldView An interface to a MIP field within a packet. +///@li @ref mip::Parser MIP parser class for converting received bytes into packets. +///@li @ref mip::CmdResult Stores the status or result of a MIP command. /// ///@section quickref_c Quick Reference [C] /// @@ -63,9 +63,9 @@ /// will return a status code. /// /// Sending and receiving to or from the device occurs via two functions: -///@li mip::DeviceInterface::sendToDevice() or +///@li mip::Interface::sendToDevice() or /// mip_interface_send_to_device() for transmission and -///@li mip::DeviceInterface::recvFromDevice() or +///@li mip::Interface::recvFromDevice() or /// mip_interface_recv_from_device() for reception. /// /// Each of these has a corresponding callback to the application. The @@ -132,7 +132,7 @@ ///@par Packet callbacks /// ///@code{.cpp} -/// void packet_callback(void* userdata, const mip::PacketRef& packet, Timestamp parseTime) +/// void packet_callback(void* userdata, const mip::PacketView& packet, Timestamp parseTime) ///@endcode /// /// Packet callbacks are invoked when a packet is received which matches the @@ -149,7 +149,7 @@ ///@par Field callbacks /// ///@code{.cpp} -/// void field_callback(void* userdata, const mip::Field& field, Timestamp parseTime) +/// void field_callback(void* userdata, const mip::FieldView& field, Timestamp parseTime) ///@endcode /// /// Similar to packet callbacks, field callbacks are invoked when a MIP @@ -537,7 +537,7 @@ ///@li Set a high overall device timeout. This is the easiest solution but may cause excess /// delays in your application if the device is unplugged, not powered, etc. ///@li Temporarily set the timeout higher, and restore it after running the long command. -///@li If using C++, use the `mip::DeviceInterface::runCommand` function and pass a large enough +///@li If using C++, use the `mip::Interface::runCommand` function and pass a large enough /// value for the `additionalTime` parameter. This raises the timeout specifically for that /// one command instance and is the recommended option. -/// \ No newline at end of file +/// diff --git a/src/c/microstrain/common/serialization.h b/src/c/microstrain/common/serialization.h index 401ce11c8..01fc1f36f 100644 --- a/src/c/microstrain/common/serialization.h +++ b/src/c/microstrain/common/serialization.h @@ -101,4 +101,4 @@ void microstrain_extract_count(microstrain_serializer* serializer, uint8_t* coun } // namespace microstrain #endif // __cplusplus -//////////////////////////////////////////////////////////////////////////////// \ No newline at end of file +//////////////////////////////////////////////////////////////////////////////// diff --git a/src/cpp/microstrain/connections/tcp/tcp_connection.cpp b/src/cpp/microstrain/connections/tcp/tcp_connection.cpp index 9a4a3d9cb..b77fa2cf5 100644 --- a/src/cpp/microstrain/connections/tcp/tcp_connection.cpp +++ b/src/cpp/microstrain/connections/tcp/tcp_connection.cpp @@ -73,4 +73,4 @@ bool TcpConnection::sendToDevice(const uint8_t* data, size_t length) } } // namespace connections -} // namespace microstrain \ No newline at end of file +} // namespace microstrain diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index 5e93545f3..7ea221a6b 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -38,6 +38,6 @@ if(MIP_ENABLE_METADATA) add_subdirectory(metadata) endif() -if(MICROSTRAIN_ENABLE_EXTRAS) +if(MIP_ENABLE_EXTRAS) add_subdirectory(extras) endif() diff --git a/src/cpp/mip/mip_interface.hpp b/src/cpp/mip/mip_interface.hpp index 799b75d55..c8c4346c5 100644 --- a/src/cpp/mip/mip_interface.hpp +++ b/src/cpp/mip/mip_interface.hpp @@ -67,7 +67,7 @@ class Interface : public C::mip_interface } ///@copydoc mip::C::mip_interface_init - ///@param connection The connection object used to communicate with the device. This object must exist for the life of the DeviceInterface object + ///@param connection The connection object used to communicate with the device. This object must exist for the life of the Interface object Interface(microstrain::Connection* connection, uint8_t* parseBuffer, size_t parseBufferSize, Timeout parseTimeout, Timeout baseReplyTimeout) : Interface(parseBuffer, parseBufferSize, parseTimeout, baseReplyTimeout) { @@ -263,11 +263,11 @@ void Interface::setUpdateFunction() //////////////////////////////////////////////////////////////////////////////// ///@brief Sets the send callback function (derived member function version). /// -///@tparam Derived Derived class type. Must inherit from DeviceInterface. +///@tparam Derived Derived class type. Must inherit from Interface. ///@tparam Send Compile-time pointer to member function of Derived. /// ///@code{.cpp} -/// class MyClass : public mip::DeviceInterface +/// class MyClass : public mip::Interface /// { /// bool sendToDevice(const uint8_t* data, size_t size); /// bool recvFromDevice(uint8_t* data, size_t max_length, Timeout wait_time, size_t* length_out, Timestamp* timestamp_out); @@ -297,10 +297,10 @@ void Interface::setSendFunction() //////////////////////////////////////////////////////////////////////////////// ///@brief Sets the receive callback function (derived member function version). /// -///@tparam Derived Derived class type. Must inherit from DeviceInterface. +///@tparam Derived Derived class type. Must inherit from Interface. ///@tparam Recv Compile-time pointer to member function of Derived. /// -///@see DeviceInterface::setSendFunction() +///@see Interface::setSendFunction() /// template void Interface::setRecvFunction() @@ -318,10 +318,10 @@ void Interface::setRecvFunction() //////////////////////////////////////////////////////////////////////////////// ///@brief Sets the update callback function (derived member function version). /// -///@tparam Derived Derived class type. Must inherit from DeviceInterface. +///@tparam Derived Derived class type. Must inherit from Interface. ///@tparam Update Compile-time pointer to member function of Derived. /// -///@see DeviceInterface::setSendFunction() +///@see Interface::setSendFunction() /// template void Interface::setUpdateFunction() @@ -369,7 +369,7 @@ void Interface::setUpdateFunction() /// }; /// /// DeviceConnection connection; -/// mip::DeviceInterface interface; +/// mip::Interface interface; /// /// interface.setCallbacks(&connection); ///@endcode @@ -426,7 +426,7 @@ void Interface::setCallbacks(T* object) /// // Use the packet data /// } /// -/// DeviceInterface device; +/// Interface device; /// DispatchHandler handler; /// /// void setup() @@ -476,7 +476,7 @@ void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t /// device.registerPacketHandler(packetHandler, descriptorSet, this); /// } /// -/// DeviceInterface device; +/// Interface device; /// DispatchHandler packetHandler; /// }; ///@endcode @@ -513,7 +513,7 @@ void Interface::registerPacketCallback(C::mip_dispatch_handler& handler, uint8_t /// // Use the field data /// } /// -/// DeviceInterface device; +/// Interface device; /// DispatchHandler handler; /// /// void setup() @@ -563,7 +563,7 @@ void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t /// device.registerFieldHandler(fieldHandler, descriptorSet, fieldDescriptor, this); /// } /// -/// DeviceInterface device; +/// Interface device; /// DispatchHandler fieldHandler; /// }; ///@endcode @@ -604,7 +604,7 @@ void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t /// // Use the packet data /// } /// -/// DeviceInterface device; +/// Interface device; /// DispatchHandler handler; /// /// void setup() @@ -663,7 +663,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* use /// // Use the packet data /// } /// -/// DeviceInterface device; +/// Interface device; /// DispatchHandler handler; /// /// void setup() @@ -730,7 +730,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* use /// device.registerDataHandler(accelHandler, this); /// } /// -/// DeviceInterface device; +/// Interface device; /// DispatchHandler accelHandler; /// }; ///@endcode @@ -791,7 +791,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* o /// device.registerDataHandler(accelHandler, this); /// } /// -/// DeviceInterface device; +/// Interface device; /// DispatchHandler accelHandler; /// }; ///@endcode From 216080ef10b2ff02fa0216d341000b8f2788878e Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 23 Aug 2024 14:42:44 -0400 Subject: [PATCH 086/147] - Add interface lib to enable warnings, etc on all libraries privately. - Fix potential endianness issue between different C++ standards. - Fix #if MICROSTRAIN_HAS_SPAN. --- CMakeLists.txt | 49 +++++++++++++------ examples/CMakeLists.txt | 2 +- src/c/microstrain/common/CMakeLists.txt | 12 +---- .../connections/serial/CMakeLists.txt | 1 + .../connections/tcp/CMakeLists.txt | 1 + src/c/mip/CMakeLists.txt | 1 + src/cpp/microstrain/common/platform.hpp | 2 +- .../common/serialization/readwrite.hpp | 21 +++++--- .../microstrain/connections/connection.hpp | 4 +- .../connections/recording/CMakeLists.txt | 1 + src/cpp/microstrain/extras/CMakeLists.txt | 2 +- src/cpp/mip/extras/CMakeLists.txt | 4 +- src/cpp/mip/metadata/CMakeLists.txt | 1 + 13 files changed, 60 insertions(+), 41 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9e1a0209b..a7242440f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -26,17 +26,16 @@ option(MICROSTRAIN_ENABLE_LOGGING "Build with logging functions enabled" ON) set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_INFO" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") -option(MICROSTRAIN_ENABLE_SERIAL "Build serial connection support into the library and examples" ON) -option(MICROSTRAIN_ENABLE_TCP "Build TCP connection support into the library and examples" ON) - option(MICROSTRAIN_ENABLE_CPP "Enables the C++ API. Turn off to avoid compiling the C++ API." ON) #option(MICROSTRAIN_ENABLE_CPP_C_NAMESPACE "Wraps the C api in a C++ namespace to avoid global namespace pollution (e.g. microstrain::C::microstrain_serial_port)" ${MICROSTRAIN_ENABLE_CPP}) +option(MICROSTRAIN_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) +option(MICROSTRAIN_ENABLE_SERIAL "Build serial connection support into the library and examples" ON) +option(MICROSTRAIN_ENABLE_TCP "Build TCP connection support into the library and examples" ON) + # MIP options -option(MIP_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) - if(NOT DEFINED MIP_ENABLE_METADATA) include("${MIP_CMAKE_DIR}/check_metadata.cmake") message("MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") @@ -105,6 +104,35 @@ set(VERSION_OUT_FILE "${SRC_DIR}/c/mip/mip_version.h") configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) +# +# Common preprocessor definitions +# +add_library(microstrain_private INTERFACE) + +# Disable windows defined min/max +# Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) +if(WIN32) + target_compile_definitions(microstrain_private + PUBLIC + "NOMINMAX=1" + "_WIN32_WINNT=_WIN32_WINNT_WINXP" + ) +endif() + +if(MSVC) + target_compile_options(microstrain_private INTERFACE + "/W4" # Enable warnings + "/Zc:__cplusplus" # Enable updated __cplusplus value + ) +else() + target_compile_options(microstrain_private INTERFACE + "-Wall" # Extra warnings + "-Wextra" + ) +endif() + + + # Suppress warnings due to adding files with target_sources. cmake_policy(SET CMP0076 NEW) @@ -127,17 +155,6 @@ endif() -# -# Preprocessor definitions -# - -if(MSVC) - add_compile_options(/W4) -else() - add_compile_options(-Wall -Wextra) -endif() - - # # Libraries # diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index d8fe59d64..712f7ea4e 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -34,7 +34,7 @@ set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) target_compile_definitions(example_utils PUBLIC ${MIP_EXAMPLE_DEFS}) #target_include_directories(example_utils PRIVATE ${SRC_DIR}) -target_link_libraries(example_utils PUBLIC mip ${EXAMPLE_LIBS}) +target_link_libraries(example_utils PUBLIC mip ${EXAMPLE_LIBS} microstrain_private) list(APPEND EXAMPLE_LIBS example_utils) diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index d1ccab161..dbf4959e1 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -9,7 +9,7 @@ add_library(microstrain_common "serialization.c" "serialization.h" ) - +target_link_libraries(microstrain_common PRIVATE microstrain_private) target_compile_features(microstrain_common PUBLIC c_std_11) target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") @@ -24,13 +24,3 @@ if(MICROSTRAIN_ENABLE_LOGGING) endif() target_include_directories(microstrain_common INTERFACE ${SRC_C_DIR}) - -# Disable windows defined min/max -# Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) -if(WIN32) - target_compile_definitions(microstrain_common - PUBLIC - "NOMINMAX=1" - "_WIN32_WINNT=_WIN32_WINNT_WINXP" - ) -endif() diff --git a/src/c/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt index a15d50227..803d0c8e2 100644 --- a/src/c/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -4,6 +4,7 @@ add_library(microstrain_serial "serial_port.c" ) +target_link_libraries(microstrain_serial PRIVATE microstrain_private) target_compile_features(microstrain_serial PUBLIC c_std_11) target_compile_definitions(microstrain_serial PUBLIC "MICROSTRAIN_ENABLE_SERIAL=1") target_link_libraries(microstrain_serial PUBLIC microstrain_common) diff --git a/src/c/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt index 801aab2be..90be4d461 100644 --- a/src/c/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -4,6 +4,7 @@ add_library(microstrain_socket "tcp_socket.c" ) +target_link_libraries(microstrain_socket PRIVATE microstrain_private) target_compile_features(microstrain_socket PUBLIC c_std_11) target_compile_definitions(microstrain_socket PUBLIC "MICROSTRAIN_ENABLE_TCP=1") target_link_libraries(microstrain_socket PUBLIC microstrain_common) diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index faab57263..efecc4234 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -36,6 +36,7 @@ add_library(mip "utils/byte_ring.h" ) +target_link_libraries(mip PRIVATE microstrain_private) target_compile_features(mip PUBLIC c_std_11) target_link_libraries(mip PUBLIC microstrain_common) diff --git a/src/cpp/microstrain/common/platform.hpp b/src/cpp/microstrain/common/platform.hpp index 2365f1a0d..c3830d902 100644 --- a/src/cpp/microstrain/common/platform.hpp +++ b/src/cpp/microstrain/common/platform.hpp @@ -21,7 +21,7 @@ #define IF_CONSTEXPR if #endif -#if __cpp_lib_optional >= 201606L || __cplusplus >= 201703L +#if __cpp_lib_optional >= 201606L #define MICROSTRAIN_HAS_OPTIONAL #endif #if __cpp_lib_span >= 202002L diff --git a/src/cpp/microstrain/common/serialization/readwrite.hpp b/src/cpp/microstrain/common/serialization/readwrite.hpp index ceee74b4d..fd16e5128 100644 --- a/src/cpp/microstrain/common/serialization/readwrite.hpp +++ b/src/cpp/microstrain/common/serialization/readwrite.hpp @@ -7,25 +7,30 @@ #include #include -#if __cpp_lib_endian >= 201907L -#include -#endif +// Don't depend on C++ standard since it could be different between +// compiling this lib and the user's project including this file. +// In that case there would be two conflicting definitions of Endian! +// Maybe use a CMake variable in the future. +// +//#if __cpp_lib_endian >= 201907L +//#include +//#endif namespace microstrain { namespace serialization { -#if __cpp_lib_endian >= 201907L -using Endian = std::endian; -#else +//#if __cpp_lib_endian >= 201907L +//using Endian = std::endian; +//#else enum class Endian { little, big, - //native = little, // Todo + //native = little, }; -#endif +//#endif // // Write to buffer diff --git a/src/cpp/microstrain/connections/connection.hpp b/src/cpp/microstrain/connections/connection.hpp index bf0ce29f9..e74fe8a40 100644 --- a/src/cpp/microstrain/connections/connection.hpp +++ b/src/cpp/microstrain/connections/connection.hpp @@ -6,7 +6,7 @@ #include #include -#if MICROSTRAIN_HAS_SPAN +#ifdef MICROSTRAIN_HAS_SPAN #include #endif @@ -34,7 +34,7 @@ class Connection virtual bool sendToDevice(const uint8_t* data, size_t length) = 0; virtual bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) = 0; -#if MICROSTRAIN_HAS_SPAN +#ifdef MICROSTRAIN_HAS_SPAN bool sendToDevice(std::span data) { return sendToDevice(data.data(), data.size()); } bool recvFromDevice(std::span& buffer, unsigned int wait_time_ms, EmbeddedTimestamp* timestamp_out) { size_t length = 0; diff --git a/src/cpp/microstrain/connections/recording/CMakeLists.txt b/src/cpp/microstrain/connections/recording/CMakeLists.txt index 36854cdc5..37f3cca7b 100644 --- a/src/cpp/microstrain/connections/recording/CMakeLists.txt +++ b/src/cpp/microstrain/connections/recording/CMakeLists.txt @@ -6,5 +6,6 @@ add_library(microstrain_recording_connection ../connection.hpp ) +target_link_libraries(microstrain_recording_connection PRIVATE microstrain_private) target_link_libraries(microstrain_recording_connection PUBLIC microstrain_common) target_compile_features(microstrain_recording_connection PUBLIC cxx_std_11) diff --git a/src/cpp/microstrain/extras/CMakeLists.txt b/src/cpp/microstrain/extras/CMakeLists.txt index e51903bbe..dfa3e6583 100644 --- a/src/cpp/microstrain/extras/CMakeLists.txt +++ b/src/cpp/microstrain/extras/CMakeLists.txt @@ -6,4 +6,4 @@ set(SOURCES add_library(microstrain_extras ${SOURCES}) target_compile_features(microstrain_extras PUBLIC cxx_std_11) -target_compile_definitions(microstrain_extras INTERFACE "MICROSTRAIN_ENABLE_EXTRAS=1") +target_compile_definitions(microstrain_extras PUBLIC "MICROSTRAIN_ENABLE_EXTRAS=1") diff --git a/src/cpp/mip/extras/CMakeLists.txt b/src/cpp/mip/extras/CMakeLists.txt index e9ff431e5..da69f61f5 100644 --- a/src/cpp/mip/extras/CMakeLists.txt +++ b/src/cpp/mip/extras/CMakeLists.txt @@ -7,5 +7,7 @@ set(SOURCES ) add_library(mip_extras ${SOURCES}) +target_link_libraries(mip_extras PRIVATE microstrain_private) target_compile_features(mip_extras PUBLIC cxx_std_11) -target_link_libraries(mip_extras PUBLIC microstrain_extras) +target_link_libraries(mip_extras PUBLIC mip microstrain_extras) +target_compile_definitions(mip_extras PUBLIC "MIP_ENABLE_EXTRAS=1") diff --git a/src/cpp/mip/metadata/CMakeLists.txt b/src/cpp/mip/metadata/CMakeLists.txt index 9dcc1bf63..aa17e68b5 100644 --- a/src/cpp/mip/metadata/CMakeLists.txt +++ b/src/cpp/mip/metadata/CMakeLists.txt @@ -21,6 +21,7 @@ if(MICROSTRAIN_CMAKE_DEBUG) endif() add_library(mip_metadata ${META_SOURCES} ${MIPDEF_HEADERS}) +target_link_libraries(mip_metadata PRIVATE microstrain_private) target_compile_features(mip_metadata PUBLIC cxx_std_20) target_link_libraries(mip_metadata PUBLIC mip) target_compile_definitions(mip_metadata PUBLIC "MIP_ENABLE_METADATA=1") From ffd6c1a493a85e091f2107c05e69dec1395cb345 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 23 Aug 2024 14:59:21 -0400 Subject: [PATCH 087/147] - Add metadata/definitions/common.hpp to CMakeLists.txt. --- src/cpp/mip/metadata/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/cpp/mip/metadata/CMakeLists.txt b/src/cpp/mip/metadata/CMakeLists.txt index aa17e68b5..03e620bf2 100644 --- a/src/cpp/mip/metadata/CMakeLists.txt +++ b/src/cpp/mip/metadata/CMakeLists.txt @@ -7,6 +7,8 @@ set(META_SOURCES "mip_metadata.hpp" "mip_structures.hpp" "mip_meta_utils.hpp" + + "definitions/common.hpp" ) # Get the mipdef list from the C version From 70f47cea320c90e7639151d91ad7e785df7cee16 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 26 Aug 2024 12:31:52 -0400 Subject: [PATCH 088/147] Fix compilation errors and warning. --- CMakeLists.txt | 2 +- examples/watch_imu.c | 1 + src/cpp/mip/mip_interface.hpp | 2 +- 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a7242440f..717290c7c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -113,7 +113,7 @@ add_library(microstrain_private INTERFACE) # Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) if(WIN32) target_compile_definitions(microstrain_private - PUBLIC + INTERFACE "NOMINMAX=1" "_WIN32_WINNT=_WIN32_WINNT_WINXP" ) diff --git a/examples/watch_imu.c b/examples/watch_imu.c index 1416c4d3c..89de7abe1 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -3,6 +3,7 @@ #include #include #include +#include #include #include diff --git a/src/cpp/mip/mip_interface.hpp b/src/cpp/mip/mip_interface.hpp index c8c4346c5..a247706b7 100644 --- a/src/cpp/mip/mip_interface.hpp +++ b/src/cpp/mip/mip_interface.hpp @@ -825,7 +825,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* o template void Interface::registerExtractor(C::mip_dispatch_handler& handler, DataField* field, uint8_t descriptorSet) { - auto callback = [](void* pointer, const C::mip_field_view* field, Timestamp timestamp) + auto callback = [](void* pointer, const C::mip_field_view* field, Timestamp /*timestamp*/) { FieldView(*field).extract( *static_cast(pointer) ); }; From 0f1ff364ff4bfa4d3df51d2973e8a43a23f8930f Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 26 Aug 2024 12:32:59 -0400 Subject: [PATCH 089/147] Fix compilation error in watch_imu example. --- examples/watch_imu.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/watch_imu.c b/examples/watch_imu.c index 89de7abe1..25542dfbb 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -3,7 +3,7 @@ #include #include #include -#include +#include #include #include @@ -13,7 +13,7 @@ #include #include -#ifdef MICROSTRAIN_PLATFORM_WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS #else #include #endif From 3b826be743edf15240c8d6fc42a14bbdbc506d82 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 27 Aug 2024 15:01:55 -0400 Subject: [PATCH 090/147] Fix various MSVC warnings. --- CMakeLists.txt | 5 +-- examples/CV7/CV7_example.c | 21 +++++++---- examples/CV7/CV7_example.cpp | 8 ++--- examples/CV7_INS/CV7_INS_simple_example.cpp | 18 +++++----- .../CV7_INS/CV7_INS_simple_ublox_example.cpp | 8 ++--- examples/CV7_INS/simple_ublox_parser.hpp | 6 ++-- examples/CV7_INS/ublox_device.hpp | 16 ++++----- examples/CX5_GX5_45/CX5_GX5_45_example.c | 16 +++++---- examples/CX5_GX5_45/CX5_GX5_45_example.cpp | 10 +++--- .../CX5_GX5_CV5_15_25_example.c | 14 +++++--- .../CX5_GX5_CV5_15_25_example.cpp | 8 ++--- examples/GQ7/GQ7_example.c | 12 ++++--- examples/GQ7/GQ7_example.cpp | 12 +++---- examples/device_info.cpp | 2 +- examples/example_utils.cpp | 6 ++-- examples/threading.cpp | 2 +- examples/watch_imu.c | 14 ++++---- examples/watch_imu.cpp | 6 ++-- src/c/microstrain/common/logging.c | 35 +++++++++---------- src/c/microstrain/common/logging.h | 6 ++-- .../connections/serial/serial_port.c | 19 +++++----- .../microstrain/connections/tcp/tcp_socket.c | 2 +- src/c/mip/mip_device_models.c | 1 + src/c/mip/mip_result.c | 1 + src/cpp/microstrain/common/index.hpp | 2 +- .../recording/recording_connection.cpp | 4 +-- src/cpp/mip/mip_result.hpp | 2 +- 27 files changed, 138 insertions(+), 118 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 717290c7c..9c165c3e8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -121,8 +121,9 @@ endif() if(MSVC) target_compile_options(microstrain_private INTERFACE - "/W4" # Enable warnings - "/Zc:__cplusplus" # Enable updated __cplusplus value + "/external:anglebrackets" # Treat angle brackets as system includes + "/external:W0" # No warnings from system includes + "/Zc:__cplusplus" # Enable updated __cplusplus value ) else() target_compile_options(microstrain_private INTERFACE diff --git a/examples/CV7/CV7_example.c b/examples/CV7/CV7_example.c index bb308bddc..8c402d5c7 100644 --- a/examples/CV7/CV7_example.c +++ b/examples/CV7/CV7_example.c @@ -73,8 +73,8 @@ const uint8_t FILTER_PITCH_EVENT_ACTION_ID = 2; //Required MIP interface user-defined functions mip_timestamp get_current_timestamp(); -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out); -bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length); +bool mip_interface_user_recv_from_device(mip_interface* device_, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out); +bool mip_interface_user_send_to_device(mip_interface* device_, const uint8_t* data, size_t length); int usage(const char* argv0); @@ -360,6 +360,9 @@ int main(int argc, const char* argv[]) void handle_filter_event_source(void* user, const mip_field_view* field, mip_timestamp timestamp) { + (void)user; + (void)timestamp; + mip_shared_event_source_data data; if(extract_mip_shared_event_source_data_from_field(field, &data)) @@ -389,10 +392,12 @@ mip_timestamp get_current_timestamp() // MIP Interface User Recv Data Function //////////////////////////////////////////////////////////////////////////////// -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) +bool mip_interface_user_recv_from_device(mip_interface* device_, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) { + (void)device_; + *timestamp_out = get_current_timestamp(); - return serial_port_read(&device_port, buffer, max_length, wait_time, out_length); + return serial_port_read(&device_port, buffer, max_length, (int)wait_time, out_length); } @@ -400,8 +405,10 @@ bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, // MIP Interface User Send Data Function //////////////////////////////////////////////////////////////////////////////// -bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length) +bool mip_interface_user_send_to_device(mip_interface* device_, const uint8_t* data, size_t length) { + (void)device_; + size_t bytes_written; return serial_port_write(&device_port, data, length, &bytes_written); @@ -432,8 +439,8 @@ void exit_gracefully(const char *message) if(serial_port_is_open(&device_port)) serial_port_close(&device_port); -#ifdef _WIN32 - int dummy = getchar(); +#ifdef MICROSTRAIN_PLATFORM_WINDOWS + getchar(); #endif exit(0); diff --git a/examples/CV7/CV7_example.cpp b/examples/CV7/CV7_example.cpp index 627270c43..a7352cf37 100644 --- a/examples/CV7/CV7_example.cpp +++ b/examples/CV7/CV7_example.cpp @@ -81,7 +81,7 @@ int main(int argc, const char* argv[]) std::unique_ptr utils; try { utils = handleCommonArgs(argc, argv); - } catch(const std::underflow_error& ex) { + } catch(const std::underflow_error&) { return printCommonUsage(argv); } catch(const std::exception& ex) { fprintf(stderr, "Error: %s\n", ex.what()); @@ -136,7 +136,7 @@ int main(int argc, const char* argv[]) { data_sensor::DATA_MAG_SCALED, sensor_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_sensor::DESCRIPTOR_SET, sensor_descriptors.size(), sensor_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeMessageFormat(*device, data_sensor::DESCRIPTOR_SET, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor message format!"); @@ -158,7 +158,7 @@ int main(int argc, const char* argv[]) { data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, filter_descriptors.size(), filter_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); @@ -350,7 +350,7 @@ void exit_gracefully(const char *message) if(message) printf("%s\n", message); -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS printf("Press ENTER to exit...\n"); int dummy = getchar(); #endif diff --git a/examples/CV7_INS/CV7_INS_simple_example.cpp b/examples/CV7_INS/CV7_INS_simple_example.cpp index 53f940d68..91a00f9d8 100644 --- a/examples/CV7_INS/CV7_INS_simple_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_example.cpp @@ -70,7 +70,7 @@ int main(int argc, const char* argv[]) std::unique_ptr utils; try { utils = handleCommonArgs(argc, argv); - } catch(const std::underflow_error& ex) { + } catch(const std::underflow_error&) { return printCommonUsage(argv); } catch(const std::exception& ex) { fprintf(stderr, "Error: %s\n", ex.what()); @@ -170,7 +170,7 @@ int main(int argc, const char* argv[]) { data_filter::DATA_VEL_NED, filter_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, filter_descriptors.size(), filter_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); // @@ -250,8 +250,8 @@ int main(int argc, const char* argv[]) external_measurement_time.nanoseconds = current_timestamp * uint64_t(1000000); // External heading command - float external_heading = 0.0; - float external_heading_uncertainty = 0.001; + float external_heading = 0.0f; + float external_heading_uncertainty = 0.001f; if(commands_aiding::headingTrue(*device, external_measurement_time, external_heading_sensor_id, external_heading, external_heading_uncertainty, 0x0001) != CmdResult::ACK_OK) printf("WARNING: Failed to send external heading to CV7-INS\n"); @@ -264,14 +264,14 @@ int main(int argc, const char* argv[]) printf("WARNING: Failed to send external position to CV7-INS\n"); // External global velocity command - float ned_velocity[3] = {0.0, 0.0, 0.0}; - float ned_velocity_uncertainty[3] = {0.1, 0.1, 0.1}; + float ned_velocity[3] = {0.0f, 0.0f, 0.0f}; + float ned_velocity_uncertainty[3] = {0.1f, 0.1f, 0.1f}; if(commands_aiding::velNed(*device, external_measurement_time, gnss_antenna_sensor_id, ned_velocity, ned_velocity_uncertainty, 0x0007) != CmdResult::ACK_OK) printf("WARNING: Failed to send external NED velocity to CV7-INS\n"); // External vehicle frame velocity command - float vehicle_frame_velocity[3] = {0.0, 0.0, 0.0}; - float vehicle_frame_velocity_uncertainty[3] = {0.1, 0.1, 0.1}; + float vehicle_frame_velocity[3] = {0.0f, 0.0f, 0.0f}; + float vehicle_frame_velocity_uncertainty[3] = {0.1f, 0.1f, 0.1f}; if(commands_aiding::velBodyFrame(*device, external_measurement_time, vehicle_frame_velocity_sensor_id, vehicle_frame_velocity, vehicle_frame_velocity_uncertainty, 0x0007) != CmdResult::ACK_OK) printf("WARNING: Failed to send external vehicle frame velocity to CV7-INS\n"); @@ -346,7 +346,7 @@ void exit_gracefully(const char *message) if(message) printf("%s\n", message); -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS printf("Press ENTER to exit...\n"); int dummy = getchar(); #endif diff --git a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp index 74c674213..75476ba73 100644 --- a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp @@ -176,7 +176,7 @@ int main(int argc, const char* argv[]) { data_system::DATA_TIME_SYNC_STATUS, system_data_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_system::DESCRIPTOR_SET, system_data_descriptors.size(), system_data_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeMessageFormat(*device, data_system::DESCRIPTOR_SET, static_cast(system_data_descriptors.size()), system_data_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set system data message format!"); @@ -332,7 +332,7 @@ int main(int argc, const char* argv[]) printf("WARNING: Failed to send week number time update to CV7-INS\n"); // Send time of week update to device - uint32_t time_of_week_int = floor(pvt_message.time_of_week); + uint32_t time_of_week_int = static_cast(floor(pvt_message.time_of_week)); if (!commands_base::writeGpsTimeUpdate(*device, commands_base::GpsTimeUpdate::FieldId::TIME_OF_WEEK, time_of_week_int)) printf("WARNING: Failed to send time of week update to CV7-INS\n"); @@ -371,7 +371,7 @@ int main(int argc, const char* argv[]) uint64_t convert_gps_tow_to_nanoseconds(int week_number, float time_of_week) { - return floor(float(week_number) * 604800 * 1e9 + time_of_week * 1e9); + return static_cast(floor(float(week_number) * 604800 * 1e9 + time_of_week * 1e9)); } time_t time_from_ymd(int year, int month, int day) @@ -497,7 +497,7 @@ void exit_gracefully(const char *message) if(message) printf("%s\n", message); -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS std::cout << "Press ENTER to exit..." << std::endl; int dummy = getchar(); #endif diff --git a/examples/CV7_INS/simple_ublox_parser.hpp b/examples/CV7_INS/simple_ublox_parser.hpp index c86aef1e5..459889b46 100644 --- a/examples/CV7_INS/simple_ublox_parser.hpp +++ b/examples/CV7_INS/simple_ublox_parser.hpp @@ -41,10 +41,10 @@ namespace mip ck_a = 0; ck_b = 0; - int num_bytes = packet.size(); - int num_bytes_without_checksum = num_bytes - 2; + size_t num_bytes = packet.size(); + size_t num_bytes_without_checksum = num_bytes - 2; - for (int i = 2; i < num_bytes_without_checksum; i++) { + for (size_t i = 2; i < num_bytes_without_checksum; i++) { ck_a += packet[i]; ck_b += ck_a; } diff --git a/examples/CV7_INS/ublox_device.hpp b/examples/CV7_INS/ublox_device.hpp index 23d48da81..93035e709 100644 --- a/examples/CV7_INS/ublox_device.hpp +++ b/examples/CV7_INS/ublox_device.hpp @@ -108,24 +108,24 @@ namespace mip ublox_message.utc_year = ublox_message_raw.utc_year; ublox_message.utc_month = ublox_message_raw.utc_month; ublox_message.utc_day = ublox_message_raw.utc_day; - ublox_message.time_of_week = ublox_message_raw.iTOW * 1e-3; + ublox_message.time_of_week = ublox_message_raw.iTOW * 1e-3f; ublox_message.time_valid = ublox_message_raw.time_valid_flag; // LLH position ublox_message.latitude = ublox_message_raw.latitude * 1e-7; ublox_message.longitude = ublox_message_raw.longitude * 1e-7;; ublox_message.height_above_ellipsoid = ublox_message_raw.height_above_ellipsoid * 1e-3; - ublox_message.llh_position_uncertainty[0] = ublox_message_raw.horizontal_accuracy * 1e-3; - ublox_message.llh_position_uncertainty[1] = ublox_message_raw.horizontal_accuracy * 1e-3; - ublox_message.llh_position_uncertainty[2] = ublox_message_raw.vertical_accuracy * 1e-3; + ublox_message.llh_position_uncertainty[0] = float(ublox_message_raw.horizontal_accuracy) * 1e-3f; + ublox_message.llh_position_uncertainty[1] = float(ublox_message_raw.horizontal_accuracy) * 1e-3f; + ublox_message.llh_position_uncertainty[2] = float(ublox_message_raw.vertical_accuracy) * 1e-3f; ublox_message.llh_position_valid = !ublox_message_raw.llh_invalid_flag; // NED velocity - ublox_message.ned_velocity[0] = ublox_message_raw.north_velocity * 1e-3; - ublox_message.ned_velocity[1] = ublox_message_raw.east_velocity * 1e-3; - ublox_message.ned_velocity[2] = ublox_message_raw.down_velocity * 1e-3; + ublox_message.ned_velocity[0] = float(ublox_message_raw.north_velocity) * 1e-3f; + ublox_message.ned_velocity[1] = float(ublox_message_raw.east_velocity) * 1e-3f; + ublox_message.ned_velocity[2] = float(ublox_message_raw.down_velocity) * 1e-3f; for (int i = 0; i < 3; i++) - ublox_message.ned_velocity_uncertainty[i] = ublox_message_raw.speed_accuracy * 1e-3; + ublox_message.ned_velocity_uncertainty[i] = float(ublox_message_raw.speed_accuracy) * 1e-3f; return ublox_message; } diff --git a/examples/CX5_GX5_45/CX5_GX5_45_example.c b/examples/CX5_GX5_45/CX5_GX5_45_example.c index 5b81301c7..e0c44beb2 100644 --- a/examples/CX5_GX5_45/CX5_GX5_45_example.c +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.c @@ -48,10 +48,10 @@ uint8_t parse_buffer[1024]; mip_interface device; //Sensor-to-vehicle frame rotation (Euler Angles) -float sensor_to_vehicle_rotation_euler[3] = {0.0, 0.0, 0.0}; +float sensor_to_vehicle_rotation_euler[3] = {0.0f, 0.0f, 0.0f}; //GNSS antenna offset -float gnss_antenna_offset_meters[3] = {-0.25, 0.0, 0.0}; +float gnss_antenna_offset_meters[3] = {-0.25f, 0.0f, 0.0f}; //Device data stores mip_sensor_gps_timestamp_data sensor_gps_time; @@ -367,10 +367,12 @@ mip_timestamp get_current_timestamp() // MIP Interface User Recv Data Function //////////////////////////////////////////////////////////////////////////////// -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) +bool mip_interface_user_recv_from_device(mip_interface* device_, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) { + (void)device_; + *timestamp_out = get_current_timestamp(); - return serial_port_read(&device_port, buffer, max_length, wait_time, out_length); + return serial_port_read(&device_port, buffer, max_length, (int)wait_time, out_length); } @@ -378,8 +380,10 @@ bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, // MIP Interface User Send Data Function //////////////////////////////////////////////////////////////////////////////// -bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length) +bool mip_interface_user_send_to_device(mip_interface* device_, const uint8_t* data, size_t length) { + (void)device_; + size_t bytes_written; return serial_port_write(&device_port, data, length, &bytes_written); @@ -410,7 +414,7 @@ void exit_gracefully(const char *message) if(serial_port_is_open(&device_port)) serial_port_close(&device_port); -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS int dummy = getchar(); #endif diff --git a/examples/CX5_GX5_45/CX5_GX5_45_example.cpp b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp index 354e2d864..e6fd52a79 100644 --- a/examples/CX5_GX5_45/CX5_GX5_45_example.cpp +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp @@ -87,7 +87,7 @@ int main(int argc, const char* argv[]) std::unique_ptr utils; try { utils = handleCommonArgs(argc, argv); - } catch(const std::underflow_error& ex) { + } catch(const std::underflow_error&) { return printCommonUsage(argv); } catch(const std::exception& ex) { fprintf(stderr, "Error: %s\n", ex.what()); @@ -143,7 +143,7 @@ int main(int argc, const char* argv[]) { data_sensor::DATA_MAG_SCALED, sensor_decimation }, }}; - if(commands_3dm::writeImuMessageFormat(*device, sensor_descriptors.size(), sensor_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeImuMessageFormat(*device, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor message format!"); @@ -156,7 +156,7 @@ int main(int argc, const char* argv[]) }}; //GNSS - if(commands_3dm::writeGpsMessageFormat(*device, gnss_descriptors.size(), gnss_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeGpsMessageFormat(*device, static_cast(gnss_descriptors.size()), gnss_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GNSS1 message format!"); @@ -180,7 +180,7 @@ int main(int argc, const char* argv[]) { data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, }}; - if(commands_3dm::writeFilterMessageFormat(*device, filter_descriptors.size(), filter_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeFilterMessageFormat(*device, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); @@ -332,7 +332,7 @@ void exit_gracefully(const char *message) if(message) printf("%s\n", message); -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS printf("Press ENTER to exit...\n"); int dummy = getchar(); #endif diff --git a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c index 20cc7db4e..d3fb4ab9e 100644 --- a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c @@ -155,7 +155,7 @@ int main(int argc, const char* argv[]) const uint16_t sampling_time = 2000; // The default is 15000 ms and longer sample times are recommended but shortened for convenience mip_cmd_queue* queue = mip_interface_cmd_queue(&device); - const int16_t old_mip_sdk_timeout = mip_cmd_queue_base_reply_timeout(queue); + const mip_timeout old_mip_sdk_timeout = mip_cmd_queue_base_reply_timeout(queue); printf("Capturing gyro bias. This will take %d seconds. \n", sampling_time/1000); mip_cmd_queue_set_base_reply_timeout(queue, sampling_time * 2); float gyro_bias[3] = {0, 0, 0}; @@ -317,10 +317,12 @@ mip_timestamp get_current_timestamp() // MIP Interface User Recv Data Function //////////////////////////////////////////////////////////////////////////////// -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) +bool mip_interface_user_recv_from_device(mip_interface* device_, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) { + (void)device_; + *timestamp_out = get_current_timestamp(); - return serial_port_read(&device_port, buffer, max_length, wait_time, out_length); + return serial_port_read(&device_port, buffer, max_length, (int)wait_time, out_length); } @@ -328,8 +330,10 @@ bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, // MIP Interface User Send Data Function //////////////////////////////////////////////////////////////////////////////// -bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length) +bool mip_interface_user_send_to_device(mip_interface* device_, const uint8_t* data, size_t length) { + (void)device_; + size_t bytes_written; return serial_port_write(&device_port, data, length, &bytes_written); @@ -360,7 +364,7 @@ void exit_gracefully(const char *message) if(serial_port_is_open(&device_port)) serial_port_close(&device_port); -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS int dummy = getchar(); #endif diff --git a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp index ab38cd072..ffac10097 100644 --- a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp @@ -106,7 +106,7 @@ int main(int argc, const char* argv[]) float gyro_bias[3] = {0, 0, 0}; const uint32_t sampling_time = 2000; // The default is 15000 ms and longer sample times are recommended but shortened for convenience - const int32_t old_mip_sdk_timeout = device->baseReplyTimeout(); + const Timeout old_mip_sdk_timeout = device->baseReplyTimeout(); printf("Capturing gyro bias. This will take %d seconds \n", sampling_time/1000); device->setBaseReplyTimeout(sampling_time * 2); @@ -149,7 +149,7 @@ int main(int argc, const char* argv[]) { data_sensor::DATA_GYRO_SCALED, sensor_decimation }, }}; - if(commands_3dm::writeImuMessageFormat(*device, sensor_descriptors.size(), sensor_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeImuMessageFormat(*device, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor message format!"); @@ -173,7 +173,7 @@ int main(int argc, const char* argv[]) { data_filter::DATA_COMPENSATED_ACCELERATION, filter_decimation }, }}; - if(commands_3dm::writeFilterMessageFormat(*device, filter_descriptors.size(), filter_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeFilterMessageFormat(*device, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); @@ -293,7 +293,7 @@ void exit_gracefully(const char *message) if(message) printf("%s\n", message); -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS int dummy = getchar(); #endif diff --git a/examples/GQ7/GQ7_example.c b/examples/GQ7/GQ7_example.c index 5a56bff73..5ca7ade6c 100644 --- a/examples/GQ7/GQ7_example.c +++ b/examples/GQ7/GQ7_example.c @@ -401,10 +401,12 @@ mip_timestamp get_current_timestamp() // MIP Interface User Recv Data Function //////////////////////////////////////////////////////////////////////////////// -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) +bool mip_interface_user_recv_from_device(mip_interface* device_, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) { + (void)device_; + *timestamp_out = get_current_timestamp(); - return serial_port_read(&device_port, buffer, max_length, wait_time, out_length); + return serial_port_read(&device_port, buffer, max_length, (int)wait_time, out_length); } @@ -412,8 +414,10 @@ bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, // MIP Interface User Send Data Function //////////////////////////////////////////////////////////////////////////////// -bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length) +bool mip_interface_user_send_to_device(mip_interface* device_, const uint8_t* data, size_t length) { + (void)device_; + size_t bytes_written; return serial_port_write(&device_port, data, length, &bytes_written); @@ -444,7 +448,7 @@ void exit_gracefully(const char *message) if(serial_port_is_open(&device_port)) serial_port_close(&device_port); -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS int dummy = getchar(); #endif diff --git a/examples/GQ7/GQ7_example.cpp b/examples/GQ7/GQ7_example.cpp index 235d80902..ba057334e 100644 --- a/examples/GQ7/GQ7_example.cpp +++ b/examples/GQ7/GQ7_example.cpp @@ -87,7 +87,7 @@ int main(int argc, const char* argv[]) std::unique_ptr utils; try { utils = handleCommonArgs(argc, argv); - } catch(const std::underflow_error& ex) { + } catch(const std::underflow_error&) { return printCommonUsage(argv); } catch(const std::exception& ex) { fprintf(stderr, "Error: %s\n", ex.what()); @@ -143,7 +143,7 @@ int main(int argc, const char* argv[]) { data_sensor::DATA_MAG_SCALED, sensor_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_sensor::DESCRIPTOR_SET, sensor_descriptors.size(), sensor_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeMessageFormat(*device, data_sensor::DESCRIPTOR_SET, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor message format!"); @@ -156,11 +156,11 @@ int main(int argc, const char* argv[]) }}; //GNSS1 - if(commands_3dm::writeMessageFormat(*device, data_gnss::MIP_GNSS1_DATA_DESC_SET, gnss_descriptors.size(), gnss_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeMessageFormat(*device, data_gnss::MIP_GNSS1_DATA_DESC_SET, static_cast(gnss_descriptors.size()), gnss_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GNSS1 message format!"); //GNSS2 - if(commands_3dm::writeMessageFormat(*device, data_gnss::MIP_GNSS2_DATA_DESC_SET, gnss_descriptors.size(), gnss_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeMessageFormat(*device, data_gnss::MIP_GNSS2_DATA_DESC_SET, static_cast(gnss_descriptors.size()), gnss_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GNSS2 message format!"); @@ -184,7 +184,7 @@ int main(int argc, const char* argv[]) { data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, filter_descriptors.size(), filter_descriptors.data()) != CmdResult::ACK_OK) + if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); @@ -366,7 +366,7 @@ void exit_gracefully(const char *message) if(message) printf("%s\n", message); -#ifdef _WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS printf("Press ENTER to exit...\n"); int dummy = getchar(); #endif diff --git a/examples/device_info.cpp b/examples/device_info.cpp index 2f36d7306..209cab11a 100644 --- a/examples/device_info.cpp +++ b/examples/device_info.cpp @@ -65,7 +65,7 @@ int main(int argc, const char* argv[]) printf("Error: command completed with NACK: %s (%d)\n", result.name(), result.value); } } - catch(const std::underflow_error& ex) + catch(const std::underflow_error&) { return printCommonUsage(argv); } diff --git a/examples/example_utils.cpp b/examples/example_utils.cpp index 05e8bb4da..b051022e5 100644 --- a/examples/example_utils.cpp +++ b/examples/example_utils.cpp @@ -8,7 +8,7 @@ #include "example_utils.hpp" -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS #define PORT_KEY "COM" #else #define PORT_KEY "/dev/" @@ -20,7 +20,7 @@ mip::Timestamp getCurrentTimestamp() return duration_cast( steady_clock::now().time_since_epoch() ).count(); } -void customLog(void* user, microstrain_log_level level, const char* fmt, va_list args) +void customLog(void* /*user*/, microstrain_log_level level, const char* fmt, va_list args) { // Convert the varargs into a string std::string log; @@ -72,7 +72,7 @@ std::unique_ptr openFromArgs(const std::string& port_or_hostname, #if defined MICROSTRAIN_ENABLE_SERIAL || defined MICROSTRAIN_ENABLE_TCP using RecordingTcpConnection = microstrain::connections::RecordingConnectionWrapper; - example_utils->connection.reset(new RecordingTcpConnection(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, port)); + example_utils->connection.reset(new RecordingTcpConnection(example_utils->recordedFile.get(), example_utils->recordedFile.get(), port_or_hostname, uint16_t(port))); #else // MIP_ENABLE_EXTRAS using TcpConnection = microstrain::connections::TcpConnection; example_utils->connection.reset(new TcpConnection(port_or_hostname, port)); diff --git a/examples/threading.cpp b/examples/threading.cpp index f47c17d86..dd7ff9e26 100644 --- a/examples/threading.cpp +++ b/examples/threading.cpp @@ -149,7 +149,7 @@ int main(int argc, const char* argv[]) deviceThread.join(); #endif } - catch(const std::underflow_error& ex) + catch(const std::underflow_error&) { return printCommonUsage(argv); } diff --git a/examples/watch_imu.c b/examples/watch_imu.c index 25542dfbb..b68e6f98a 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -101,21 +101,21 @@ mip_timestamp get_current_timestamp() } -bool mip_interface_user_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) +bool mip_interface_user_recv_from_device(mip_interface* device_, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* out_length, mip_timestamp* timestamp_out) { - (void)device; + (void)device_; *timestamp_out = get_current_timestamp(); - if( !serial_port_read(&port, buffer, max_length, wait_time, out_length) ) + if( !serial_port_read(&port, buffer, max_length, (int)wait_time, out_length) ) return false; return true; } -bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* data, size_t length) +bool mip_interface_user_send_to_device(mip_interface* device_, const uint8_t* data, size_t length) { - (void)device; + (void)device_; size_t bytes_written; if (!serial_port_write(&port, data, length, &bytes_written)) @@ -127,7 +127,7 @@ bool mip_interface_user_send_to_device(mip_interface* device, const uint8_t* dat bool open_port(const char* name, uint32_t baudrate) { - return serial_port_open(&port, name, baudrate); + return serial_port_open(&port, name, (int)baudrate); } int usage(const char* argv0) @@ -215,7 +215,7 @@ int main(int argc, const char* argv[]) // Process data for 3 seconds. for(unsigned int i=0; i<30; i++) { -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS #else usleep(100000); #endif diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index b933f7a7f..2f5111a1c 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -77,13 +77,13 @@ int run(mip::Interface& device) { mip::data_sensor::DATA_MAG_SCALED, decimation }, }}; - result = mip::commands_3dm::writeMessageFormat(device, mip::data_sensor::DESCRIPTOR_SET, descriptors.size(), descriptors.data()); + result = mip::commands_3dm::writeMessageFormat(device, mip::data_sensor::DESCRIPTOR_SET, static_cast(descriptors.size()), descriptors.data()); if( result == mip::CmdResult::NACK_COMMAND_FAILED ) { // Failed to set message format - maybe this device doesn't have a magnetometer. // Try again without the last descriptor (scaled mag). - result = mip::commands_3dm::writeMessageFormat(device, mip::data_sensor::DESCRIPTOR_SET, descriptors.size()-1, descriptors.data()); + result = mip::commands_3dm::writeMessageFormat(device, mip::data_sensor::DESCRIPTOR_SET, static_cast(descriptors.size()-1), descriptors.data()); } if( result != mip::CmdResult::ACK_OK ) return fprintf(stderr, "Failed to set message format: %s (%d)\n", result.name(), result.value), 1; @@ -134,7 +134,7 @@ int main(int argc, const char* argv[]) { utils = handleCommonArgs(argc, argv); } - catch(const std::underflow_error& ex) + catch(const std::underflow_error&) { return printCommonUsage(argv); } diff --git a/src/c/microstrain/common/logging.c b/src/c/microstrain/common/logging.c index c38d53a98..4f4f4c20c 100644 --- a/src/c/microstrain/common/logging.c +++ b/src/c/microstrain/common/logging.c @@ -26,9 +26,9 @@ void* microstrain_log_user_data_ = NULL; /// void microstrain_logging_init(microstrain_log_callback callback, microstrain_log_level level, void* user) { - microstrain_log_callback_ = callback; - microstrain_log_level_ = level; - microstrain_log_user_data_ = user; + microstrain_log_callback_ = callback; + microstrain_log_level_ = level; + microstrain_log_user_data_ = user; } //////////////////////////////////////////////////////////////////////////////// @@ -36,9 +36,9 @@ void microstrain_logging_init(microstrain_log_callback callback, microstrain_log /// ///@return The currently active logging callback /// -microstrain_log_callback microstrain_logging_callback() +microstrain_log_callback microstrain_logging_callback(void) { - return microstrain_log_callback_; + return microstrain_log_callback_; } //////////////////////////////////////////////////////////////////////////////// @@ -46,9 +46,9 @@ microstrain_log_callback microstrain_logging_callback() /// ///@return The currently active logging level /// -microstrain_log_level microstrain_logging_level() +microstrain_log_level microstrain_logging_level(void) { - return microstrain_log_level_; + return microstrain_log_level_; } //////////////////////////////////////////////////////////////////////////////// @@ -56,9 +56,9 @@ microstrain_log_level microstrain_logging_level() /// ///@return The currently active logging user data /// -void* microstrain_logging_user_data() +void* microstrain_logging_user_data(void) { - return microstrain_log_user_data_; + return microstrain_log_user_data_; } //////////////////////////////////////////////////////////////////////////////// @@ -68,13 +68,12 @@ void* microstrain_logging_user_data() /// void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...) { - const microstrain_log_callback logging_callback = microstrain_logging_callback(); - const microstrain_log_level logging_level = microstrain_logging_level(); - if (logging_callback != NULL && logging_level >= level) - { - va_list args; - va_start(args, fmt); - logging_callback(microstrain_logging_user_data(), level, fmt, args); - va_end(args); - } + const microstrain_log_callback callback = microstrain_logging_callback(); + if(callback != NULL && microstrain_logging_level() >= level) + { + va_list args; + va_start(args, fmt); + callback(microstrain_logging_user_data(), level, fmt, args); + va_end(args); + } } \ No newline at end of file diff --git a/src/c/microstrain/common/logging.h b/src/c/microstrain/common/logging.h index c241cc651..7110a58e4 100644 --- a/src/c/microstrain/common/logging.h +++ b/src/c/microstrain/common/logging.h @@ -43,9 +43,9 @@ typedef void (*microstrain_log_callback)(void* user, microstrain_log_level level void microstrain_logging_init(microstrain_log_callback callback, microstrain_log_level level, void* user); -microstrain_log_callback microstrain_logging_callback(); -microstrain_log_level microstrain_logging_level(); -void* microstrain_logging_user_data(); +microstrain_log_callback microstrain_logging_callback(void); +microstrain_log_level microstrain_logging_level(void); +void* microstrain_logging_user_data(void); void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); diff --git a/src/c/microstrain/connections/serial/serial_port.c b/src/c/microstrain/connections/serial/serial_port.c index b255486a9..534d0ac91 100644 --- a/src/c/microstrain/connections/serial/serial_port.c +++ b/src/c/microstrain/connections/serial/serial_port.c @@ -76,7 +76,7 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) return false; MICROSTRAIN_LOG_DEBUG("Opening serial port %s at %d\n", port_str, baudrate); -#ifdef WIN32 +#ifdef MICROSTRAIN_PLATFORM_WINDOWS BOOL ready; DCB dcb; @@ -111,7 +111,7 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) // If the port string was modified if (added_prefix) { - free(tmp_port_str); + free((char*)tmp_port_str); tmp_port_str = NULL; } @@ -122,7 +122,7 @@ bool serial_port_open(serial_port *port, const char *port_str, int baudrate) return false; } - //Setup the com port buffer sizes + // Set up the com port buffer sizes if(SetupComm(port->handle, COM_PORT_BUFFER_SIZE, COM_PORT_BUFFER_SIZE) == 0) { MICROSTRAIN_LOG_ERROR("Unable to setup com port buffer size (%d)\n", last_error); @@ -260,7 +260,7 @@ bool serial_port_close(serial_port *port) if(!serial_port_is_open(port)) return false; -#ifdef WIN32 //Windows +#ifdef MICROSTRAIN_PLATFORM_WINDOWS //Close the serial port CloseHandle(port->handle); #else //Linux & Mac @@ -273,18 +273,17 @@ bool serial_port_close(serial_port *port) bool serial_port_write(serial_port *port, const void *buffer, size_t num_bytes, size_t *bytes_written) { - *bytes_written = 0; //Check for a valid port handle if(!serial_port_is_open(port)) return false; -#ifdef WIN32 //Windows +#ifdef MICROSTRAIN_PLATFORM_WINDOWS DWORD local_bytes_written; //Call the windows write function - if(WriteFile(port->handle, buffer, num_bytes, &local_bytes_written, NULL)) + if(WriteFile(port->handle, buffer, (DWORD)num_bytes, &local_bytes_written, NULL)) { *bytes_written = local_bytes_written; @@ -339,9 +338,9 @@ bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, int wai DWORD local_bytes_read; //Call the windows read function - if(!ReadFile(port->handle, buffer, num_bytes, &local_bytes_read, NULL)) + if(!ReadFile(port->handle, buffer, (DWORD)num_bytes, &local_bytes_read, NULL)) return false; - *bytes_read = local_bytes_read; + *bytes_read = (size_t)local_bytes_read; #else //Linux // Poll the device before attempting to read any data, so we will only block for 10ms if there is no data available @@ -387,7 +386,7 @@ bool serial_port_read(serial_port *port, void *buffer, size_t num_bytes, int wai uint32_t serial_port_read_count(serial_port *port) { -#ifdef MICROSTRAIN_PLATFORM_WINDOWS //Windows +#ifdef MICROSTRAIN_PLATFORM_WINDOWS // Clear the last error, if any SetLastError(0); #endif diff --git a/src/c/microstrain/connections/tcp/tcp_socket.c b/src/c/microstrain/connections/tcp/tcp_socket.c index d346ace98..7c897c869 100644 --- a/src/c/microstrain/connections/tcp/tcp_socket.c +++ b/src/c/microstrain/connections/tcp/tcp_socket.c @@ -53,7 +53,7 @@ static bool tcp_socket_open_common(tcp_socket* socket_ptr, const char* hostname, hints.ai_flags = 0; char port_str[6]; // Maximum 5 digits - sprintf(port_str, "%d", port); + snprintf(port_str, sizeof(port_str), "%d", port); int result = getaddrinfo(hostname, port_str, &hints, &info); if( result != 0 ) diff --git a/src/c/mip/mip_device_models.c b/src/c/mip/mip_device_models.c index cd0f00d5a..12b8bed75 100644 --- a/src/c/mip/mip_device_models.c +++ b/src/c/mip/mip_device_models.c @@ -73,6 +73,7 @@ const char* get_model_name_from_number(mip_model_number model) case MODEL_3DM_CX5_25: return "3DM-CX5-25"; case MODEL_3DM_CX5_15: return "3DM-CX5-15"; case MODEL_3DM_CX5_10: return "3DM-CX5-10"; + case MODEL_3DM_CL5_10: return "3DM-CL5-10"; case MODEL_3DM_CL5_15: return "3DM-CL5-15"; case MODEL_3DM_CL5_25: return "3DM-CL5-25"; case MODEL_3DM_GQ7: return "3DM-GQ7"; diff --git a/src/c/mip/mip_result.c b/src/c/mip/mip_result.c index bf9f74541..82e8f75a2 100644 --- a/src/c/mip/mip_result.c +++ b/src/c/mip/mip_result.c @@ -33,6 +33,7 @@ const char* mip_cmd_result_to_string(enum mip_cmd_result result) case MIP_NACK_COMMAND_FAILED: return "Command Failed"; case MIP_NACK_COMMAND_TIMEOUT: return "Device Error"; + case MIP_STATUS_USER_START: default: if(mip_cmd_result_is_user(result)) return "User Status"; else return "Unknown"; diff --git a/src/cpp/microstrain/common/index.hpp b/src/cpp/microstrain/common/index.hpp index 69cbb34d5..888ecd3ed 100644 --- a/src/cpp/microstrain/common/index.hpp +++ b/src/cpp/microstrain/common/index.hpp @@ -27,7 +27,7 @@ namespace microstrain class Index { private: - unsigned int INVALID = -1; + unsigned int INVALID = -1U; public: constexpr explicit Index(unsigned int index) : m_index(index) {} diff --git a/src/cpp/microstrain/connections/recording/recording_connection.cpp b/src/cpp/microstrain/connections/recording/recording_connection.cpp index 351cb7035..b5f842344 100644 --- a/src/cpp/microstrain/connections/recording/recording_connection.cpp +++ b/src/cpp/microstrain/connections/recording/recording_connection.cpp @@ -25,7 +25,7 @@ bool RecordingConnection::sendToDevice(const uint8_t* data, size_t length) if( ok && mSendFile != nullptr) { - mSendFile->write(reinterpret_cast(data), length); + mSendFile->write(reinterpret_cast(data), static_cast(length)); mSendFileWritten += length; } @@ -39,7 +39,7 @@ bool RecordingConnection::recvFromDevice(uint8_t* buffer, size_t max_length, uns if (ok && mRecvFile != nullptr) { - mRecvFile->write(reinterpret_cast(buffer), *count_out); + mRecvFile->write(reinterpret_cast(buffer), static_cast(*count_out)); mRecvFileWritten += *count_out; } diff --git a/src/cpp/mip/mip_result.hpp b/src/cpp/mip/mip_result.hpp index 12f6a43b8..886ae3faf 100644 --- a/src/cpp/mip/mip_result.hpp +++ b/src/cpp/mip/mip_result.hpp @@ -38,7 +38,7 @@ struct CmdResult static constexpr C::mip_cmd_result NACK_COMMAND_FAILED = C::MIP_NACK_COMMAND_FAILED; ///<@copydoc C::MIP_NACK_COMMAND_FAILED static constexpr C::mip_cmd_result NACK_COMMAND_TIMEOUT = C::MIP_NACK_COMMAND_TIMEOUT; ///<@copydoc C::MIP_NACK_COMMAND_TIMEOUT -#ifndef _WIN32 // Avoid name conflict with windows.h +#ifndef MICROSTRAIN_PLATFORM_WINDOWS // Avoid name conflict with windows.h static constexpr C::mip_cmd_result STATUS_PENDING = STATUS_QUEUED; #endif From c93b8311ce3e001c0b5e4210ad1bb15fe4d594e0 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 27 Aug 2024 15:17:15 -0400 Subject: [PATCH 091/147] Fix mip_timestamp/timeout to use microstrain_* instead of redefining it. --- src/c/microstrain/common/embedded_time.h | 2 +- src/c/mip/mip_serialization.c | 2 ++ src/c/mip/mip_types.h | 32 +++++++++--------------- 3 files changed, 15 insertions(+), 21 deletions(-) diff --git a/src/c/microstrain/common/embedded_time.h b/src/c/microstrain/common/embedded_time.h index 9cc33648b..b7c2d64c6 100644 --- a/src/c/microstrain/common/embedded_time.h +++ b/src/c/microstrain/common/embedded_time.h @@ -20,7 +20,7 @@ namespace C { /// #ifdef MICROSTRAIN_TIMESTAMP_TYPE typedef MICROSTRAIN_TIMESTAMP_TYPE microstrain_embedded_timestamp; -static_assert( sizeof(microstrain_embedded_timestamp) >= 8 || microstrain_embedded_timestamp(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); +static_assert( sizeof(microstrain_embedded_timestamp) >= 8 || (microstrain_embedded_timestamp)(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); #elif defined(MICROSTRAIN_PLATFORM_DESKTOP) // By default, on desktop we use 64-bit timestamps. diff --git a/src/c/mip/mip_serialization.c b/src/c/mip/mip_serialization.c index 54f0fc2ca..1a55932f4 100644 --- a/src/c/mip/mip_serialization.c +++ b/src/c/mip/mip_serialization.c @@ -2,6 +2,8 @@ #include "mip_serialization.h" #include "mip_offsets.h" +#include + //////////////////////////////////////////////////////////////////////////////// ///@brief Initialize a serialization struct for creation of a new field at the diff --git a/src/c/mip/mip_types.h b/src/c/mip/mip_types.h index 8b6188b2c..1bef0948f 100644 --- a/src/c/mip/mip_types.h +++ b/src/c/mip/mip_types.h @@ -5,33 +5,25 @@ #include #ifdef __cplusplus + +#include + namespace mip { namespace C { extern "C" { + +typedef microstrain::C::microstrain_embedded_timestamp mip_timestamp; +typedef microstrain::C::microstrain_embedded_timestamp mip_timeout; + #else -#include // For static_assert in C11 -#endif +#include +typedef microstrain_embedded_timestamp mip_timestamp; +typedef microstrain_embedded_timestamp mip_timeout; -///@brief Type used for packet timestamps and timeouts. -/// -/// Timestamps must be monotonic except for overflow at the maximum value back to 0. -/// The units can be anything, but typically are milliseconds. Choose a long enough -/// unit so that consecutive calls to the parser will not exceed half of the maximum -/// value for this type. For milliseconds, the time to overflow is approximately 50 -/// days, so the parser should be invoked at least every 25 days. Failure to observe -/// this requirement may result in false timeouts or delays in getting parsed packets. -/// -#ifdef MICROSTRAIN_TIMESTAMP_TYPE - typedef MICROSTRAIN_TIMESTAMP_TYPE mip_timestamp; - static_assert( sizeof(mip_timestamp) >= 8 || (mip_timestamp)(-1) > 0, "MICROSTRAIN_TIMESTAMP_TYPE must be unsigned unless 64 bits."); -#else - typedef uint64_t mip_timestamp; #endif -typedef mip_timestamp mip_timeout; - #ifdef MIP_ENABLE_DIAGNOSTICS @@ -55,8 +47,8 @@ typedef mip_timestamp mip_timeout; } // extern "C" } // namespace C -using Timestamp = C::mip_timestamp; -using Timeout = C::mip_timeout; +using Timestamp = microstrain::EmbeddedTimestamp; +using Timeout = microstrain::EmbeddedTimeout; } // namespace mip From 0bc4f42f112d8cf94c4fa32b1df656553055b802 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 27 Aug 2024 15:53:29 -0400 Subject: [PATCH 092/147] Fix more warnings and restore /W4. --- CMakeLists.txt | 1 + examples/CX5_GX5_45/CX5_GX5_45_example.c | 2 +- .../CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c | 2 +- examples/GQ7/GQ7_example.c | 2 +- examples/threading.cpp | 2 +- examples/watch_imu.c | 12 +++++++++++- examples/watch_imu.cpp | 8 ++++---- src/c/mip/mip_parser.c | 6 +++--- 8 files changed, 23 insertions(+), 12 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9c165c3e8..ab895baa4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -123,6 +123,7 @@ if(MSVC) target_compile_options(microstrain_private INTERFACE "/external:anglebrackets" # Treat angle brackets as system includes "/external:W0" # No warnings from system includes + "/W4" # More warnings "/Zc:__cplusplus" # Enable updated __cplusplus value ) else() diff --git a/examples/CX5_GX5_45/CX5_GX5_45_example.c b/examples/CX5_GX5_45/CX5_GX5_45_example.c index e0c44beb2..a3aa4094d 100644 --- a/examples/CX5_GX5_45/CX5_GX5_45_example.c +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.c @@ -415,7 +415,7 @@ void exit_gracefully(const char *message) serial_port_close(&device_port); #ifdef MICROSTRAIN_PLATFORM_WINDOWS - int dummy = getchar(); + getchar(); #endif exit(0); diff --git a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c index d3fb4ab9e..6b6c14b3c 100644 --- a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c @@ -365,7 +365,7 @@ void exit_gracefully(const char *message) serial_port_close(&device_port); #ifdef MICROSTRAIN_PLATFORM_WINDOWS - int dummy = getchar(); + getchar(); #endif exit(0); diff --git a/examples/GQ7/GQ7_example.c b/examples/GQ7/GQ7_example.c index 5ca7ade6c..6c540a51a 100644 --- a/examples/GQ7/GQ7_example.c +++ b/examples/GQ7/GQ7_example.c @@ -449,7 +449,7 @@ void exit_gracefully(const char *message) serial_port_close(&device_port); #ifdef MICROSTRAIN_PLATFORM_WINDOWS - int dummy = getchar(); + getchar(); #endif exit(0); diff --git a/examples/threading.cpp b/examples/threading.cpp index dd7ff9e26..e143bcd7c 100644 --- a/examples/threading.cpp +++ b/examples/threading.cpp @@ -58,7 +58,7 @@ unsigned int display_progress() return count; } -void packet_callback(void*, const mip::PacketView& packet, mip::Timestamp timestamp) +void packet_callback(void*, const mip::PacketView&, mip::Timestamp) { numSamples = numSamples + 1; } diff --git a/examples/watch_imu.c b/examples/watch_imu.c index b68e6f98a..942576730 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -12,6 +12,7 @@ #include #include #include +#include #ifdef MICROSTRAIN_PLATFORM_WINDOWS #else @@ -25,6 +26,8 @@ mip_sensor_scaled_accel_data scaled_accel; void customLog(void* user, microstrain_log_level level, const char* fmt, va_list args) { + (void)user; + switch (level) { case MICROSTRAIN_LOG_LEVEL_FATAL: @@ -40,6 +43,7 @@ void customLog(void* user, microstrain_log_level level, const char* fmt, va_list void handlePacket(void* unused, const mip_packet_view* packet, mip_timestamp timestamp) { (void)unused; + (void)timestamp; printf("\nGot packet with descriptor set 0x%02X:", mip_packet_descriptor_set(packet)); @@ -55,6 +59,8 @@ void handlePacket(void* unused, const mip_packet_view* packet, mip_timestamp tim void handleAccel(void* user, const mip_field_view* field, mip_timestamp timestamp) { (void)user; + (void)timestamp; + mip_sensor_scaled_accel_data data; if(extract_mip_sensor_scaled_accel_data_from_field(field, &data)) @@ -72,6 +78,8 @@ void handleAccel(void* user, const mip_field_view* field, mip_timestamp timestam void handleGyro(void* user, const mip_field_view* field, mip_timestamp timestamp) { (void)user; + (void)timestamp; + mip_sensor_scaled_gyro_data data; if(extract_mip_sensor_scaled_gyro_data_from_field(field, &data)) @@ -81,6 +89,8 @@ void handleGyro(void* user, const mip_field_view* field, mip_timestamp timestamp void handleMag(void* user, const mip_field_view* field, mip_timestamp timestamp) { (void)user; + (void)timestamp; + mip_sensor_scaled_mag_data data; if(extract_mip_sensor_scaled_mag_data_from_field(field, &data)) @@ -141,7 +151,7 @@ int main(int argc, const char* argv[]) if(argc != 3) return usage(argv[0]); - uint32_t baudrate = atoi(argv[2]); + uint32_t baudrate = strtol(argv[2], NULL, 10); if( baudrate == 0 ) return usage(argv[0]); diff --git a/examples/watch_imu.cpp b/examples/watch_imu.cpp index 2f5111a1c..3e958cdd4 100644 --- a/examples/watch_imu.cpp +++ b/examples/watch_imu.cpp @@ -14,7 +14,7 @@ mip::data_sensor::ScaledAccel scaled_accel; -void handlePacket(void*, const mip::PacketView& packet, mip::Timestamp timestamp) +void handlePacket(void*, const mip::PacketView& packet, mip::Timestamp) { // if(packet.descriptorSet() != mip::MIP_SENSOR_DATA_DESC_SET) // return; @@ -27,7 +27,7 @@ void handlePacket(void*, const mip::PacketView& packet, mip::Timestamp timestamp printf("\n"); } -void handleAccel(void*, const mip::FieldView& field, mip::Timestamp timestamp) +void handleAccel(void*, const mip::FieldView& field, mip::Timestamp) { mip::data_sensor::ScaledAccel data; @@ -43,12 +43,12 @@ void handleAccel(void*, const mip::FieldView& field, mip::Timestamp timestamp) } } -void handleGyro(void*, const mip::data_sensor::ScaledGyro& data, mip::Timestamp timestamp) +void handleGyro(void*, const mip::data_sensor::ScaledGyro& data, mip::Timestamp) { printf("Gyro Data: %f, %f, %f\n", data.scaled_gyro[0], data.scaled_gyro[1], data.scaled_gyro[2]); } -void handleMag(void*, const mip::data_sensor::ScaledMag& data, mip::Timestamp timestamp) +void handleMag(void*, const mip::data_sensor::ScaledMag& data, mip::Timestamp) { printf("Mag Data: %f, %f, %f\n", data.scaled_mag[0], data.scaled_mag[1], data.scaled_mag[2]); } diff --git a/src/c/mip/mip_parser.c b/src/c/mip/mip_parser.c index a04404718..e9c934db5 100644 --- a/src/c/mip/mip_parser.c +++ b/src/c/mip/mip_parser.c @@ -134,7 +134,7 @@ size_t mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer, size_t // Copy as much data as will fit in the ring buffer. size_t count = byte_ring_copy_from_and_update(&parser->_ring, &input_buffer, &input_count); - MIP_DIAG_INC(parser->_diag_bytes_read, count); + MIP_DIAG_INC(parser->_diag_bytes_read, (uint32_t)count); mip_packet_view packet; while( mip_parser_parse_one_packet_from_ring(parser, &packet, timestamp) ) @@ -150,7 +150,7 @@ size_t mip_parser_parse(mip_parser* parser, const uint8_t* input_buffer, size_t // Pull more data from the input buffer if possible. count = byte_ring_copy_from_and_update(&parser->_ring, &input_buffer, &input_count); - MIP_DIAG_INC(parser->_diag_bytes_read, count); + MIP_DIAG_INC(parser->_diag_bytes_read, (uint32_t)count); return input_count; } @@ -380,7 +380,7 @@ size_t mip_parser_get_write_ptr(mip_parser* parser, uint8_t** const ptr_out) /// void mip_parser_process_written(mip_parser* parser, size_t count, mip_timestamp timestamp, unsigned int max_packets) { - MIP_DIAG_INC(parser->_diag_bytes_read, count); + MIP_DIAG_INC(parser->_diag_bytes_read, (uint32_t)count); byte_ring_notify_written(&parser->_ring, count); mip_parser_parse(parser, NULL, 0, timestamp, max_packets); From 1de1c62f7388f3476da1333d9e179169b94f2c39 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 27 Aug 2024 17:18:17 -0400 Subject: [PATCH 093/147] Fix more warnings. --- examples/CSV/csv.cpp | 2 ++ examples/CV7/CV7_example.cpp | 4 ++-- examples/CV7_INS/CV7_INS_simple_example.cpp | 2 +- examples/CV7_INS/CV7_INS_simple_ublox_example.cpp | 8 ++++---- examples/CX5_GX5_45/CX5_GX5_45_example.cpp | 2 +- examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp | 3 +-- examples/GQ7/GQ7_example.cpp | 2 +- examples/watch_imu.c | 2 +- 8 files changed, 13 insertions(+), 12 deletions(-) diff --git a/examples/CSV/csv.cpp b/examples/CSV/csv.cpp index 7988f91d7..d2a7758df 100644 --- a/examples/CSV/csv.cpp +++ b/examples/CSV/csv.cpp @@ -21,6 +21,8 @@ mip::metadata::Definitions mipdefs{mip::metadata::ALL_FIELDS}; void signal_handler(int signum) { + (void)signum; + stop_flag = true; } diff --git a/examples/CV7/CV7_example.cpp b/examples/CV7/CV7_example.cpp index a7352cf37..0c85cfc33 100644 --- a/examples/CV7/CV7_example.cpp +++ b/examples/CV7/CV7_example.cpp @@ -316,7 +316,7 @@ int main(int argc, const char* argv[]) // Filter Event Source Field Handler //////////////////////////////////////////////////////////////////////////////// -void handleFilterEventSource(void*, const mip::FieldView& field, mip::Timestamp timestamp) +void handleFilterEventSource(void*, const mip::FieldView& field, mip::Timestamp) { mip::data_shared::EventSource data; @@ -352,7 +352,7 @@ void exit_gracefully(const char *message) #ifdef MICROSTRAIN_PLATFORM_WINDOWS printf("Press ENTER to exit...\n"); - int dummy = getchar(); + getchar(); #endif exit(0); diff --git a/examples/CV7_INS/CV7_INS_simple_example.cpp b/examples/CV7_INS/CV7_INS_simple_example.cpp index 91a00f9d8..257885615 100644 --- a/examples/CV7_INS/CV7_INS_simple_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_example.cpp @@ -348,7 +348,7 @@ void exit_gracefully(const char *message) #ifdef MICROSTRAIN_PLATFORM_WINDOWS printf("Press ENTER to exit...\n"); - int dummy = getchar(); + getchar(); #endif exit(0); diff --git a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp index 75476ba73..4bfc8a186 100644 --- a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp @@ -61,7 +61,7 @@ struct InputArguments bool enable_pps_sync = false; - int pps_input_pin_id = 1; + uint8_t pps_input_pin_id = 1; commands_filter::InitializationConfiguration::AlignmentSelector filter_heading_alignment_method = commands_filter::InitializationConfiguration::AlignmentSelector::KINEMATIC; @@ -467,11 +467,11 @@ InputArguments parse_input_arguments(int argc, const char* argv[]) // PPS sync enable if (argc >= 11) - input_arguments.enable_pps_sync = std::stoi(argv[10]); + input_arguments.enable_pps_sync = (uint8_t)std::strtoul(argv[10], nullptr, 10); // PPS input pin ID if (argc >= 12) - input_arguments.pps_input_pin_id = std::stoi(argv[11]); + input_arguments.pps_input_pin_id = (uint8_t)std::strtoul(argv[11], nullptr, 10); return input_arguments; } @@ -499,7 +499,7 @@ void exit_gracefully(const char *message) #ifdef MICROSTRAIN_PLATFORM_WINDOWS std::cout << "Press ENTER to exit..." << std::endl; - int dummy = getchar(); + getchar(); #endif exit(0); diff --git a/examples/CX5_GX5_45/CX5_GX5_45_example.cpp b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp index e6fd52a79..0b1d4c3e0 100644 --- a/examples/CX5_GX5_45/CX5_GX5_45_example.cpp +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp @@ -334,7 +334,7 @@ void exit_gracefully(const char *message) #ifdef MICROSTRAIN_PLATFORM_WINDOWS printf("Press ENTER to exit...\n"); - int dummy = getchar(); + getchar(); #endif exit(0); diff --git a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp index ffac10097..b454be215 100644 --- a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp @@ -116,7 +116,6 @@ int main(int argc, const char* argv[]) if(commands_3dm::saveGyroBias(*device) != CmdResult::ACK_OK) exit_gracefully("ERROR: Could not save gyro bias!"); - const uint8_t fn_selector = 1; const uint8_t device_selector = 3; const uint8_t enable_flag = 1; if(commands_3dm::writeDatastreamControl(*device, device_selector, enable_flag) != CmdResult::ACK_OK) @@ -294,7 +293,7 @@ void exit_gracefully(const char *message) printf("%s\n", message); #ifdef MICROSTRAIN_PLATFORM_WINDOWS - int dummy = getchar(); + getchar(); #endif exit(0); diff --git a/examples/GQ7/GQ7_example.cpp b/examples/GQ7/GQ7_example.cpp index ba057334e..a9bccf035 100644 --- a/examples/GQ7/GQ7_example.cpp +++ b/examples/GQ7/GQ7_example.cpp @@ -368,7 +368,7 @@ void exit_gracefully(const char *message) #ifdef MICROSTRAIN_PLATFORM_WINDOWS printf("Press ENTER to exit...\n"); - int dummy = getchar(); + getchar(); #endif exit(0); diff --git a/examples/watch_imu.c b/examples/watch_imu.c index 942576730..64443ee3e 100644 --- a/examples/watch_imu.c +++ b/examples/watch_imu.c @@ -151,7 +151,7 @@ int main(int argc, const char* argv[]) if(argc != 3) return usage(argv[0]); - uint32_t baudrate = strtol(argv[2], NULL, 10); + uint32_t baudrate = strtoul(argv[2], NULL, 10); if( baudrate == 0 ) return usage(argv[0]); From 813728180ff8676431ed8b7f7dfd172a4adbdae9 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Wed, 28 Aug 2024 13:10:31 -0400 Subject: [PATCH 094/147] Added variables for library names and created catch-all libraries Created mip/microstrain interface libraries linking against all desired libraries/modules (easier integration across projects/directories) Created variables for all the library/module names (easier integration across projects/directories) Cleaned up some Windows compiler warnings for type conversions --- CMakeLists.txt | 79 +++++++++++-------- examples/CMakeLists.txt | 19 +++-- src/c/microstrain/common/CMakeLists.txt | 18 +++-- .../connections/serial/CMakeLists.txt | 16 ++-- .../connections/tcp/CMakeLists.txt | 18 +++-- .../microstrain/connections/tcp/tcp_socket.c | 6 +- src/c/mip/CMakeLists.txt | 36 +++++---- src/cpp/microstrain/CMakeLists.txt | 1 - src/cpp/microstrain/common/CMakeLists.txt | 7 +- .../microstrain/connections/CMakeLists.txt | 1 - .../connections/recording/CMakeLists.txt | 15 ++-- .../connections/serial/CMakeLists.txt | 6 +- .../connections/tcp/CMakeLists.txt | 6 +- src/cpp/microstrain/extras/CMakeLists.txt | 15 +++- src/cpp/mip/CMakeLists.txt | 25 +++--- src/cpp/mip/extras/CMakeLists.txt | 17 ++-- src/cpp/mip/metadata/CMakeLists.txt | 38 +++++---- src/cpp/mip/metadata/mip_all_definitions.hpp | 19 ++--- test/CMakeLists.txt | 5 +- 19 files changed, 194 insertions(+), 153 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ab895baa4..7f71f1e55 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,3 @@ - cmake_minimum_required(VERSION 3.10) set(CMAKE_CXX_STANDARD 14) @@ -41,6 +40,7 @@ if(NOT DEFINED MIP_ENABLE_METADATA) message("MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") endif() option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" ${MIP_COMPILER_SUPPORTS_METADATA}) +option(MIP_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ${MICROSTRAIN_ENABLE_EXTRAS}) # Build options option(BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) @@ -62,24 +62,24 @@ mark_as_advanced(MICROSTRAIN_CMAKE_DEBUG) find_package(Git) set(DEFAULT_MIP_GIT_VERSION "v0.0.0") if(NOT GIT_FOUND) - message(STATUS "Unable to find git, will build with unknown version") - set(MIP_GIT_VERSION ${DEFAULT_MSCL_GIT_VERSION}) + message(STATUS "Unable to find git, will build with unknown version") + set(MIP_GIT_VERSION ${DEFAULT_MSCL_GIT_VERSION}) else() - execute_process( - COMMAND ${CMAKE_COMMAND} -E env ${GIT_EXECUTABLE} describe --tags - WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - OUTPUT_VARIABLE MIP_GIT_VERSION_OUT - ERROR_VARIABLE MIP_GIT_VERSION_ERR - RESULT_VARIABLE MIP_GIT_VERSION_RET - ) - if(NOT ${MIP_GIT_VERSION_RET} EQUAL 0) - message(STATUS "Unable to determine version from Git, defaulting to version ${DEFAULT_MIP_GIT_VERSION}") - set(MIP_GIT_VERSION ${DEFAULT_MIP_GIT_VERSION}) - else() - set(MIP_GIT_VERSION ${MIP_GIT_VERSION_OUT}) - string(REGEX REPLACE "\n" "" MIP_GIT_VERSION "${MIP_GIT_VERSION}") - message(STATUS "MIP SDK Version: ${MIP_GIT_VERSION}") - endif() + execute_process( + COMMAND ${CMAKE_COMMAND} -E env ${GIT_EXECUTABLE} describe --tags + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + OUTPUT_VARIABLE MIP_GIT_VERSION_OUT + ERROR_VARIABLE MIP_GIT_VERSION_ERR + RESULT_VARIABLE MIP_GIT_VERSION_RET + ) + if(NOT ${MIP_GIT_VERSION_RET} EQUAL 0) + message(STATUS "Unable to determine version from Git, defaulting to version ${DEFAULT_MIP_GIT_VERSION}") + set(MIP_GIT_VERSION ${DEFAULT_MIP_GIT_VERSION}) + else() + set(MIP_GIT_VERSION ${MIP_GIT_VERSION_OUT}) + string(REGEX REPLACE "\n" "" MIP_GIT_VERSION "${MIP_GIT_VERSION}") + message(STATUS "MIP SDK Version: ${MIP_GIT_VERSION}") + endif() endif() # Massage the version number a little so we can use it in a couple places @@ -107,12 +107,14 @@ configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) # # Common preprocessor definitions # -add_library(microstrain_private INTERFACE) +set(MICROSTRAIN_PRIVATE_LIBRARY "microstrain_private") +mark_as_advanced(MICROSTRAIN_PRIVATE_LIBRARY) +add_library(${MICROSTRAIN_PRIVATE_LIBRARY} INTERFACE) # Disable windows defined min/max # Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) if(WIN32) - target_compile_definitions(microstrain_private + target_compile_definitions(${MICROSTRAIN_PRIVATE_LIBRARY} INTERFACE "NOMINMAX=1" "_WIN32_WINNT=_WIN32_WINNT_WINXP" @@ -120,24 +122,32 @@ if(WIN32) endif() if(MSVC) - target_compile_options(microstrain_private INTERFACE + target_compile_options(${MICROSTRAIN_PRIVATE_LIBRARY} INTERFACE "/external:anglebrackets" # Treat angle brackets as system includes "/external:W0" # No warnings from system includes - "/W4" # More warnings + "/W4" # Enable warnings "/Zc:__cplusplus" # Enable updated __cplusplus value ) else() - target_compile_options(microstrain_private INTERFACE + target_compile_options(${MICROSTRAIN_PRIVATE_LIBRARY} INTERFACE "-Wall" # Extra warnings "-Wextra" ) endif() +# Create "catch-all" interface libraries +set(MICROSTRAIN_LIBRARIES "microstrain_all" CACHE INTERNAL "Interface library to make linking all desired MicroStrain libraries easier") +add_library(${MICROSTRAIN_LIBRARIES} INTERFACE) +set(MIP_LIBRARIES "mip_all" CACHE INTERNAL "Interface library to make linking all desired MIP libraries easier") +add_library(${MIP_LIBRARIES} INTERFACE) # Suppress warnings due to adding files with target_sources. cmake_policy(SET CMP0076 NEW) +# Supress warnings due to linking libraries across directories +cmake_policy(SET CMP0079 NEW) + # Add all the C files (required even for C++ API) set(SRC_C_DIR "${CMAKE_CURRENT_LIST_DIR}/src/c") @@ -152,10 +162,11 @@ if(MICROSTRAIN_ENABLE_CPP) add_subdirectory(src/cpp/microstrain) add_subdirectory(src/cpp/mip) - #target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_CPP_C_NAMESPACE=${MICROSTRAIN_ENABLE_CPP_C_NAMESPACE}") + #target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_CPP_C_NAMESPACE=${MICROSTRAIN_ENABLE_CPP_C_NAMESPACE}") endif() - +# Link the MicroStrain SDK to allow for linkage of only the MIP SDK +target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MICROSTRAIN_LIBRARIES}) # # Libraries @@ -237,7 +248,7 @@ include(CMakePackageConfigHelpers) set(CONFIG_EXPORT_DIR "${CMAKE_INSTALL_DATADIR}/cmake/mip") -set(EXPORT_TARGETS mip) +set(EXPORT_TARGETS ${MIP_LIBRARY}) configure_package_config_file( "${CMAKE_CURRENT_LIST_DIR}/cmake/mip-config.cmake.in" "${CMAKE_BINARY_DIR}/mip-config.cmake" @@ -268,28 +279,28 @@ write_basic_package_version_file( # install( # FILES "${MIP_HEADER}" # DESTINATION "${MIP_HEADER_DESTINATION}" -# COMPONENT mip +# COMPONENT ${MIP_LIBRARY} # ) #endforeach() # #install(TARGETS -# mip +# ${MIP_LIBRARY} # EXPORT mip-targets # ARCHIVE -# COMPONENT mip +# COMPONENT ${MIP_LIBRARY} # DESTINATION "${CMAKE_INSTALL_LIBDIR}/" #) # #install(EXPORT # mip-targets -# COMPONENT mip +# COMPONENT ${MIP_LIBRARY} # DESTINATION "${CONFIG_EXPORT_DIR}" #) # #install(FILES # "${CMAKE_BINARY_DIR}/mip-config.cmake" # "${CMAKE_BINARY_DIR}/mip-config-version.cmake" -# COMPONENT mip +# COMPONENT ${MIP_LIBRARY} # DESTINATION "${CONFIG_EXPORT_DIR}" #) @@ -370,7 +381,7 @@ if(BUILD_PACKAGE) set(CPACK_GENERATOR "${FOUND_CPACK_GENERATORS}") set(CPACK_PACKAGE_VENDOR "MicroStrain by HBK") set(CPACK_PACKAGE_CONTACT "MicroStrain Support ") - set(CPACK_COMPONENTS_ALL "mip") + set(CPACK_COMPONENTS_ALL ${MIP_LIBRARY}) set(CPACK_PACKAGE_VERSION ${MIP_GIT_VERSION_CLEAN}) @@ -405,8 +416,8 @@ if(BUILD_PACKAGE) # Finally include cpack which should have taken all of the previous variables into consideration include(CPack) - cpack_add_component(mip + cpack_add_component(${MIP_LIBRARY} DESCRIPTION "MIP SDK static library and header files" - GROUP mip + GROUP ${MIP_LIBRARY} ) endif() diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 712f7ea4e..5f46c2f0d 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -1,8 +1,7 @@ - set(EXAMPLE_DIR "${CMAKE_CURRENT_LIST_DIR}") +set(MIP_EXAMPLE_UTILS_LIBRARY "example_utils") - -add_library(example_utils +add_library(${MIP_EXAMPLE_UTILS_LIBRARY} "${EXAMPLE_DIR}/example_utils.c" "${EXAMPLE_DIR}/example_utils.h" "${EXAMPLE_DIR}/example_utils.cpp" @@ -22,7 +21,7 @@ if(MICROSTRAIN_ENABLE_TCP) endif() if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) - list(APPEND EXAMPLE_LIBS microstrain_recording_connection) + list(APPEND EXAMPLE_LIBS ${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY}) endif() if(MIP_ENABLE_EXTRAS) @@ -32,11 +31,11 @@ endif() set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) -target_compile_definitions(example_utils PUBLIC ${MIP_EXAMPLE_DEFS}) -#target_include_directories(example_utils PRIVATE ${SRC_DIR}) -target_link_libraries(example_utils PUBLIC mip ${EXAMPLE_LIBS} microstrain_private) +target_compile_definitions(${MIP_EXAMPLE_UTILS_LIBRARY} PUBLIC ${MIP_EXAMPLE_DEFS}) +#target_include_directories(${MIP_EXAMPLE_UTILS_LIBRARY} PRIVATE ${SRC_DIR}) +target_link_libraries(${MIP_EXAMPLE_UTILS_LIBRARY} PUBLIC ${MIP_LIBRARY} ${EXAMPLE_LIBS} ${MICROSTRAIN_PRIVATE_LIBRARY}) -list(APPEND EXAMPLE_LIBS example_utils) +list(APPEND EXAMPLE_LIBS ${MIP_EXAMPLE_UTILS_LIBRARY}) macro(add_mip_example name sources) @@ -46,7 +45,7 @@ macro(add_mip_example name sources) if(MICROSTRAIN_ENABLE_CPP) # Technically should only do this for C++ examples but this is simpler target_compile_features(${name} PUBLIC cxx_std_11) endif() - target_link_libraries(${name} PUBLIC mip ${EXAMPLE_LIBS}) + target_link_libraries(${name} PUBLIC ${MIP_LIBRARY} ${EXAMPLE_LIBS}) target_compile_definitions(${name} PUBLIC ${MIP_EXAMPLE_DEFS}) target_include_directories(${name} PRIVATE ${EXAMPLE_DIR}) @@ -64,7 +63,7 @@ if(MICROSTRAIN_ENABLE_CPP AND (MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_T endif() if(MIP_ENABLE_METADATA) add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") - target_link_libraries(CsvExample PRIVATE mip_metadata) + target_link_libraries(CsvExample PRIVATE ${MIP_METADATA_LIBRARY}) endif() # Product-specific examples diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index dbf4959e1..49aba92c5 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -1,26 +1,30 @@ +set(MICROSTRAIN_COMMON_LIBRARY "microstrain_common" CACHE INTERNAL "Name of the common MicroStrain library") +mark_as_advanced(MICROSTRAIN_COMMON_LIBRARY) #option(MICROSTRAIN_ENABLE_LOGGING "Build with logging functions enabled" ON) set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any call to logging functions with a higher level than this will be compiled out.") set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") -add_library(microstrain_common +add_library(${MICROSTRAIN_COMMON_LIBRARY} "logging.h" "platform.h" "serialization.c" "serialization.h" ) -target_link_libraries(microstrain_common PRIVATE microstrain_private) -target_compile_features(microstrain_common PUBLIC c_std_11) -target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") +target_link_libraries(${MICROSTRAIN_COMMON_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY}) +target_compile_features(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC c_std_11) +target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") # Logging is a little weird since we need to install the header no matter what if(MICROSTRAIN_ENABLE_LOGGING) if(MICROSTRAIN_LOGGING_MAX_LEVEL STREQUAL "") message(FATAL_ERROR "MICROSTRAIN_LOGGING_MAX_LEVEL must be MICROSTRAIN_LOG_LEVEL_* or a number") endif() - target_sources(microstrain_common PRIVATE "${CMAKE_CURRENT_LIST_DIR}/logging.c") + target_sources(${MICROSTRAIN_COMMON_LIBRARY} PRIVATE "${CMAKE_CURRENT_LIST_DIR}/logging.c") message("MicroStrain logging is enabled. Max level = '${MICROSTRAIN_LOGGING_MAX_LEVEL}'") - target_compile_definitions(microstrain_common PUBLIC "MICROSTRAIN_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") + target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") endif() -target_include_directories(microstrain_common INTERFACE ${SRC_C_DIR}) +target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${SRC_C_DIR}) + +target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_COMMON_LIBRARY}) diff --git a/src/c/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt index 803d0c8e2..1675a191c 100644 --- a/src/c/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -1,10 +1,16 @@ +set(MICROSTRAIN_SERIAL_LIBRARY "microstrain_serial" CACHE INTERNAL "Name of the MicroStrain serial connections library") +mark_as_advanced(MICROSTRAIN_SERIAL_LIBRARY) -add_library(microstrain_serial +add_library(${MICROSTRAIN_SERIAL_LIBRARY} "serial_port.h" "serial_port.c" ) -target_link_libraries(microstrain_serial PRIVATE microstrain_private) -target_compile_features(microstrain_serial PUBLIC c_std_11) -target_compile_definitions(microstrain_serial PUBLIC "MICROSTRAIN_ENABLE_SERIAL=1") -target_link_libraries(microstrain_serial PUBLIC microstrain_common) +target_compile_features(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC c_std_11) +target_link_libraries(${MICROSTRAIN_SERIAL_LIBRARY} + PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} + PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} +) +target_compile_definitions(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_SERIAL=1") + +target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_SERIAL_LIBRARY}) diff --git a/src/c/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt index 90be4d461..75725e392 100644 --- a/src/c/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -1,14 +1,20 @@ +set(MICROSTRAIN_SOCKET_LIBRARY "microstrain_socket" CACHE INTERNAL "Name of the MicroStrain TCP socket connections library") +mark_as_advanced(MICROSTRAIN_SOCKET_LIBRARY) -add_library(microstrain_socket +add_library(${MICROSTRAIN_SOCKET_LIBRARY} "tcp_socket.h" "tcp_socket.c" ) -target_link_libraries(microstrain_socket PRIVATE microstrain_private) -target_compile_features(microstrain_socket PUBLIC c_std_11) -target_compile_definitions(microstrain_socket PUBLIC "MICROSTRAIN_ENABLE_TCP=1") -target_link_libraries(microstrain_socket PUBLIC microstrain_common) +target_compile_features(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC c_std_11) +target_link_libraries(${MICROSTRAIN_SOCKET_LIBRARY} + PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} + PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} +) +target_compile_definitions(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_TCP=1") if(WIN32) - target_link_libraries(microstrain_socket PUBLIC "ws2_32") + target_link_libraries(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC "ws2_32") endif() + +target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_SOCKET_LIBRARY}) diff --git a/src/c/microstrain/connections/tcp/tcp_socket.c b/src/c/microstrain/connections/tcp/tcp_socket.c index 7c897c869..dc6094d5f 100644 --- a/src/c/microstrain/connections/tcp/tcp_socket.c +++ b/src/c/microstrain/connections/tcp/tcp_socket.c @@ -65,7 +65,7 @@ static bool tcp_socket_open_common(tcp_socket* socket_ptr, const char* hostname, if( socket_ptr->handle == INVALID_SOCKET ) continue; - if( connect(socket_ptr->handle, addr->ai_addr, addr->ai_addrlen) == 0 ) + if( connect(socket_ptr->handle, addr->ai_addr, (int)addr->ai_addrlen) == 0 ) break; #ifdef MICROSTRAIN_PLATFORM_WINDOWS @@ -141,7 +141,7 @@ bool tcp_socket_send(tcp_socket* socket_ptr, const void* buffer, size_t num_byte { for(*bytes_written = 0; *bytes_written < num_bytes; ) { - ssize_t sent = send(socket_ptr->handle, buffer, num_bytes, SEND_FLAGS); + ssize_t sent = send(socket_ptr->handle, buffer, (int)num_bytes, SEND_FLAGS); if(sent < 0) return false; @@ -152,7 +152,7 @@ bool tcp_socket_send(tcp_socket* socket_ptr, const void* buffer, size_t num_byte bool tcp_socket_recv(tcp_socket* socket_ptr, void* buffer, size_t num_bytes, size_t* bytes_read) { - ssize_t local_bytes_read = recv(socket_ptr->handle, buffer, num_bytes, SEND_FLAGS); + ssize_t local_bytes_read = recv(socket_ptr->handle, buffer, (int)num_bytes, SEND_FLAGS); if( local_bytes_read < 0 ) { diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index efecc4234..a2ebf62d7 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -1,9 +1,11 @@ +set(MIP_LIBRARY "mip" CACHE INTERNAL "Name of the MIP library") +mark_as_advanced(MIP_LIBRARY) # # Core MIP C library # -add_library(mip +add_library(${MIP_LIBRARY} "${VERSION_OUT_FILE}" "mip_cmdqueue.c" @@ -36,12 +38,14 @@ add_library(mip "utils/byte_ring.h" ) -target_link_libraries(mip PRIVATE microstrain_private) -target_compile_features(mip PUBLIC c_std_11) -target_link_libraries(mip PUBLIC microstrain_common) +target_compile_features(${MIP_LIBRARY} PUBLIC c_std_11) +target_link_libraries(${MIP_LIBRARY} + PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} + PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} +) if(${MIP_ENABLE_DIAGNOSTICS}) - target_compile_definitions(mip PUBLIC "MIP_ENABLE_DIAGNOSTICS=1") + target_compile_definitions(${MIP_LIBRARY} PUBLIC "MIP_ENABLE_DIAGNOSTICS=1") endif() @@ -49,7 +53,7 @@ endif() # Mip definition files # -set(MIPDEFS +set(MIP_DEFS commands_3dm commands_aiding commands_base @@ -65,17 +69,19 @@ set(MIPDEFS ) # Set this list as a target property so the C++ version can access it. -set_target_properties(mip PROPERTIES definitions "${MIPDEFS}") +set_target_properties(${MIP_LIBRARY} PROPERTIES definitions "${MIP_DEFS}") -set(MIPDEF_HEADERS ${MIPDEFS}) -set(MIPDEF_SOURCES ${MIPDEFS}) -list(TRANSFORM MIPDEF_HEADERS APPEND ".h") -list(TRANSFORM MIPDEF_SOURCES APPEND ".c") -list(APPEND MIPDEF_SOURCES ${MIPDEF_HEADERS}) -list(TRANSFORM MIPDEF_SOURCES PREPEND "definitions/") +set(MIP_DEF_HEADERS ${MIP_DEFS}) +set(MIP_DEF_SOURCES ${MIP_DEFS}) +list(TRANSFORM MIP_DEF_HEADERS APPEND ".h") +list(TRANSFORM MIP_DEF_SOURCES APPEND ".c") +list(APPEND MIP_DEF_SOURCES ${MIP_DEF_HEADERS}) +list(TRANSFORM MIP_DEF_SOURCES PREPEND "definitions/") if(MICROSTRAIN_CMAKE_DEBUG) - message("C definitions = ${MIPDEF_SOURCES}") + message("C definitions = ${MIP_DEF_SOURCES}") endif() -target_sources(mip PRIVATE ${MIPDEF_SOURCES}) +target_sources(${MIP_LIBRARY} PRIVATE ${MIP_DEF_SOURCES}) + +target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_LIBRARY}) diff --git a/src/cpp/microstrain/CMakeLists.txt b/src/cpp/microstrain/CMakeLists.txt index 5de3ea426..cd94d5325 100644 --- a/src/cpp/microstrain/CMakeLists.txt +++ b/src/cpp/microstrain/CMakeLists.txt @@ -1,4 +1,3 @@ - add_subdirectory(common) add_subdirectory(connections) diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index eb5ab8ba2..f25bf4d11 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -1,6 +1,5 @@ - # microstrain_common is defined by the C api. -target_sources(microstrain_common PRIVATE +target_sources(${MICROSTRAIN_COMMON_LIBRARY} PRIVATE embedded_time.hpp index.hpp logging.hpp @@ -10,5 +9,5 @@ target_sources(microstrain_common PRIVATE serialization/serializer.hpp ) -target_compile_features(microstrain_common PUBLIC cxx_std_11) -target_include_directories(microstrain_common INTERFACE ${SRC_CPP_DIR}) +target_compile_features(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC cxx_std_11) +target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${SRC_CPP_DIR}) diff --git a/src/cpp/microstrain/connections/CMakeLists.txt b/src/cpp/microstrain/connections/CMakeLists.txt index a7fe81fd8..a24319196 100644 --- a/src/cpp/microstrain/connections/CMakeLists.txt +++ b/src/cpp/microstrain/connections/CMakeLists.txt @@ -1,4 +1,3 @@ - if(MICROSTRAIN_ENABLE_SERIAL) add_subdirectory(serial) endif() diff --git a/src/cpp/microstrain/connections/recording/CMakeLists.txt b/src/cpp/microstrain/connections/recording/CMakeLists.txt index 37f3cca7b..6560170f3 100644 --- a/src/cpp/microstrain/connections/recording/CMakeLists.txt +++ b/src/cpp/microstrain/connections/recording/CMakeLists.txt @@ -1,11 +1,16 @@ +set(MICROSTRAIN_RECORDING_CONNECTION_LIBRARY "microstrain_recording_connection" CACHE INTERNAL "Name of the MicroStrain recording connections library") +mark_as_advanced(MICROSTRAIN_RECORDING_CONNECTION_LIBRARY) - -add_library(microstrain_recording_connection +add_library(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} recording_connection.cpp recording_connection.hpp ../connection.hpp ) -target_link_libraries(microstrain_recording_connection PRIVATE microstrain_private) -target_link_libraries(microstrain_recording_connection PUBLIC microstrain_common) -target_compile_features(microstrain_recording_connection PUBLIC cxx_std_11) +target_compile_features(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} PUBLIC cxx_std_11) +target_link_libraries(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} + PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} + PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} +) + +target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY}) diff --git a/src/cpp/microstrain/connections/serial/CMakeLists.txt b/src/cpp/microstrain/connections/serial/CMakeLists.txt index ec0606ff3..007c012f0 100644 --- a/src/cpp/microstrain/connections/serial/CMakeLists.txt +++ b/src/cpp/microstrain/connections/serial/CMakeLists.txt @@ -1,10 +1,8 @@ - # Add to existing C library. -target_sources(microstrain_serial - PRIVATE +target_sources(${MICROSTRAIN_SERIAL_LIBRARY} PRIVATE serial_connection.cpp serial_connection.hpp ../connection.hpp ) -target_compile_features(microstrain_serial PUBLIC cxx_std_11) +target_compile_features(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC cxx_std_11) diff --git a/src/cpp/microstrain/connections/tcp/CMakeLists.txt b/src/cpp/microstrain/connections/tcp/CMakeLists.txt index 25b49d1a1..de092a4c4 100644 --- a/src/cpp/microstrain/connections/tcp/CMakeLists.txt +++ b/src/cpp/microstrain/connections/tcp/CMakeLists.txt @@ -1,10 +1,8 @@ - # Add to existing C library. -target_sources(microstrain_socket - PRIVATE +target_sources(${MICROSTRAIN_SOCKET_LIBRARY} PRIVATE tcp_connection.cpp tcp_connection.hpp ../connection.hpp ) -target_compile_features(microstrain_socket PUBLIC cxx_std_11) +target_compile_features(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC cxx_std_11) diff --git a/src/cpp/microstrain/extras/CMakeLists.txt b/src/cpp/microstrain/extras/CMakeLists.txt index dfa3e6583..c403895b0 100644 --- a/src/cpp/microstrain/extras/CMakeLists.txt +++ b/src/cpp/microstrain/extras/CMakeLists.txt @@ -1,9 +1,18 @@ +set(MICROSTRAIN_EXTRAS_LIBRARY "microstrain_extras" CACHE INTERNAL "Name of the MicroStrain extras library") +mark_as_advanced(MICROSTRAIN_EXTRAS_LIBRARY) set(SOURCES scope_helper.cpp scope_helper.hpp ) -add_library(microstrain_extras ${SOURCES}) -target_compile_features(microstrain_extras PUBLIC cxx_std_11) -target_compile_definitions(microstrain_extras PUBLIC "MICROSTRAIN_ENABLE_EXTRAS=1") +add_library(${MICROSTRAIN_EXTRAS_LIBRARY} ${SOURCES}) + +target_compile_features(${MICROSTRAIN_EXTRAS_LIBRARY} PUBLIC cxx_std_11) +target_link_libraries(${MICROSTRAIN_EXTRAS_LIBRARY} + PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} + PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} +) +target_compile_definitions(${MICROSTRAIN_EXTRAS_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_EXTRAS=1") + +target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_EXTRAS_LIBRARY}) diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index 7ea221a6b..e353aa23a 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -1,7 +1,6 @@ - set(MIP_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") -target_sources(mip PRIVATE +target_sources(${MIP_LIBRARY} PRIVATE mip.hpp mip_all.hpp mip_cmdqueue.hpp @@ -15,24 +14,24 @@ target_sources(mip PRIVATE mip_serialization.hpp ) -target_compile_features(mip PUBLIC cxx_std_11) -target_include_directories(mip PRIVATE ${MIP_INCLUDE_DIR}) +target_compile_features(${MIP_LIBRARY} PUBLIC cxx_std_11) +target_include_directories(${MIP_LIBRARY} PRIVATE ${MIP_INCLUDE_DIR}) # Get the mipdef list from the C version -get_target_property(MIPDEFS mip definitions) +get_target_property(MIP_DEFS ${MIP_LIBRARY} definitions) -set(MIPDEF_HEADERS ${MIPDEFS}) -set(MIPDEF_SOURCES ${MIPDEFS}) -list(TRANSFORM MIPDEF_HEADERS APPEND ".hpp") -list(TRANSFORM MIPDEF_SOURCES APPEND ".cpp") -list(APPEND MIPDEF_SOURCES ${MIPDEF_HEADERS}) -list(TRANSFORM MIPDEF_SOURCES PREPEND "definitions/") +set(MIP_DEF_HEADERS ${MIP_DEFS}) +set(MIP_DEF_SOURCES ${MIP_DEFS}) +list(TRANSFORM MIP_DEF_HEADERS APPEND ".hpp") +list(TRANSFORM MIP_DEF_SOURCES APPEND ".cpp") +list(APPEND MIP_DEF_SOURCES ${MIP_DEF_HEADERS}) +list(TRANSFORM MIP_DEF_SOURCES PREPEND "definitions/") if(MICROSTRAIN_CMAKE_DEBUG) - message("C++ definitions = ${MIPDEF_SOURCES}") + message("C++ definitions = ${MIP_DEF_SOURCES}") endif() -target_sources(mip PRIVATE ${MIPDEF_SOURCES}) +target_sources(${MIP_LIBRARY} PRIVATE ${MIP_DEF_SOURCES}) if(MIP_ENABLE_METADATA) add_subdirectory(metadata) diff --git a/src/cpp/mip/extras/CMakeLists.txt b/src/cpp/mip/extras/CMakeLists.txt index da69f61f5..e64ac5663 100644 --- a/src/cpp/mip/extras/CMakeLists.txt +++ b/src/cpp/mip/extras/CMakeLists.txt @@ -1,13 +1,18 @@ +set(MIP_EXTRAS_LIBRARY "mip_extras" CACHE INTERNAL "Name of the MIP extras library") +mark_as_advanced(MIP_EXTRAS_LIBRARY) -set(SOURCES +add_library(${MIP_EXTRAS_LIBRARY} composite_result.hpp descriptor_id.hpp firmware_version.cpp firmware_version.hpp ) -add_library(mip_extras ${SOURCES}) -target_link_libraries(mip_extras PRIVATE microstrain_private) -target_compile_features(mip_extras PUBLIC cxx_std_11) -target_link_libraries(mip_extras PUBLIC mip microstrain_extras) -target_compile_definitions(mip_extras PUBLIC "MIP_ENABLE_EXTRAS=1") +target_compile_features(${MIP_EXTRAS_LIBRARY} PUBLIC cxx_std_11) +target_link_libraries(${MIP_EXTRAS_LIBRARY} + PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} + PUBLIC ${MIP_LIBRARY} ${MICROSTRAIN_EXTRAS_LIBRARY} +) +target_compile_definitions(${MIP_EXTRAS_LIBRARY} PUBLIC "MIP_ENABLE_EXTRAS=1") + +target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_EXTRAS_LIBRARY}) diff --git a/src/cpp/mip/metadata/CMakeLists.txt b/src/cpp/mip/metadata/CMakeLists.txt index 03e620bf2..eb993e53b 100644 --- a/src/cpp/mip/metadata/CMakeLists.txt +++ b/src/cpp/mip/metadata/CMakeLists.txt @@ -1,29 +1,33 @@ +set(MIP_METADATA_LIBRARY "mip_metadata" CACHE INTERNAL "Name of the MIP metadata library") +mark_as_advanced(MIP_METADATA_LIBRARY) +# Get the mipdef list from the C version +get_target_property(MIP_DEFS ${MIP_LIBRARY} definitions) + +set(MIP_DEF_HEADERS ${MIP_DEFS}) +list(TRANSFORM MIP_DEF_HEADERS APPEND ".hpp") +list(TRANSFORM MIP_DEF_HEADERS PREPEND "definitions/") + +if(MICROSTRAIN_CMAKE_DEBUG) + message("C++ metadata definitions = ${MIP_DEF_HEADERS}") +endif() -set(META_SOURCES +add_library(${MIP_METADATA_LIBRARY} "mip_all_definitions.hpp" "mip_definitions.hpp" "mip_definitions.cpp" "mip_metadata.hpp" "mip_structures.hpp" "mip_meta_utils.hpp" - "definitions/common.hpp" + ${MIP_DEF_HEADERS} ) -# Get the mipdef list from the C version -get_target_property(MIPDEFS mip definitions) - -set(MIPDEF_HEADERS ${MIPDEFS}) -list(TRANSFORM MIPDEF_HEADERS APPEND ".hpp") -list(TRANSFORM MIPDEF_HEADERS PREPEND "definitions/") - -if(MICROSTRAIN_CMAKE_DEBUG) - message("C++ metadata definitions = ${MIPDEF_HEADERS}") -endif() +target_compile_features(${MIP_METADATA_LIBRARY} PUBLIC cxx_std_20) +target_link_libraries(${MIP_METADATA_LIBRARY} + PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} + PUBLIC ${MIP_LIBRARY} +) +target_compile_definitions(${MIP_METADATA_LIBRARY} PUBLIC "MIP_ENABLE_METADATA=1") -add_library(mip_metadata ${META_SOURCES} ${MIPDEF_HEADERS}) -target_link_libraries(mip_metadata PRIVATE microstrain_private) -target_compile_features(mip_metadata PUBLIC cxx_std_20) -target_link_libraries(mip_metadata PUBLIC mip) -target_compile_definitions(mip_metadata PUBLIC "MIP_ENABLE_METADATA=1") +target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_METADATA_LIBRARY}) diff --git a/src/cpp/mip/metadata/mip_all_definitions.hpp b/src/cpp/mip/metadata/mip_all_definitions.hpp index bbb20b482..ce3a6185f 100644 --- a/src/cpp/mip/metadata/mip_all_definitions.hpp +++ b/src/cpp/mip/metadata/mip_all_definitions.hpp @@ -1,12 +1,11 @@ - -#include -#include -#include -#include -#include -#include -#include +#include "definitions/commands_3dm.hpp" +#include "definitions/commands_aiding.hpp" +#include "definitions/commands_base.hpp" +#include "definitions/commands_filter.hpp" +#include "definitions/commands_gnss.hpp" +#include "definitions/commands_rtk.hpp" +#include "definitions/commands_system.hpp" #include "definitions/data_filter.hpp" #include "definitions/data_gnss.hpp" @@ -14,7 +13,6 @@ #include "definitions/data_shared.hpp" #include "definitions/data_system.hpp" - namespace mip::metadata { @@ -52,5 +50,4 @@ static constexpr inline std::initializer_list< const std::initializer_list< cons &ALL_DATA_SYSTEM, }; -} // namespace mip - +} // namespace mip::metadata diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 5ca50fad7..0c96aabe0 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,4 +1,3 @@ - set(TEST_DIR "${CMAKE_CURRENT_LIST_DIR}") # @@ -6,14 +5,12 @@ set(TEST_DIR "${CMAKE_CURRENT_LIST_DIR}") # macro(add_mip_test name sources command) - add_executable(${name} ${sources}) target_include_directories(${name} PRIVATE ${SRC_DIR}) - target_link_libraries(${name} mip) + target_link_libraries(${name} ${MIP_LIBRARY}) add_test(${name} ${command} ${ARGN}) - endmacro() add_mip_test(TestMipPacketBuilding "${TEST_DIR}/mip/test_mip_packet_builder.c" TestMipPacketBuilding) From a524df4dcf7844395e9c942ab6c300e33a658347 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Wed, 28 Aug 2024 16:05:16 -0400 Subject: [PATCH 095/147] Fixed packet length usage issue --- .../common/serialization/serializer.hpp | 2 +- src/cpp/mip/definitions/commands_3dm.cpp | 318 ++++++------- src/cpp/mip/definitions/commands_aiding.cpp | 38 +- src/cpp/mip/definitions/commands_base.cpp | 12 +- src/cpp/mip/definitions/commands_filter.cpp | 436 +++++++++--------- src/cpp/mip/definitions/commands_gnss.cpp | 20 +- src/cpp/mip/definitions/commands_rtk.cpp | 16 +- src/cpp/mip/definitions/commands_system.cpp | 6 +- src/cpp/mip/mip_packet.hpp | 2 +- 9 files changed, 425 insertions(+), 425 deletions(-) diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index 3a019c9a4..bd62b0961 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -32,8 +32,8 @@ class SerializerBase #endif size_t capacity() const { return m_size; } - size_t length() const { return m_size; } size_t offset() const { return m_offset; } + size_t usedLength() const { return offset(); } int remaining() const { return int(m_size - m_offset); } bool isOverrun() const { return m_offset > m_size; } diff --git a/src/cpp/mip/definitions/commands_3dm.cpp b/src/cpp/mip/definitions/commands_3dm.cpp index 0038aed3a..00c114c13 100644 --- a/src/cpp/mip/definitions/commands_3dm.cpp +++ b/src/cpp/mip/definitions/commands_3dm.cpp @@ -78,7 +78,7 @@ TypedResult pollImuMessage(C::mip_interface& device, bool suppre assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_IMU_MESSAGE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_IMU_MESSAGE, buffer, (uint8_t)serializer.usedLength()); } void PollGnssMessage::insert(Serializer& serializer) const { @@ -115,7 +115,7 @@ TypedResult pollGnssMessage(C::mip_interface& device, bool supp assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_GNSS_MESSAGE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_GNSS_MESSAGE, buffer, (uint8_t)serializer.usedLength()); } void PollFilterMessage::insert(Serializer& serializer) const { @@ -152,7 +152,7 @@ TypedResult pollFilterMessage(C::mip_interface& device, bool assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_FILTER_MESSAGE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_FILTER_MESSAGE, buffer, (uint8_t)serializer.usedLength()); } void ImuMessageFormat::insert(Serializer& serializer) const { @@ -210,7 +210,7 @@ TypedResult writeImuMessageFormat(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult readImuMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { @@ -221,7 +221,7 @@ TypedResult readImuMessageFormat(C::mip_interface& device, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_IMU_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength(), REPLY_IMU_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -245,7 +245,7 @@ TypedResult saveImuMessageFormat(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadImuMessageFormat(C::mip_interface& device) { @@ -255,7 +255,7 @@ TypedResult loadImuMessageFormat(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultImuMessageFormat(C::mip_interface& device) { @@ -265,7 +265,7 @@ TypedResult defaultImuMessageFormat(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } void GpsMessageFormat::insert(Serializer& serializer) const { @@ -323,7 +323,7 @@ TypedResult writeGpsMessageFormat(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGpsMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { @@ -334,7 +334,7 @@ TypedResult readGpsMessageFormat(C::mip_interface& device, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_GNSS_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength(), REPLY_GNSS_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -358,7 +358,7 @@ TypedResult saveGpsMessageFormat(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGpsMessageFormat(C::mip_interface& device) { @@ -368,7 +368,7 @@ TypedResult loadGpsMessageFormat(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGpsMessageFormat(C::mip_interface& device) { @@ -378,7 +378,7 @@ TypedResult defaultGpsMessageFormat(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } void FilterMessageFormat::insert(Serializer& serializer) const { @@ -436,7 +436,7 @@ TypedResult writeFilterMessageFormat(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult readFilterMessageFormat(C::mip_interface& device, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { @@ -447,7 +447,7 @@ TypedResult readFilterMessageFormat(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_FILTER_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength(), REPLY_FILTER_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -471,7 +471,7 @@ TypedResult saveFilterMessageFormat(C::mip_interface& devic serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadFilterMessageFormat(C::mip_interface& device) { @@ -481,7 +481,7 @@ TypedResult loadFilterMessageFormat(C::mip_interface& devic serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultFilterMessageFormat(C::mip_interface& device) { @@ -491,7 +491,7 @@ TypedResult defaultFilterMessageFormat(C::mip_interface& de serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FILTER_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } void ImuGetBaseRate::insert(Serializer& serializer) const { @@ -651,7 +651,7 @@ TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool s assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_DATA, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_DATA, buffer, (uint8_t)serializer.usedLength()); } void GetBaseRate::insert(Serializer& serializer) const { @@ -689,7 +689,7 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_BASE_RATE, buffer, (uint8_t)serializer.length(), REPLY_BASE_RATE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GET_BASE_RATE, buffer, (uint8_t)serializer.usedLength(), REPLY_BASE_RATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -771,7 +771,7 @@ TypedResult writeMessageFormat(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult readMessageFormat(C::mip_interface& device, uint8_t descSet, uint8_t* numDescriptorsOut, uint8_t numDescriptorsOutMax, DescriptorRate* descriptorsOut) { @@ -784,7 +784,7 @@ TypedResult readMessageFormat(C::mip_interface& device, uint8_t d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength(), REPLY_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -812,7 +812,7 @@ TypedResult saveMessageFormat(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadMessageFormat(C::mip_interface& device, uint8_t descSet) { @@ -824,7 +824,7 @@ TypedResult loadMessageFormat(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultMessageFormat(C::mip_interface& device, uint8_t descSet) { @@ -836,7 +836,7 @@ TypedResult defaultMessageFormat(C::mip_interface& device, uint8_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } void NmeaPollData::insert(Serializer& serializer) const { @@ -873,7 +873,7 @@ TypedResult nmeaPollData(C::mip_interface& device, bool suppressAc assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_NMEA_MESSAGE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POLL_NMEA_MESSAGE, buffer, (uint8_t)serializer.usedLength()); } void NmeaMessageFormat::insert(Serializer& serializer) const { @@ -931,7 +931,7 @@ TypedResult writeNmeaMessageFormat(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult readNmeaMessageFormat(C::mip_interface& device, uint8_t* countOut, uint8_t countOutMax, NmeaMessage* formatEntriesOut) { @@ -942,7 +942,7 @@ TypedResult readNmeaMessageFormat(C::mip_interface& device, u assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length(), REPLY_NMEA_MESSAGE_FORMAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength(), REPLY_NMEA_MESSAGE_FORMAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -966,7 +966,7 @@ TypedResult saveNmeaMessageFormat(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadNmeaMessageFormat(C::mip_interface& device) { @@ -976,7 +976,7 @@ TypedResult loadNmeaMessageFormat(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultNmeaMessageFormat(C::mip_interface& device) { @@ -986,7 +986,7 @@ TypedResult defaultNmeaMessageFormat(C::mip_interface& device serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_NMEA_MESSAGE_FORMAT, buffer, (uint8_t)serializer.usedLength()); } void DeviceSettings::insert(Serializer& serializer) const { @@ -1007,7 +1007,7 @@ TypedResult saveDeviceSettings(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadDeviceSettings(C::mip_interface& device) { @@ -1017,7 +1017,7 @@ TypedResult loadDeviceSettings(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultDeviceSettings(C::mip_interface& device) { @@ -1027,7 +1027,7 @@ TypedResult defaultDeviceSettings(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DEVICE_STARTUP_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } void UartBaudrate::insert(Serializer& serializer) const { @@ -1071,7 +1071,7 @@ TypedResult writeUartBaudrate(C::mip_interface& device, uint32_t b assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* baudOut) { @@ -1082,7 +1082,7 @@ TypedResult readUartBaudrate(C::mip_interface& device, uint32_t* b assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length(), REPLY_UART_BAUDRATE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.usedLength(), REPLY_UART_BAUDRATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1104,7 +1104,7 @@ TypedResult saveUartBaudrate(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadUartBaudrate(C::mip_interface& device) { @@ -1114,7 +1114,7 @@ TypedResult loadUartBaudrate(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultUartBaudrate(C::mip_interface& device) { @@ -1124,7 +1124,7 @@ TypedResult defaultUartBaudrate(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_UART_BAUDRATE, buffer, (uint8_t)serializer.usedLength()); } void FactoryStreaming::insert(Serializer& serializer) const { @@ -1152,7 +1152,7 @@ TypedResult factoryStreaming(C::mip_interface& device, Factory assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONFIGURE_FACTORY_STREAMING, buffer, (uint8_t)serializer.usedLength()); } void DatastreamControl::insert(Serializer& serializer) const { @@ -1206,7 +1206,7 @@ TypedResult writeDatastreamControl(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.usedLength()); } TypedResult readDatastreamControl(C::mip_interface& device, uint8_t descSet, bool* enabledOut) { @@ -1219,7 +1219,7 @@ TypedResult readDatastreamControl(C::mip_interface& device, u assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length(), REPLY_DATASTREAM_ENABLE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.usedLength(), REPLY_DATASTREAM_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1245,7 +1245,7 @@ TypedResult saveDatastreamControl(C::mip_interface& device, u assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadDatastreamControl(C::mip_interface& device, uint8_t descSet) { @@ -1257,7 +1257,7 @@ TypedResult loadDatastreamControl(C::mip_interface& device, u assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultDatastreamControl(C::mip_interface& device, uint8_t descSet) { @@ -1269,7 +1269,7 @@ TypedResult defaultDatastreamControl(C::mip_interface& device assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL_DATA_STREAM, buffer, (uint8_t)serializer.usedLength()); } void ConstellationSettings::Settings::insert(Serializer& serializer) const { @@ -1368,7 +1368,7 @@ TypedResult writeConstellationSettings(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult readConstellationSettings(C::mip_interface& device, uint16_t* maxChannelsAvailableOut, uint16_t* maxChannelsUseOut, uint8_t* configCountOut, uint8_t configCountOutMax, ConstellationSettings::Settings* settingsOut) { @@ -1379,7 +1379,7 @@ TypedResult readConstellationSettings(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.usedLength(), REPLY_GNSS_CONSTELLATION_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1409,7 +1409,7 @@ TypedResult saveConstellationSettings(C::mip_interface& d serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadConstellationSettings(C::mip_interface& device) { @@ -1419,7 +1419,7 @@ TypedResult loadConstellationSettings(C::mip_interface& d serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultConstellationSettings(C::mip_interface& device) { @@ -1429,7 +1429,7 @@ TypedResult defaultConstellationSettings(C::mip_interface serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_CONSTELLATION_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } void GnssSbasSettings::insert(Serializer& serializer) const { @@ -1507,7 +1507,7 @@ TypedResult writeGnssSbasSettings(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGnssSbasSettings(C::mip_interface& device, uint8_t* enableSbasOut, GnssSbasSettings::SBASOptions* sbasOptionsOut, uint8_t* numIncludedPrnsOut, uint8_t numIncludedPrnsOutMax, uint16_t* includedPrnsOut) { @@ -1518,7 +1518,7 @@ TypedResult readGnssSbasSettings(C::mip_interface& device, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_SBAS_SETTINGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.usedLength(), REPLY_GNSS_SBAS_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1548,7 +1548,7 @@ TypedResult saveGnssSbasSettings(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGnssSbasSettings(C::mip_interface& device) { @@ -1558,7 +1558,7 @@ TypedResult loadGnssSbasSettings(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGnssSbasSettings(C::mip_interface& device) { @@ -1568,7 +1568,7 @@ TypedResult defaultGnssSbasSettings(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SBAS_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } void GnssAssistedFix::insert(Serializer& serializer) const { @@ -1622,7 +1622,7 @@ TypedResult writeGnssAssistedFix(C::mip_interface& device, Gnss assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGnssAssistedFix(C::mip_interface& device, GnssAssistedFix::AssistedFixOption* optionOut, uint8_t* flagsOut) { @@ -1633,7 +1633,7 @@ TypedResult readGnssAssistedFix(C::mip_interface& device, GnssA assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length(), REPLY_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.usedLength(), REPLY_GNSS_ASSISTED_FIX_SETTINGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1658,7 +1658,7 @@ TypedResult saveGnssAssistedFix(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGnssAssistedFix(C::mip_interface& device) { @@ -1668,7 +1668,7 @@ TypedResult loadGnssAssistedFix(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGnssAssistedFix(C::mip_interface& device) { @@ -1678,7 +1678,7 @@ TypedResult defaultGnssAssistedFix(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_ASSISTED_FIX_SETTINGS, buffer, (uint8_t)serializer.usedLength()); } void GnssTimeAssistance::insert(Serializer& serializer) const { @@ -1742,7 +1742,7 @@ TypedResult writeGnssTimeAssistance(C::mip_interface& device assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGnssTimeAssistance(C::mip_interface& device, double* towOut, uint16_t* weekNumberOut, float* accuracyOut) { @@ -1753,7 +1753,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)serializer.length(), REPLY_GNSS_TIME_ASSISTANCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_TIME_ASSISTANCE, buffer, (uint8_t)serializer.usedLength(), REPLY_GNSS_TIME_ASSISTANCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1855,7 +1855,7 @@ TypedResult writeImuLowpassFilter(C::mip_interface& device, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength()); } TypedResult readImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor, bool* enableOut, bool* manualOut, uint16_t* frequencyOut, uint8_t* reservedOut) { @@ -1868,7 +1868,7 @@ TypedResult readImuLowpassFilter(C::mip_interface& device, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length(), REPLY_ADVANCED_DATA_FILTER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength(), REPLY_ADVANCED_DATA_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1903,7 +1903,7 @@ TypedResult saveImuLowpassFilter(C::mip_interface& device, uin assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { @@ -1915,7 +1915,7 @@ TypedResult loadImuLowpassFilter(C::mip_interface& device, uin assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultImuLowpassFilter(C::mip_interface& device, uint8_t targetDescriptor) { @@ -1927,7 +1927,7 @@ TypedResult defaultImuLowpassFilter(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_IMU_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength()); } void PpsSource::insert(Serializer& serializer) const { @@ -1971,7 +1971,7 @@ TypedResult writePpsSource(C::mip_interface& device, PpsSource::Sourc assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source* sourceOut) { @@ -1982,7 +1982,7 @@ TypedResult readPpsSource(C::mip_interface& device, PpsSource::Source assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_PPS_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.usedLength(), REPLY_PPS_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2004,7 +2004,7 @@ TypedResult savePpsSource(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadPpsSource(C::mip_interface& device) { @@ -2014,7 +2014,7 @@ TypedResult loadPpsSource(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultPpsSource(C::mip_interface& device) { @@ -2024,7 +2024,7 @@ TypedResult defaultPpsSource(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PPS_SOURCE, buffer, (uint8_t)serializer.usedLength()); } void GpioConfig::insert(Serializer& serializer) const { @@ -2098,7 +2098,7 @@ TypedResult writeGpioConfig(C::mip_interface& device, uint8_t pin, G assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, GpioConfig::Feature* featureOut, GpioConfig::Behavior* behaviorOut, GpioConfig::PinMode* pinModeOut) { @@ -2111,7 +2111,7 @@ TypedResult readGpioConfig(C::mip_interface& device, uint8_t pin, Gp assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_GPIO_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.usedLength(), REPLY_GPIO_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2143,7 +2143,7 @@ TypedResult saveGpioConfig(C::mip_interface& device, uint8_t pin) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) { @@ -2155,7 +2155,7 @@ TypedResult loadGpioConfig(C::mip_interface& device, uint8_t pin) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) { @@ -2167,7 +2167,7 @@ TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_CONFIG, buffer, (uint8_t)serializer.usedLength()); } void GpioState::insert(Serializer& serializer) const { @@ -2227,7 +2227,7 @@ TypedResult writeGpioState(C::mip_interface& device, uint8_t pin, boo assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool* stateOut) { @@ -2240,7 +2240,7 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)serializer.length(), REPLY_GPIO_STATE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GPIO_STATE, buffer, (uint8_t)serializer.usedLength(), REPLY_GPIO_STATE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2318,7 +2318,7 @@ TypedResult writeOdometer(C::mip_interface& device, Odometer::Mode mod assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* modeOut, float* scalingOut, float* uncertaintyOut) { @@ -2329,7 +2329,7 @@ TypedResult readOdometer(C::mip_interface& device, Odometer::Mode* mod assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_ODOMETER_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.usedLength(), REPLY_ODOMETER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2357,7 +2357,7 @@ TypedResult saveOdometer(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadOdometer(C::mip_interface& device) { @@ -2367,7 +2367,7 @@ TypedResult loadOdometer(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultOdometer(C::mip_interface& device) { @@ -2377,7 +2377,7 @@ TypedResult defaultOdometer(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ODOMETER_CONFIG, buffer, (uint8_t)serializer.usedLength()); } void GetEventSupport::Info::insert(Serializer& serializer) const { @@ -2439,7 +2439,7 @@ TypedResult getEventSupport(C::mip_interface& device, GetEventS assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_SUPPORT, buffer, (uint8_t)serializer.length(), REPLY_EVENT_SUPPORT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_SUPPORT, buffer, (uint8_t)serializer.usedLength(), REPLY_EVENT_SUPPORT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2512,7 +2512,7 @@ TypedResult writeEventControl(C::mip_interface& device, uint8_t in assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readEventControl(C::mip_interface& device, uint8_t instance, EventControl::Mode* modeOut) { @@ -2525,7 +2525,7 @@ TypedResult readEventControl(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_EVENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_EVENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2551,7 +2551,7 @@ TypedResult saveEventControl(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadEventControl(C::mip_interface& device, uint8_t instance) { @@ -2563,7 +2563,7 @@ TypedResult loadEventControl(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultEventControl(C::mip_interface& device, uint8_t instance) { @@ -2575,7 +2575,7 @@ TypedResult defaultEventControl(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void GetEventTriggerStatus::Entry::insert(Serializer& serializer) const { @@ -2638,7 +2638,7 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_STATUS, buffer, (uint8_t)serializer.length(), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_STATUS, buffer, (uint8_t)serializer.usedLength(), REPLY_EVENT_TRIGGER_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2715,7 +2715,7 @@ TypedResult getEventActionStatus(C::mip_interface& device, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_STATUS, buffer, (uint8_t)serializer.length(), REPLY_EVENT_ACTION_STATUS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_STATUS, buffer, (uint8_t)serializer.usedLength(), REPLY_EVENT_ACTION_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2953,7 +2953,7 @@ TypedResult writeEventTrigger(C::mip_interface& device, uint8_t in } assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult readEventTrigger(C::mip_interface& device, uint8_t instance, EventTrigger::Type* typeOut, EventTrigger::Parameters* parametersOut) { @@ -2966,7 +2966,7 @@ TypedResult readEventTrigger(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_EVENT_TRIGGER_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.usedLength(), REPLY_EVENT_TRIGGER_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3007,7 +3007,7 @@ TypedResult saveEventTrigger(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadEventTrigger(C::mip_interface& device, uint8_t instance) { @@ -3019,7 +3019,7 @@ TypedResult loadEventTrigger(C::mip_interface& device, uint8_t ins assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t instance) { @@ -3031,7 +3031,7 @@ TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_TRIGGER_CONFIG, buffer, (uint8_t)serializer.usedLength()); } void EventAction::GpioParams::insert(Serializer& serializer) const { @@ -3184,7 +3184,7 @@ TypedResult writeEventAction(C::mip_interface& device, uint8_t inst } assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult readEventAction(C::mip_interface& device, uint8_t instance, uint8_t* triggerOut, EventAction::Type* typeOut, EventAction::Parameters* parametersOut) { @@ -3197,7 +3197,7 @@ TypedResult readEventAction(C::mip_interface& device, uint8_t insta assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_EVENT_ACTION_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.usedLength(), REPLY_EVENT_ACTION_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3236,7 +3236,7 @@ TypedResult saveEventAction(C::mip_interface& device, uint8_t insta assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadEventAction(C::mip_interface& device, uint8_t instance) { @@ -3248,7 +3248,7 @@ TypedResult loadEventAction(C::mip_interface& device, uint8_t insta assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultEventAction(C::mip_interface& device, uint8_t instance) { @@ -3260,7 +3260,7 @@ TypedResult defaultEventAction(C::mip_interface& device, uint8_t in assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EVENT_ACTION_CONFIG, buffer, (uint8_t)serializer.usedLength()); } void AccelBias::insert(Serializer& serializer) const { @@ -3306,7 +3306,7 @@ TypedResult writeAccelBias(C::mip_interface& device, const float* bia assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAccelBias(C::mip_interface& device, float* biasOut) { @@ -3317,7 +3317,7 @@ TypedResult readAccelBias(C::mip_interface& device, float* biasOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_BIAS_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.usedLength(), REPLY_ACCEL_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3340,7 +3340,7 @@ TypedResult saveAccelBias(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAccelBias(C::mip_interface& device) { @@ -3350,7 +3350,7 @@ TypedResult loadAccelBias(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAccelBias(C::mip_interface& device) { @@ -3360,7 +3360,7 @@ TypedResult defaultAccelBias(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS, buffer, (uint8_t)serializer.usedLength()); } void GyroBias::insert(Serializer& serializer) const { @@ -3406,7 +3406,7 @@ TypedResult writeGyroBias(C::mip_interface& device, const float* bias) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGyroBias(C::mip_interface& device, float* biasOut) { @@ -3417,7 +3417,7 @@ TypedResult readGyroBias(C::mip_interface& device, float* biasOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.usedLength(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3440,7 +3440,7 @@ TypedResult saveGyroBias(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGyroBias(C::mip_interface& device) { @@ -3450,7 +3450,7 @@ TypedResult loadGyroBias(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGyroBias(C::mip_interface& device) { @@ -3460,7 +3460,7 @@ TypedResult defaultGyroBias(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS, buffer, (uint8_t)serializer.usedLength()); } void CaptureGyroBias::insert(Serializer& serializer) const { @@ -3494,7 +3494,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CAPTURE_GYRO_BIAS, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CAPTURE_GYRO_BIAS, buffer, (uint8_t)serializer.usedLength(), REPLY_GYRO_BIAS_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3553,7 +3553,7 @@ TypedResult writeMagHardIronOffset(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult readMagHardIronOffset(C::mip_interface& device, float* offsetOut) { @@ -3564,7 +3564,7 @@ TypedResult readMagHardIronOffset(C::mip_interface& device, f assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.usedLength(), REPLY_HARD_IRON_OFFSET_VECTOR, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3587,7 +3587,7 @@ TypedResult saveMagHardIronOffset(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadMagHardIronOffset(C::mip_interface& device) { @@ -3597,7 +3597,7 @@ TypedResult loadMagHardIronOffset(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultMagHardIronOffset(C::mip_interface& device) { @@ -3607,7 +3607,7 @@ TypedResult defaultMagHardIronOffset(C::mip_interface& device serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET, buffer, (uint8_t)serializer.usedLength()); } void MagSoftIronMatrix::insert(Serializer& serializer) const { @@ -3653,7 +3653,7 @@ TypedResult writeMagSoftIronMatrix(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.usedLength()); } TypedResult readMagSoftIronMatrix(C::mip_interface& device, float* offsetOut) { @@ -3664,7 +3664,7 @@ TypedResult readMagSoftIronMatrix(C::mip_interface& device, f assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length(), REPLY_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.usedLength(), REPLY_SOFT_IRON_COMP_MATRIX, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3687,7 +3687,7 @@ TypedResult saveMagSoftIronMatrix(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadMagSoftIronMatrix(C::mip_interface& device) { @@ -3697,7 +3697,7 @@ TypedResult loadMagSoftIronMatrix(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultMagSoftIronMatrix(C::mip_interface& device) { @@ -3707,7 +3707,7 @@ TypedResult defaultMagSoftIronMatrix(C::mip_interface& device serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX, buffer, (uint8_t)serializer.usedLength()); } void ConingScullingEnable::insert(Serializer& serializer) const { @@ -3751,7 +3751,7 @@ TypedResult writeConingScullingEnable(C::mip_interface& de assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readConingScullingEnable(C::mip_interface& device, bool* enableOut) { @@ -3762,7 +3762,7 @@ TypedResult readConingScullingEnable(C::mip_interface& dev assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length(), REPLY_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.usedLength(), REPLY_CONING_AND_SCULLING_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3784,7 +3784,7 @@ TypedResult saveConingScullingEnable(C::mip_interface& dev serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadConingScullingEnable(C::mip_interface& device) { @@ -3794,7 +3794,7 @@ TypedResult loadConingScullingEnable(C::mip_interface& dev serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultConingScullingEnable(C::mip_interface& device) { @@ -3804,7 +3804,7 @@ TypedResult defaultConingScullingEnable(C::mip_interface& serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONING_AND_SCULLING_ENABLE, buffer, (uint8_t)serializer.usedLength()); } void Sensor2VehicleTransformEuler::insert(Serializer& serializer) const { @@ -3868,7 +3868,7 @@ TypedResult writeSensor2VehicleTransformEuler(C::m assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSensor2VehicleTransformEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { @@ -3879,7 +3879,7 @@ TypedResult readSensor2VehicleTransformEuler(C::mi assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.usedLength(), REPLY_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3907,7 +3907,7 @@ TypedResult saveSensor2VehicleTransformEuler(C::mi serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSensor2VehicleTransformEuler(C::mip_interface& device) { @@ -3917,7 +3917,7 @@ TypedResult loadSensor2VehicleTransformEuler(C::mi serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSensor2VehicleTransformEuler(C::mip_interface& device) { @@ -3927,7 +3927,7 @@ TypedResult defaultSensor2VehicleTransformEuler(C: serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_EUL, buffer, (uint8_t)serializer.usedLength()); } void Sensor2VehicleTransformQuaternion::insert(Serializer& serializer) const { @@ -3973,7 +3973,7 @@ TypedResult writeSensor2VehicleTransformQuate assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSensor2VehicleTransformQuaternion(C::mip_interface& device, float* qOut) { @@ -3984,7 +3984,7 @@ TypedResult readSensor2VehicleTransformQuater assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.usedLength(), REPLY_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4007,7 +4007,7 @@ TypedResult saveSensor2VehicleTransformQuater serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSensor2VehicleTransformQuaternion(C::mip_interface& device) { @@ -4017,7 +4017,7 @@ TypedResult loadSensor2VehicleTransformQuater serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSensor2VehicleTransformQuaternion(C::mip_interface& device) { @@ -4027,7 +4027,7 @@ TypedResult defaultSensor2VehicleTransformQua serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_QUAT, buffer, (uint8_t)serializer.usedLength()); } void Sensor2VehicleTransformDcm::insert(Serializer& serializer) const { @@ -4073,7 +4073,7 @@ TypedResult writeSensor2VehicleTransformDcm(C::mip_i assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSensor2VehicleTransformDcm(C::mip_interface& device, float* dcmOut) { @@ -4084,7 +4084,7 @@ TypedResult readSensor2VehicleTransformDcm(C::mip_in assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.usedLength(), REPLY_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4107,7 +4107,7 @@ TypedResult saveSensor2VehicleTransformDcm(C::mip_in serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSensor2VehicleTransformDcm(C::mip_interface& device) { @@ -4117,7 +4117,7 @@ TypedResult loadSensor2VehicleTransformDcm(C::mip_in serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSensor2VehicleTransformDcm(C::mip_interface& device) { @@ -4127,7 +4127,7 @@ TypedResult defaultSensor2VehicleTransformDcm(C::mip serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_TRANSFORM_DCM, buffer, (uint8_t)serializer.usedLength()); } void ComplementaryFilter::insert(Serializer& serializer) const { @@ -4201,7 +4201,7 @@ TypedResult writeComplementaryFilter(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.usedLength()); } TypedResult readComplementaryFilter(C::mip_interface& device, bool* pitchRollEnableOut, bool* headingEnableOut, float* pitchRollTimeConstantOut, float* headingTimeConstantOut) { @@ -4212,7 +4212,7 @@ TypedResult readComplementaryFilter(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length(), REPLY_LEGACY_COMP_FILTER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.usedLength(), REPLY_LEGACY_COMP_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4243,7 +4243,7 @@ TypedResult saveComplementaryFilter(C::mip_interface& devic serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadComplementaryFilter(C::mip_interface& device) { @@ -4253,7 +4253,7 @@ TypedResult loadComplementaryFilter(C::mip_interface& devic serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultComplementaryFilter(C::mip_interface& device) { @@ -4263,7 +4263,7 @@ TypedResult defaultComplementaryFilter(C::mip_interface& de serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LEGACY_COMP_FILTER, buffer, (uint8_t)serializer.usedLength()); } void SensorRange::insert(Serializer& serializer) const { @@ -4317,7 +4317,7 @@ TypedResult writeSensorRange(C::mip_interface& device, SensorRangeT assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSensorRange(C::mip_interface& device, SensorRangeType sensor, uint8_t* settingOut) { @@ -4330,7 +4330,7 @@ TypedResult readSensorRange(C::mip_interface& device, SensorRangeTy assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length(), REPLY_SENSOR_RANGE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.usedLength(), REPLY_SENSOR_RANGE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4356,7 +4356,7 @@ TypedResult saveSensorRange(C::mip_interface& device, SensorRangeTy assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSensorRange(C::mip_interface& device, SensorRangeType sensor) { @@ -4368,7 +4368,7 @@ TypedResult loadSensorRange(C::mip_interface& device, SensorRangeTy assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSensorRange(C::mip_interface& device, SensorRangeType sensor) { @@ -4380,7 +4380,7 @@ TypedResult defaultSensorRange(C::mip_interface& device, SensorRang assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR_RANGE, buffer, (uint8_t)serializer.usedLength()); } void CalibratedSensorRanges::Entry::insert(Serializer& serializer) const { @@ -4438,7 +4438,7 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CALIBRATED_RANGES, buffer, (uint8_t)serializer.length(), REPLY_CALIBRATED_RANGES, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CALIBRATED_RANGES, buffer, (uint8_t)serializer.usedLength(), REPLY_CALIBRATED_RANGES, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4538,7 +4538,7 @@ TypedResult writeLowpassFilter(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength()); } TypedResult readLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc, bool* enableOut, bool* manualOut, float* frequencyOut) { @@ -4553,7 +4553,7 @@ TypedResult readLowpassFilter(C::mip_interface& device, uint8_t d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length(), REPLY_LOWPASS_FILTER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength(), REPLY_LOWPASS_FILTER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4589,7 +4589,7 @@ TypedResult saveLowpassFilter(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { @@ -4603,7 +4603,7 @@ TypedResult loadLowpassFilter(C::mip_interface& device, uint8_t d assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_t descSet, uint8_t fieldDesc) { @@ -4617,7 +4617,7 @@ TypedResult defaultLowpassFilter(C::mip_interface& device, uint8_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_LOWPASS_FILTER, buffer, (uint8_t)serializer.usedLength()); } } // namespace commands_3dm diff --git a/src/cpp/mip/definitions/commands_aiding.cpp b/src/cpp/mip/definitions/commands_aiding.cpp index 6168a4014..77dd90c05 100644 --- a/src/cpp/mip/definitions/commands_aiding.cpp +++ b/src/cpp/mip/definitions/commands_aiding.cpp @@ -169,7 +169,7 @@ TypedResult writeFrameConfig(C::mip_interface& device, uint8_t fram } assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult readFrameConfig(C::mip_interface& device, uint8_t frameId, FrameConfig::Format format, bool* trackingEnabledOut, float* translationOut, FrameConfig::Rotation* rotationOut) { @@ -184,7 +184,7 @@ TypedResult readFrameConfig(C::mip_interface& device, uint8_t frame assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length(), REPLY_FRAME_CONFIG, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.usedLength(), REPLY_FRAME_CONFIG, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -226,7 +226,7 @@ TypedResult saveFrameConfig(C::mip_interface& device, uint8_t frame assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frameId) { @@ -238,7 +238,7 @@ TypedResult loadFrameConfig(C::mip_interface& device, uint8_t frame assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t frameId) { @@ -250,7 +250,7 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_FRAME_CONFIG, buffer, (uint8_t)serializer.usedLength()); } void EchoControl::insert(Serializer& serializer) const { @@ -294,7 +294,7 @@ TypedResult writeEchoControl(C::mip_interface& device, EchoControl: assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readEchoControl(C::mip_interface& device, EchoControl::Mode* modeOut) { @@ -305,7 +305,7 @@ TypedResult readEchoControl(C::mip_interface& device, EchoControl:: assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ECHO_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_ECHO_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -327,7 +327,7 @@ TypedResult saveEchoControl(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadEchoControl(C::mip_interface& device) { @@ -337,7 +337,7 @@ TypedResult loadEchoControl(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultEchoControl(C::mip_interface& device) { @@ -347,7 +347,7 @@ TypedResult defaultEchoControl(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ECHO_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void PosEcef::insert(Serializer& serializer) const { @@ -397,7 +397,7 @@ TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_ECEF, buffer, (uint8_t)serializer.usedLength()); } void PosLlh::insert(Serializer& serializer) const { @@ -457,7 +457,7 @@ TypedResult posLlh(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_POS_LLH, buffer, (uint8_t)serializer.usedLength()); } void HeightAboveEllipsoid::insert(Serializer& serializer) const { @@ -503,7 +503,7 @@ TypedResult heightAboveEllipsoid(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABOVE_ELLIPSOID, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEIGHT_ABOVE_ELLIPSOID, buffer, (uint8_t)serializer.usedLength()); } void VelEcef::insert(Serializer& serializer) const { @@ -553,7 +553,7 @@ TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_ECEF, buffer, (uint8_t)serializer.usedLength()); } void VelNed::insert(Serializer& serializer) const { @@ -603,7 +603,7 @@ TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t f assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_NED, buffer, (uint8_t)serializer.usedLength()); } void VelBodyFrame::insert(Serializer& serializer) const { @@ -653,7 +653,7 @@ TypedResult velBodyFrame(C::mip_interface& device, const Time& tim assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_BODY_FRAME, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEL_BODY_FRAME, buffer, (uint8_t)serializer.usedLength()); } void HeadingTrue::insert(Serializer& serializer) const { @@ -699,7 +699,7 @@ TypedResult headingTrue(C::mip_interface& device, const Time& time, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_TRUE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_TRUE, buffer, (uint8_t)serializer.usedLength()); } void MagneticField::insert(Serializer& serializer) const { @@ -749,7 +749,7 @@ TypedResult magneticField(C::mip_interface& device, const Time& t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_FIELD, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_FIELD, buffer, (uint8_t)serializer.usedLength()); } void Pressure::insert(Serializer& serializer) const { @@ -795,7 +795,7 @@ TypedResult pressure(C::mip_interface& device, const Time& time, uint8 assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE, buffer, (uint8_t)serializer.usedLength()); } } // namespace commands_aiding diff --git a/src/cpp/mip/definitions/commands_base.cpp b/src/cpp/mip/definitions/commands_base.cpp index e8edbaec2..07dbc036d 100644 --- a/src/cpp/mip/definitions/commands_base.cpp +++ b/src/cpp/mip/definitions/commands_base.cpp @@ -354,7 +354,7 @@ TypedResult writeCommSpeed(C::mip_interface& device, uint8_t port, ui assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.usedLength()); } TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uint32_t* baudOut) { @@ -367,7 +367,7 @@ TypedResult readCommSpeed(C::mip_interface& device, uint8_t port, uin assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length(), REPLY_COMM_SPEED, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.usedLength(), REPLY_COMM_SPEED, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -393,7 +393,7 @@ TypedResult saveCommSpeed(C::mip_interface& device, uint8_t port) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) { @@ -405,7 +405,7 @@ TypedResult loadCommSpeed(C::mip_interface& device, uint8_t port) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) { @@ -417,7 +417,7 @@ TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COMM_SPEED, buffer, (uint8_t)serializer.usedLength()); } void GpsTimeUpdate::insert(Serializer& serializer) const { @@ -456,7 +456,7 @@ TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeU assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GPS_TIME_UPDATE, buffer, (uint8_t)serializer.usedLength()); } void SoftReset::insert(Serializer& serializer) const { diff --git a/src/cpp/mip/definitions/commands_filter.cpp b/src/cpp/mip/definitions/commands_filter.cpp index 9a444f810..e4a477435 100644 --- a/src/cpp/mip/definitions/commands_filter.cpp +++ b/src/cpp/mip/definitions/commands_filter.cpp @@ -65,7 +65,7 @@ TypedResult setInitialAttitude(C::mip_interface& device, flo assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_ATTITUDE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_ATTITUDE, buffer, (uint8_t)serializer.usedLength()); } void EstimationControl::insert(Serializer& serializer) const { @@ -109,7 +109,7 @@ TypedResult writeEstimationControl(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult readEstimationControl(C::mip_interface& device, EstimationControl::EnableFlags* enableOut) { @@ -120,7 +120,7 @@ TypedResult readEstimationControl(C::mip_interface& device, E assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length(), REPLY_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.usedLength(), REPLY_ESTIMATION_CONTROL_FLAGS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -142,7 +142,7 @@ TypedResult saveEstimationControl(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadEstimationControl(C::mip_interface& device) { @@ -152,7 +152,7 @@ TypedResult loadEstimationControl(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultEstimationControl(C::mip_interface& device) { @@ -162,7 +162,7 @@ TypedResult defaultEstimationControl(C::mip_interface& device serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ESTIMATION_CONTROL_FLAGS, buffer, (uint8_t)serializer.usedLength()); } void ExternalGnssUpdate::insert(Serializer& serializer) const { @@ -232,7 +232,7 @@ TypedResult externalGnssUpdate(C::mip_interface& device, dou assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_GNSS_UPDATE, buffer, (uint8_t)serializer.usedLength()); } void ExternalHeadingUpdate::insert(Serializer& serializer) const { @@ -266,7 +266,7 @@ TypedResult externalHeadingUpdate(C::mip_interface& devic assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE, buffer, (uint8_t)serializer.usedLength()); } void ExternalHeadingUpdateWithTime::insert(Serializer& serializer) const { @@ -312,7 +312,7 @@ TypedResult externalHeadingUpdateWithTime(C::mip_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_EXTERNAL_HEADING_UPDATE_WITH_TIME, buffer, (uint8_t)serializer.usedLength()); } void TareOrientation::insert(Serializer& serializer) const { @@ -356,7 +356,7 @@ TypedResult writeTareOrientation(C::mip_interface& device, Tare assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult readTareOrientation(C::mip_interface& device, TareOrientation::MipTareAxes* axesOut) { @@ -367,7 +367,7 @@ TypedResult readTareOrientation(C::mip_interface& device, TareO assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length(), REPLY_TARE_ORIENTATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.usedLength(), REPLY_TARE_ORIENTATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -389,7 +389,7 @@ TypedResult saveTareOrientation(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadTareOrientation(C::mip_interface& device) { @@ -399,7 +399,7 @@ TypedResult loadTareOrientation(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultTareOrientation(C::mip_interface& device) { @@ -409,7 +409,7 @@ TypedResult defaultTareOrientation(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_TARE_ORIENTATION, buffer, (uint8_t)serializer.usedLength()); } void VehicleDynamicsMode::insert(Serializer& serializer) const { @@ -453,7 +453,7 @@ TypedResult writeVehicleDynamicsMode(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readVehicleDynamicsMode(C::mip_interface& device, VehicleDynamicsMode::DynamicsMode* modeOut) { @@ -464,7 +464,7 @@ TypedResult readVehicleDynamicsMode(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length(), REPLY_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.usedLength(), REPLY_VEHICLE_DYNAMICS_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -486,7 +486,7 @@ TypedResult saveVehicleDynamicsMode(C::mip_interface& devic serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadVehicleDynamicsMode(C::mip_interface& device) { @@ -496,7 +496,7 @@ TypedResult loadVehicleDynamicsMode(C::mip_interface& devic serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultVehicleDynamicsMode(C::mip_interface& device) { @@ -506,7 +506,7 @@ TypedResult defaultVehicleDynamicsMode(C::mip_interface& de serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_DYNAMICS_MODE, buffer, (uint8_t)serializer.usedLength()); } void SensorToVehicleRotationEuler::insert(Serializer& serializer) const { @@ -570,7 +570,7 @@ TypedResult writeSensorToVehicleRotationEuler(C::m assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSensorToVehicleRotationEuler(C::mip_interface& device, float* rollOut, float* pitchOut, float* yawOut) { @@ -581,7 +581,7 @@ TypedResult readSensorToVehicleRotationEuler(C::mi assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.usedLength(), REPLY_SENSOR2VEHICLE_ROTATION_EULER, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -609,7 +609,7 @@ TypedResult saveSensorToVehicleRotationEuler(C::mi serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSensorToVehicleRotationEuler(C::mip_interface& device) { @@ -619,7 +619,7 @@ TypedResult loadSensorToVehicleRotationEuler(C::mi serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSensorToVehicleRotationEuler(C::mip_interface& device) { @@ -629,7 +629,7 @@ TypedResult defaultSensorToVehicleRotationEuler(C: serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_EULER, buffer, (uint8_t)serializer.usedLength()); } void SensorToVehicleRotationDcm::insert(Serializer& serializer) const { @@ -675,7 +675,7 @@ TypedResult writeSensorToVehicleRotationDcm(C::mip_i assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSensorToVehicleRotationDcm(C::mip_interface& device, float* dcmOut) { @@ -686,7 +686,7 @@ TypedResult readSensorToVehicleRotationDcm(C::mip_in assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.usedLength(), REPLY_SENSOR2VEHICLE_ROTATION_DCM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -709,7 +709,7 @@ TypedResult saveSensorToVehicleRotationDcm(C::mip_in serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSensorToVehicleRotationDcm(C::mip_interface& device) { @@ -719,7 +719,7 @@ TypedResult loadSensorToVehicleRotationDcm(C::mip_in serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSensorToVehicleRotationDcm(C::mip_interface& device) { @@ -729,7 +729,7 @@ TypedResult defaultSensorToVehicleRotationDcm(C::mip serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_DCM, buffer, (uint8_t)serializer.usedLength()); } void SensorToVehicleRotationQuaternion::insert(Serializer& serializer) const { @@ -775,7 +775,7 @@ TypedResult writeSensorToVehicleRotationQuate assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSensorToVehicleRotationQuaternion(C::mip_interface& device, float* quatOut) { @@ -786,7 +786,7 @@ TypedResult readSensorToVehicleRotationQuater assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.usedLength(), REPLY_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -809,7 +809,7 @@ TypedResult saveSensorToVehicleRotationQuater serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSensorToVehicleRotationQuaternion(C::mip_interface& device) { @@ -819,7 +819,7 @@ TypedResult loadSensorToVehicleRotationQuater serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSensorToVehicleRotationQuaternion(C::mip_interface& device) { @@ -829,7 +829,7 @@ TypedResult defaultSensorToVehicleRotationQua serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_ROTATION_QUATERNION, buffer, (uint8_t)serializer.usedLength()); } void SensorToVehicleOffset::insert(Serializer& serializer) const { @@ -875,7 +875,7 @@ TypedResult writeSensorToVehicleOffset(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSensorToVehicleOffset(C::mip_interface& device, float* offsetOut) { @@ -886,7 +886,7 @@ TypedResult readSensorToVehicleOffset(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.usedLength(), REPLY_SENSOR2VEHICLE_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -909,7 +909,7 @@ TypedResult saveSensorToVehicleOffset(C::mip_interface& d serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSensorToVehicleOffset(C::mip_interface& device) { @@ -919,7 +919,7 @@ TypedResult loadSensorToVehicleOffset(C::mip_interface& d serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSensorToVehicleOffset(C::mip_interface& device) { @@ -929,7 +929,7 @@ TypedResult defaultSensorToVehicleOffset(C::mip_interface serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SENSOR2VEHICLE_OFFSET, buffer, (uint8_t)serializer.usedLength()); } void AntennaOffset::insert(Serializer& serializer) const { @@ -975,7 +975,7 @@ TypedResult writeAntennaOffset(C::mip_interface& device, const fl assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAntennaOffset(C::mip_interface& device, float* offsetOut) { @@ -986,7 +986,7 @@ TypedResult readAntennaOffset(C::mip_interface& device, float* of assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_ANTENNA_OFFSET, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength(), REPLY_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1009,7 +1009,7 @@ TypedResult saveAntennaOffset(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAntennaOffset(C::mip_interface& device) { @@ -1019,7 +1019,7 @@ TypedResult loadAntennaOffset(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAntennaOffset(C::mip_interface& device) { @@ -1029,7 +1029,7 @@ TypedResult defaultAntennaOffset(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength()); } void GnssSource::insert(Serializer& serializer) const { @@ -1073,7 +1073,7 @@ TypedResult writeGnssSource(C::mip_interface& device, GnssSource::So assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGnssSource(C::mip_interface& device, GnssSource::Source* sourceOut) { @@ -1084,7 +1084,7 @@ TypedResult readGnssSource(C::mip_interface& device, GnssSource::Sou assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_GNSS_SOURCE_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_GNSS_SOURCE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1106,7 +1106,7 @@ TypedResult saveGnssSource(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGnssSource(C::mip_interface& device) { @@ -1116,7 +1116,7 @@ TypedResult loadGnssSource(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGnssSource(C::mip_interface& device) { @@ -1126,7 +1126,7 @@ TypedResult defaultGnssSource(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GNSS_SOURCE_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void HeadingSource::insert(Serializer& serializer) const { @@ -1170,7 +1170,7 @@ TypedResult writeHeadingSource(C::mip_interface& device, HeadingS assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readHeadingSource(C::mip_interface& device, HeadingSource::Source* sourceOut) { @@ -1181,7 +1181,7 @@ TypedResult readHeadingSource(C::mip_interface& device, HeadingSo assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_HEADING_UPDATE_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_HEADING_UPDATE_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1203,7 +1203,7 @@ TypedResult saveHeadingSource(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadHeadingSource(C::mip_interface& device) { @@ -1213,7 +1213,7 @@ TypedResult loadHeadingSource(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultHeadingSource(C::mip_interface& device) { @@ -1223,7 +1223,7 @@ TypedResult defaultHeadingSource(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HEADING_UPDATE_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void AutoInitControl::insert(Serializer& serializer) const { @@ -1267,7 +1267,7 @@ TypedResult writeAutoInitControl(C::mip_interface& device, uint assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAutoInitControl(C::mip_interface& device, uint8_t* enableOut) { @@ -1278,7 +1278,7 @@ TypedResult readAutoInitControl(C::mip_interface& device, uint8 assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_AUTOINIT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_AUTOINIT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1300,7 +1300,7 @@ TypedResult saveAutoInitControl(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAutoInitControl(C::mip_interface& device) { @@ -1310,7 +1310,7 @@ TypedResult loadAutoInitControl(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAutoInitControl(C::mip_interface& device) { @@ -1320,7 +1320,7 @@ TypedResult defaultAutoInitControl(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AUTOINIT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void AccelNoise::insert(Serializer& serializer) const { @@ -1366,7 +1366,7 @@ TypedResult writeAccelNoise(C::mip_interface& device, const float* n assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut) { @@ -1377,7 +1377,7 @@ TypedResult readAccelNoise(C::mip_interface& device, float* noiseOut assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.usedLength(), REPLY_ACCEL_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1400,7 +1400,7 @@ TypedResult saveAccelNoise(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAccelNoise(C::mip_interface& device) { @@ -1410,7 +1410,7 @@ TypedResult loadAccelNoise(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAccelNoise(C::mip_interface& device) { @@ -1420,7 +1420,7 @@ TypedResult defaultAccelNoise(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_NOISE, buffer, (uint8_t)serializer.usedLength()); } void GyroNoise::insert(Serializer& serializer) const { @@ -1466,7 +1466,7 @@ TypedResult writeGyroNoise(C::mip_interface& device, const float* noi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) { @@ -1477,7 +1477,7 @@ TypedResult readGyroNoise(C::mip_interface& device, float* noiseOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length(), REPLY_GYRO_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.usedLength(), REPLY_GYRO_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1500,7 +1500,7 @@ TypedResult saveGyroNoise(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGyroNoise(C::mip_interface& device) { @@ -1510,7 +1510,7 @@ TypedResult loadGyroNoise(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGyroNoise(C::mip_interface& device) { @@ -1520,7 +1520,7 @@ TypedResult defaultGyroNoise(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_NOISE, buffer, (uint8_t)serializer.usedLength()); } void AccelBiasModel::insert(Serializer& serializer) const { @@ -1578,7 +1578,7 @@ TypedResult writeAccelBiasModel(C::mip_interface& device, const assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAccelBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { @@ -1589,7 +1589,7 @@ TypedResult readAccelBiasModel(C::mip_interface& device, float* assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_BIAS_MODEL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength(), REPLY_ACCEL_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1616,7 +1616,7 @@ TypedResult saveAccelBiasModel(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAccelBiasModel(C::mip_interface& device) { @@ -1626,7 +1626,7 @@ TypedResult loadAccelBiasModel(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAccelBiasModel(C::mip_interface& device) { @@ -1636,7 +1636,7 @@ TypedResult defaultAccelBiasModel(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength()); } void GyroBiasModel::insert(Serializer& serializer) const { @@ -1694,7 +1694,7 @@ TypedResult writeGyroBiasModel(C::mip_interface& device, const fl assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGyroBiasModel(C::mip_interface& device, float* betaOut, float* noiseOut) { @@ -1705,7 +1705,7 @@ TypedResult readGyroBiasModel(C::mip_interface& device, float* be assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length(), REPLY_GYRO_BIAS_MODEL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength(), REPLY_GYRO_BIAS_MODEL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1732,7 +1732,7 @@ TypedResult saveGyroBiasModel(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGyroBiasModel(C::mip_interface& device) { @@ -1742,7 +1742,7 @@ TypedResult loadGyroBiasModel(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGyroBiasModel(C::mip_interface& device) { @@ -1752,7 +1752,7 @@ TypedResult defaultGyroBiasModel(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_BIAS_MODEL, buffer, (uint8_t)serializer.usedLength()); } void AltitudeAiding::insert(Serializer& serializer) const { @@ -1796,7 +1796,7 @@ TypedResult writeAltitudeAiding(C::mip_interface& device, Altitu assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAltitudeAiding(C::mip_interface& device, AltitudeAiding::AidingSelector* selectorOut) { @@ -1807,7 +1807,7 @@ TypedResult readAltitudeAiding(C::mip_interface& device, Altitud assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_ALTITUDE_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1829,7 +1829,7 @@ TypedResult saveAltitudeAiding(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAltitudeAiding(C::mip_interface& device) { @@ -1839,7 +1839,7 @@ TypedResult loadAltitudeAiding(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAltitudeAiding(C::mip_interface& device) { @@ -1849,7 +1849,7 @@ TypedResult defaultAltitudeAiding(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ALTITUDE_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void PitchRollAiding::insert(Serializer& serializer) const { @@ -1893,7 +1893,7 @@ TypedResult writePitchRollAiding(C::mip_interface& device, Pitc assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readPitchRollAiding(C::mip_interface& device, PitchRollAiding::AidingSource* sourceOut) { @@ -1904,7 +1904,7 @@ TypedResult readPitchRollAiding(C::mip_interface& device, Pitch assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -1926,7 +1926,7 @@ TypedResult savePitchRollAiding(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadPitchRollAiding(C::mip_interface& device) { @@ -1936,7 +1936,7 @@ TypedResult loadPitchRollAiding(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultPitchRollAiding(C::mip_interface& device) { @@ -1946,7 +1946,7 @@ TypedResult defaultPitchRollAiding(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SECONDARY_PITCH_ROLL_AIDING_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void AutoZupt::insert(Serializer& serializer) const { @@ -2000,7 +2000,7 @@ TypedResult writeAutoZupt(C::mip_interface& device, uint8_t enable, fl assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { @@ -2011,7 +2011,7 @@ TypedResult readAutoZupt(C::mip_interface& device, uint8_t* enableOut, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ZUPT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2036,7 +2036,7 @@ TypedResult saveAutoZupt(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAutoZupt(C::mip_interface& device) { @@ -2046,7 +2046,7 @@ TypedResult loadAutoZupt(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAutoZupt(C::mip_interface& device) { @@ -2056,7 +2056,7 @@ TypedResult defaultAutoZupt(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void AutoAngularZupt::insert(Serializer& serializer) const { @@ -2110,7 +2110,7 @@ TypedResult writeAutoAngularZupt(C::mip_interface& device, uint assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAutoAngularZupt(C::mip_interface& device, uint8_t* enableOut, float* thresholdOut) { @@ -2121,7 +2121,7 @@ TypedResult readAutoAngularZupt(C::mip_interface& device, uint8 assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_ANGULAR_ZUPT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2146,7 +2146,7 @@ TypedResult saveAutoAngularZupt(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAutoAngularZupt(C::mip_interface& device) { @@ -2156,7 +2156,7 @@ TypedResult loadAutoAngularZupt(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAutoAngularZupt(C::mip_interface& device) { @@ -2166,7 +2166,7 @@ TypedResult defaultAutoAngularZupt(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANGULAR_ZUPT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void CommandedZupt::insert(Serializer& serializer) const { @@ -2213,7 +2213,7 @@ TypedResult writeMagCaptureAutoCal(C::mip_interface& device) serializer.insert(FunctionSelector::WRITE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult saveMagCaptureAutoCal(C::mip_interface& device) { @@ -2223,7 +2223,7 @@ TypedResult saveMagCaptureAutoCal(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_CAPTURE_AUTO_CALIBRATION, buffer, (uint8_t)serializer.usedLength()); } void GravityNoise::insert(Serializer& serializer) const { @@ -2269,7 +2269,7 @@ TypedResult writeGravityNoise(C::mip_interface& device, const floa assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGravityNoise(C::mip_interface& device, float* noiseOut) { @@ -2280,7 +2280,7 @@ TypedResult readGravityNoise(C::mip_interface& device, float* nois assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length(), REPLY_GRAVITY_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.usedLength(), REPLY_GRAVITY_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2303,7 +2303,7 @@ TypedResult saveGravityNoise(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGravityNoise(C::mip_interface& device) { @@ -2313,7 +2313,7 @@ TypedResult loadGravityNoise(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGravityNoise(C::mip_interface& device) { @@ -2323,7 +2323,7 @@ TypedResult defaultGravityNoise(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GRAVITY_NOISE, buffer, (uint8_t)serializer.usedLength()); } void PressureAltitudeNoise::insert(Serializer& serializer) const { @@ -2367,7 +2367,7 @@ TypedResult writePressureAltitudeNoise(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readPressureAltitudeNoise(C::mip_interface& device, float* noiseOut) { @@ -2378,7 +2378,7 @@ TypedResult readPressureAltitudeNoise(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length(), REPLY_PRESSURE_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.usedLength(), REPLY_PRESSURE_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2400,7 +2400,7 @@ TypedResult savePressureAltitudeNoise(C::mip_interface& d serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadPressureAltitudeNoise(C::mip_interface& device) { @@ -2410,7 +2410,7 @@ TypedResult loadPressureAltitudeNoise(C::mip_interface& d serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultPressureAltitudeNoise(C::mip_interface& device) { @@ -2420,7 +2420,7 @@ TypedResult defaultPressureAltitudeNoise(C::mip_interface serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PRESSURE_NOISE, buffer, (uint8_t)serializer.usedLength()); } void HardIronOffsetNoise::insert(Serializer& serializer) const { @@ -2466,7 +2466,7 @@ TypedResult writeHardIronOffsetNoise(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readHardIronOffsetNoise(C::mip_interface& device, float* noiseOut) { @@ -2477,7 +2477,7 @@ TypedResult readHardIronOffsetNoise(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length(), REPLY_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.usedLength(), REPLY_HARD_IRON_OFFSET_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2500,7 +2500,7 @@ TypedResult saveHardIronOffsetNoise(C::mip_interface& devic serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadHardIronOffsetNoise(C::mip_interface& device) { @@ -2510,7 +2510,7 @@ TypedResult loadHardIronOffsetNoise(C::mip_interface& devic serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultHardIronOffsetNoise(C::mip_interface& device) { @@ -2520,7 +2520,7 @@ TypedResult defaultHardIronOffsetNoise(C::mip_interface& de serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_HARD_IRON_OFFSET_NOISE, buffer, (uint8_t)serializer.usedLength()); } void SoftIronMatrixNoise::insert(Serializer& serializer) const { @@ -2566,7 +2566,7 @@ TypedResult writeSoftIronMatrixNoise(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSoftIronMatrixNoise(C::mip_interface& device, float* noiseOut) { @@ -2577,7 +2577,7 @@ TypedResult readSoftIronMatrixNoise(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length(), REPLY_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.usedLength(), REPLY_SOFT_IRON_MATRIX_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2600,7 +2600,7 @@ TypedResult saveSoftIronMatrixNoise(C::mip_interface& devic serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSoftIronMatrixNoise(C::mip_interface& device) { @@ -2610,7 +2610,7 @@ TypedResult loadSoftIronMatrixNoise(C::mip_interface& devic serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSoftIronMatrixNoise(C::mip_interface& device) { @@ -2620,7 +2620,7 @@ TypedResult defaultSoftIronMatrixNoise(C::mip_interface& de serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SOFT_IRON_MATRIX_NOISE, buffer, (uint8_t)serializer.usedLength()); } void MagNoise::insert(Serializer& serializer) const { @@ -2666,7 +2666,7 @@ TypedResult writeMagNoise(C::mip_interface& device, const float* noise assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) { @@ -2677,7 +2677,7 @@ TypedResult readMagNoise(C::mip_interface& device, float* noiseOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length(), REPLY_MAG_NOISE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.usedLength(), REPLY_MAG_NOISE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2700,7 +2700,7 @@ TypedResult saveMagNoise(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadMagNoise(C::mip_interface& device) { @@ -2710,7 +2710,7 @@ TypedResult loadMagNoise(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultMagNoise(C::mip_interface& device) { @@ -2720,7 +2720,7 @@ TypedResult defaultMagNoise(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_NOISE, buffer, (uint8_t)serializer.usedLength()); } void InclinationSource::insert(Serializer& serializer) const { @@ -2774,7 +2774,7 @@ TypedResult writeInclinationSource(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readInclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* inclinationOut) { @@ -2785,7 +2785,7 @@ TypedResult readInclinationSource(C::mip_interface& device, F assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_INCLINATION_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength(), REPLY_INCLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2810,7 +2810,7 @@ TypedResult saveInclinationSource(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadInclinationSource(C::mip_interface& device) { @@ -2820,7 +2820,7 @@ TypedResult loadInclinationSource(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultInclinationSource(C::mip_interface& device) { @@ -2830,7 +2830,7 @@ TypedResult defaultInclinationSource(C::mip_interface& device serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INCLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength()); } void MagneticDeclinationSource::insert(Serializer& serializer) const { @@ -2884,7 +2884,7 @@ TypedResult writeMagneticDeclinationSource(C::mip_int assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readMagneticDeclinationSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* declinationOut) { @@ -2895,7 +2895,7 @@ TypedResult readMagneticDeclinationSource(C::mip_inte assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_DECLINATION_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength(), REPLY_DECLINATION_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -2920,7 +2920,7 @@ TypedResult saveMagneticDeclinationSource(C::mip_inte serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadMagneticDeclinationSource(C::mip_interface& device) { @@ -2930,7 +2930,7 @@ TypedResult loadMagneticDeclinationSource(C::mip_inte serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultMagneticDeclinationSource(C::mip_interface& device) { @@ -2940,7 +2940,7 @@ TypedResult defaultMagneticDeclinationSource(C::mip_i serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_DECLINATION_SOURCE, buffer, (uint8_t)serializer.usedLength()); } void MagFieldMagnitudeSource::insert(Serializer& serializer) const { @@ -2994,7 +2994,7 @@ TypedResult writeMagFieldMagnitudeSource(C::mip_interfa assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readMagFieldMagnitudeSource(C::mip_interface& device, FilterMagParamSource* sourceOut, float* magnitudeOut) { @@ -3005,7 +3005,7 @@ TypedResult readMagFieldMagnitudeSource(C::mip_interfac assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length(), REPLY_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.usedLength(), REPLY_MAGNETIC_MAGNITUDE_SOURCE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3030,7 +3030,7 @@ TypedResult saveMagFieldMagnitudeSource(C::mip_interfac serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadMagFieldMagnitudeSource(C::mip_interface& device) { @@ -3040,7 +3040,7 @@ TypedResult loadMagFieldMagnitudeSource(C::mip_interfac serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultMagFieldMagnitudeSource(C::mip_interface& device) { @@ -3050,7 +3050,7 @@ TypedResult defaultMagFieldMagnitudeSource(C::mip_inter serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAGNETIC_MAGNITUDE_SOURCE, buffer, (uint8_t)serializer.usedLength()); } void ReferencePosition::insert(Serializer& serializer) const { @@ -3124,7 +3124,7 @@ TypedResult writeReferencePosition(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.usedLength()); } TypedResult readReferencePosition(C::mip_interface& device, bool* enableOut, double* latitudeOut, double* longitudeOut, double* altitudeOut) { @@ -3135,7 +3135,7 @@ TypedResult readReferencePosition(C::mip_interface& device, b assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length(), REPLY_REFERENCE_POSITION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.usedLength(), REPLY_REFERENCE_POSITION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3166,7 +3166,7 @@ TypedResult saveReferencePosition(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadReferencePosition(C::mip_interface& device) { @@ -3176,7 +3176,7 @@ TypedResult loadReferencePosition(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultReferencePosition(C::mip_interface& device) { @@ -3186,7 +3186,7 @@ TypedResult defaultReferencePosition(C::mip_interface& device serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REFERENCE_POSITION, buffer, (uint8_t)serializer.usedLength()); } void AccelMagnitudeErrorAdaptiveMeasurement::insert(Serializer& serializer) const { @@ -3290,7 +3290,7 @@ TypedResult writeAccelMagnitudeErrorAdap assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { @@ -3301,7 +3301,7 @@ TypedResult readAccelMagnitudeErrorAdapt assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3341,7 +3341,7 @@ TypedResult saveAccelMagnitudeErrorAdapt serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3351,7 +3351,7 @@ TypedResult loadAccelMagnitudeErrorAdapt serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAccelMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3361,7 +3361,7 @@ TypedResult defaultAccelMagnitudeErrorAd serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ACCEL_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void MagMagnitudeErrorAdaptiveMeasurement::insert(Serializer& serializer) const { @@ -3465,7 +3465,7 @@ TypedResult writeMagMagnitudeErrorAdaptive assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device, FilterAdaptiveMeasurement* adaptiveMeasurementOut, float* frequencyOut, float* lowLimitOut, float* highLimitOut, float* lowLimitUncertaintyOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { @@ -3476,7 +3476,7 @@ TypedResult readMagMagnitudeErrorAdaptiveM assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3516,7 +3516,7 @@ TypedResult saveMagMagnitudeErrorAdaptiveM serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3526,7 +3526,7 @@ TypedResult loadMagMagnitudeErrorAdaptiveM serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultMagMagnitudeErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3536,7 +3536,7 @@ TypedResult defaultMagMagnitudeErrorAdapti serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_MAGNITUDE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void MagDipAngleErrorAdaptiveMeasurement::insert(Serializer& serializer) const { @@ -3620,7 +3620,7 @@ TypedResult writeMagDipAngleErrorAdaptiveMe assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device, bool* enableOut, float* frequencyOut, float* highLimitOut, float* highLimitUncertaintyOut, float* minimumUncertaintyOut) { @@ -3631,7 +3631,7 @@ TypedResult readMagDipAngleErrorAdaptiveMea assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3665,7 +3665,7 @@ TypedResult saveMagDipAngleErrorAdaptiveMea serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3675,7 +3675,7 @@ TypedResult loadMagDipAngleErrorAdaptiveMea serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultMagDipAngleErrorAdaptiveMeasurement(C::mip_interface& device) { @@ -3685,7 +3685,7 @@ TypedResult defaultMagDipAngleErrorAdaptive serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MAG_DIP_ANGLE_ERROR_ADAPTIVE_MEASUREMENT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void AidingMeasurementEnable::insert(Serializer& serializer) const { @@ -3739,7 +3739,7 @@ TypedResult writeAidingMeasurementEnable(C::mip_interfa assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource, bool* enableOut) { @@ -3752,7 +3752,7 @@ TypedResult readAidingMeasurementEnable(C::mip_interfac assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length(), REPLY_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.usedLength(), REPLY_AIDING_MEASUREMENT_ENABLE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3778,7 +3778,7 @@ TypedResult saveAidingMeasurementEnable(C::mip_interfac assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { @@ -3790,7 +3790,7 @@ TypedResult loadAidingMeasurementEnable(C::mip_interfac assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAidingMeasurementEnable(C::mip_interface& device, AidingMeasurementEnable::AidingSource aidingSource) { @@ -3802,7 +3802,7 @@ TypedResult defaultAidingMeasurementEnable(C::mip_inter assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_AIDING_MEASUREMENT_ENABLE, buffer, (uint8_t)serializer.usedLength()); } void Run::insert(Serializer& serializer) const { @@ -3879,7 +3879,7 @@ TypedResult writeKinematicConstraint(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.usedLength()); } TypedResult readKinematicConstraint(C::mip_interface& device, uint8_t* accelerationConstraintSelectionOut, uint8_t* velocityConstraintSelectionOut, uint8_t* angularConstraintSelectionOut) { @@ -3890,7 +3890,7 @@ TypedResult readKinematicConstraint(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length(), REPLY_KINEMATIC_CONSTRAINT, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.usedLength(), REPLY_KINEMATIC_CONSTRAINT, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -3918,7 +3918,7 @@ TypedResult saveKinematicConstraint(C::mip_interface& devic serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadKinematicConstraint(C::mip_interface& device) { @@ -3928,7 +3928,7 @@ TypedResult loadKinematicConstraint(C::mip_interface& devic serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultKinematicConstraint(C::mip_interface& device) { @@ -3938,7 +3938,7 @@ TypedResult defaultKinematicConstraint(C::mip_interface& de serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_KINEMATIC_CONSTRAINT, buffer, (uint8_t)serializer.usedLength()); } void InitializationConfiguration::insert(Serializer& serializer) const { @@ -4066,7 +4066,7 @@ TypedResult writeInitializationConfiguration(C::mip assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult readInitializationConfiguration(C::mip_interface& device, uint8_t* waitForRunCommandOut, InitializationConfiguration::InitialConditionSource* initialCondSrcOut, InitializationConfiguration::AlignmentSelector* autoHeadingAlignmentSelectorOut, float* initialHeadingOut, float* initialPitchOut, float* initialRollOut, float* initialPositionOut, float* initialVelocityOut, FilterReferenceFrame* referenceFrameSelectorOut) { @@ -4077,7 +4077,7 @@ TypedResult readInitializationConfiguration(C::mip_ assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_INITIALIZATION_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.usedLength(), REPLY_INITIALIZATION_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4125,7 +4125,7 @@ TypedResult saveInitializationConfiguration(C::mip_ serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadInitializationConfiguration(C::mip_interface& device) { @@ -4135,7 +4135,7 @@ TypedResult loadInitializationConfiguration(C::mip_ serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultInitializationConfiguration(C::mip_interface& device) { @@ -4145,7 +4145,7 @@ TypedResult defaultInitializationConfiguration(C::m serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_INITIALIZATION_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } void AdaptiveFilterOptions::insert(Serializer& serializer) const { @@ -4199,7 +4199,7 @@ TypedResult writeAdaptiveFilterOptions(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.usedLength()); } TypedResult readAdaptiveFilterOptions(C::mip_interface& device, uint8_t* levelOut, uint16_t* timeLimitOut) { @@ -4210,7 +4210,7 @@ TypedResult readAdaptiveFilterOptions(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length(), REPLY_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.usedLength(), REPLY_ADAPTIVE_FILTER_OPTIONS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4235,7 +4235,7 @@ TypedResult saveAdaptiveFilterOptions(C::mip_interface& d serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadAdaptiveFilterOptions(C::mip_interface& device) { @@ -4245,7 +4245,7 @@ TypedResult loadAdaptiveFilterOptions(C::mip_interface& d serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultAdaptiveFilterOptions(C::mip_interface& device) { @@ -4255,7 +4255,7 @@ TypedResult defaultAdaptiveFilterOptions(C::mip_interface serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ADAPTIVE_FILTER_OPTIONS, buffer, (uint8_t)serializer.usedLength()); } void MultiAntennaOffset::insert(Serializer& serializer) const { @@ -4311,7 +4311,7 @@ TypedResult writeMultiAntennaOffset(C::mip_interface& device assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult readMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId, float* antennaOffsetOut) { @@ -4324,7 +4324,7 @@ TypedResult readMultiAntennaOffset(C::mip_interface& device, assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length(), REPLY_MULTI_ANTENNA_OFFSET, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength(), REPLY_MULTI_ANTENNA_OFFSET, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4351,7 +4351,7 @@ TypedResult saveMultiAntennaOffset(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { @@ -4363,7 +4363,7 @@ TypedResult loadMultiAntennaOffset(C::mip_interface& device, assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultMultiAntennaOffset(C::mip_interface& device, uint8_t receiverId) { @@ -4375,7 +4375,7 @@ TypedResult defaultMultiAntennaOffset(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_MULTI_ANTENNA_OFFSET, buffer, (uint8_t)serializer.usedLength()); } void RelPosConfiguration::insert(Serializer& serializer) const { @@ -4441,7 +4441,7 @@ TypedResult writeRelPosConfiguration(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult readRelPosConfiguration(C::mip_interface& device, uint8_t* sourceOut, FilterReferenceFrame* referenceFrameSelectorOut, double* referenceCoordinatesOut) { @@ -4452,7 +4452,7 @@ TypedResult readRelPosConfiguration(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_REL_POS_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.usedLength(), REPLY_REL_POS_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4481,7 +4481,7 @@ TypedResult saveRelPosConfiguration(C::mip_interface& devic serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadRelPosConfiguration(C::mip_interface& device) { @@ -4491,7 +4491,7 @@ TypedResult loadRelPosConfiguration(C::mip_interface& devic serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultRelPosConfiguration(C::mip_interface& device) { @@ -4501,7 +4501,7 @@ TypedResult defaultRelPosConfiguration(C::mip_interface& de serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REL_POS_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } void RefPointLeverArm::insert(Serializer& serializer) const { @@ -4557,7 +4557,7 @@ TypedResult writeRefPointLeverArm(C::mip_interface& device, Re assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.usedLength()); } TypedResult readRefPointLeverArm(C::mip_interface& device, RefPointLeverArm::ReferencePointSelector* refPointSelOut, float* leverArmOffsetOut) { @@ -4568,7 +4568,7 @@ TypedResult readRefPointLeverArm(C::mip_interface& device, Ref assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length(), REPLY_REF_POINT_LEVER_ARM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.usedLength(), REPLY_REF_POINT_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4594,7 +4594,7 @@ TypedResult saveRefPointLeverArm(C::mip_interface& device) serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadRefPointLeverArm(C::mip_interface& device) { @@ -4604,7 +4604,7 @@ TypedResult loadRefPointLeverArm(C::mip_interface& device) serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultRefPointLeverArm(C::mip_interface& device) { @@ -4614,7 +4614,7 @@ TypedResult defaultRefPointLeverArm(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_REF_POINT_LEVER_ARM, buffer, (uint8_t)serializer.usedLength()); } void SpeedMeasurement::insert(Serializer& serializer) const { @@ -4654,7 +4654,7 @@ TypedResult speedMeasurement(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_MEASUREMENT, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_MEASUREMENT, buffer, (uint8_t)serializer.usedLength()); } void SpeedLeverArm::insert(Serializer& serializer) const { @@ -4710,7 +4710,7 @@ TypedResult writeSpeedLeverArm(C::mip_interface& device, uint8_t assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t source, float* leverArmOffsetOut) { @@ -4723,7 +4723,7 @@ TypedResult readSpeedLeverArm(C::mip_interface& device, uint8_t s assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length(), REPLY_SPEED_LEVER_ARM, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.usedLength(), REPLY_SPEED_LEVER_ARM, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4750,7 +4750,7 @@ TypedResult saveSpeedLeverArm(C::mip_interface& device, uint8_t s assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t source) { @@ -4762,7 +4762,7 @@ TypedResult loadSpeedLeverArm(C::mip_interface& device, uint8_t s assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_t source) { @@ -4774,7 +4774,7 @@ TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_ assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SPEED_LEVER_ARM, buffer, (uint8_t)serializer.usedLength()); } void WheeledVehicleConstraintControl::insert(Serializer& serializer) const { @@ -4818,7 +4818,7 @@ TypedResult writeWheeledVehicleConstraintContro assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readWheeledVehicleConstraintControl(C::mip_interface& device, uint8_t* enableOut) { @@ -4829,7 +4829,7 @@ TypedResult readWheeledVehicleConstraintControl assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_VEHICLE_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4851,7 +4851,7 @@ TypedResult saveWheeledVehicleConstraintControl serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadWheeledVehicleConstraintControl(C::mip_interface& device) { @@ -4861,7 +4861,7 @@ TypedResult loadWheeledVehicleConstraintControl serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultWheeledVehicleConstraintControl(C::mip_interface& device) { @@ -4871,7 +4871,7 @@ TypedResult defaultWheeledVehicleConstraintCont serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_VEHICLE_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void VerticalGyroConstraintControl::insert(Serializer& serializer) const { @@ -4915,7 +4915,7 @@ TypedResult writeVerticalGyroConstraintControl(C: assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readVerticalGyroConstraintControl(C::mip_interface& device, uint8_t* enableOut) { @@ -4926,7 +4926,7 @@ TypedResult readVerticalGyroConstraintControl(C:: assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_GYRO_CONSTRAINT_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -4948,7 +4948,7 @@ TypedResult saveVerticalGyroConstraintControl(C:: serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadVerticalGyroConstraintControl(C::mip_interface& device) { @@ -4958,7 +4958,7 @@ TypedResult loadVerticalGyroConstraintControl(C:: serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultVerticalGyroConstraintControl(C::mip_interface& device) { @@ -4968,7 +4968,7 @@ TypedResult defaultVerticalGyroConstraintControl( serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_GYRO_CONSTRAINT_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void GnssAntennaCalControl::insert(Serializer& serializer) const { @@ -5022,7 +5022,7 @@ TypedResult writeGnssAntennaCalControl(C::mip_interface& assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult readGnssAntennaCalControl(C::mip_interface& device, uint8_t* enableOut, float* maxOffsetOut) { @@ -5033,7 +5033,7 @@ TypedResult readGnssAntennaCalControl(C::mip_interface& d assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length(), REPLY_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.usedLength(), REPLY_ANTENNA_CALIBRATION_CONTROL, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -5058,7 +5058,7 @@ TypedResult saveGnssAntennaCalControl(C::mip_interface& d serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadGnssAntennaCalControl(C::mip_interface& device) { @@ -5068,7 +5068,7 @@ TypedResult loadGnssAntennaCalControl(C::mip_interface& d serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultGnssAntennaCalControl(C::mip_interface& device) { @@ -5078,7 +5078,7 @@ TypedResult defaultGnssAntennaCalControl(C::mip_interface serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_ANTENNA_CALIBRATION_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void SetInitialHeading::insert(Serializer& serializer) const { @@ -5100,7 +5100,7 @@ TypedResult setInitialHeading(C::mip_interface& device, float assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_HEADING, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SET_INITIAL_HEADING, buffer, (uint8_t)serializer.usedLength()); } } // namespace commands_filter diff --git a/src/cpp/mip/definitions/commands_gnss.cpp b/src/cpp/mip/definitions/commands_gnss.cpp index 078d367c1..0daf3cf77 100644 --- a/src/cpp/mip/definitions/commands_gnss.cpp +++ b/src/cpp/mip/definitions/commands_gnss.cpp @@ -175,7 +175,7 @@ TypedResult writeSignalConfiguration(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult readSignalConfiguration(C::mip_interface& device, uint8_t* gpsEnableOut, uint8_t* glonassEnableOut, uint8_t* galileoEnableOut, uint8_t* beidouEnableOut, uint8_t* reservedOut) { @@ -186,7 +186,7 @@ TypedResult readSignalConfiguration(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_SIGNAL_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.usedLength(), REPLY_SIGNAL_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -221,7 +221,7 @@ TypedResult saveSignalConfiguration(C::mip_interface& devic serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadSignalConfiguration(C::mip_interface& device) { @@ -231,7 +231,7 @@ TypedResult loadSignalConfiguration(C::mip_interface& devic serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultSignalConfiguration(C::mip_interface& device) { @@ -241,7 +241,7 @@ TypedResult defaultSignalConfiguration(C::mip_interface& de serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_SIGNAL_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } void RtkDongleConfiguration::insert(Serializer& serializer) const { @@ -301,7 +301,7 @@ TypedResult writeRtkDongleConfiguration(C::mip_interface assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult readRtkDongleConfiguration(C::mip_interface& device, uint8_t* enableOut, uint8_t* reservedOut) { @@ -312,7 +312,7 @@ TypedResult readRtkDongleConfiguration(C::mip_interface& assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length(), REPLY_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.usedLength(), REPLY_RTK_DONGLE_CONFIGURATION, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -338,7 +338,7 @@ TypedResult saveRtkDongleConfiguration(C::mip_interface& serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadRtkDongleConfiguration(C::mip_interface& device) { @@ -348,7 +348,7 @@ TypedResult loadRtkDongleConfiguration(C::mip_interface& serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultRtkDongleConfiguration(C::mip_interface& device) { @@ -358,7 +358,7 @@ TypedResult defaultRtkDongleConfiguration(C::mip_interfa serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_RTK_DONGLE_CONFIGURATION, buffer, (uint8_t)serializer.usedLength()); } } // namespace commands_gnss diff --git a/src/cpp/mip/definitions/commands_rtk.cpp b/src/cpp/mip/definitions/commands_rtk.cpp index e9f26bed0..72e2ee86e 100644 --- a/src/cpp/mip/definitions/commands_rtk.cpp +++ b/src/cpp/mip/definitions/commands_rtk.cpp @@ -227,7 +227,7 @@ TypedResult writeConnectedDeviceType(C::mip_interface& devi assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readConnectedDeviceType(C::mip_interface& device, ConnectedDeviceType::Type* devtypeOut) { @@ -238,7 +238,7 @@ TypedResult readConnectedDeviceType(C::mip_interface& devic assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length(), REPLY_CONNECTED_DEVICE_TYPE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.usedLength(), REPLY_CONNECTED_DEVICE_TYPE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -260,7 +260,7 @@ TypedResult saveConnectedDeviceType(C::mip_interface& devic serializer.insert(FunctionSelector::SAVE); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.usedLength()); } TypedResult loadConnectedDeviceType(C::mip_interface& device) { @@ -270,7 +270,7 @@ TypedResult loadConnectedDeviceType(C::mip_interface& devic serializer.insert(FunctionSelector::LOAD); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.usedLength()); } TypedResult defaultConnectedDeviceType(C::mip_interface& device) { @@ -280,7 +280,7 @@ TypedResult defaultConnectedDeviceType(C::mip_interface& de serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONNECTED_DEVICE_TYPE, buffer, (uint8_t)serializer.usedLength()); } void GetActCode::insert(Serializer& serializer) const { @@ -469,7 +469,7 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SERVICE_STATUS, buffer, (uint8_t)serializer.length(), REPLY_SERVICE_STATUS, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_SERVICE_STATUS, buffer, (uint8_t)serializer.usedLength(), REPLY_SERVICE_STATUS, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -512,7 +512,7 @@ TypedResult prodEraseStorage(C::mip_interface& device, MediaSe assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PROD_ERASE_STORAGE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_PROD_ERASE_STORAGE, buffer, (uint8_t)serializer.usedLength()); } void LedControl::insert(Serializer& serializer) const { @@ -560,7 +560,7 @@ TypedResult ledControl(C::mip_interface& device, const uint8_t* prim assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_CONTROL, buffer, (uint8_t)serializer.usedLength()); } void ModemHardReset::insert(Serializer& serializer) const { diff --git a/src/cpp/mip/definitions/commands_system.cpp b/src/cpp/mip/definitions/commands_system.cpp index d5194ddb0..5746e54a3 100644 --- a/src/cpp/mip/definitions/commands_system.cpp +++ b/src/cpp/mip/definitions/commands_system.cpp @@ -62,7 +62,7 @@ TypedResult writeCommMode(C::mip_interface& device, uint8_t mode) assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.usedLength()); } TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) { @@ -73,7 +73,7 @@ TypedResult readCommMode(C::mip_interface& device, uint8_t* modeOut) assert(serializer.isOk()); uint8_t responseLength = sizeof(buffer); - TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.length(), REPLY_COM_MODE, buffer, &responseLength); + TypedResult result = mip_interface_run_command_with_response(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.usedLength(), REPLY_COM_MODE, buffer, &responseLength); if( result == MIP_ACK_OK ) { @@ -95,7 +95,7 @@ TypedResult defaultCommMode(C::mip_interface& device) serializer.insert(FunctionSelector::RESET); assert(serializer.isOk()); - return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.length()); + return mip_interface_run_command(&device, DESCRIPTOR_SET, CMD_COM_MODE, buffer, (uint8_t)serializer.usedLength()); } } // namespace commands_system diff --git a/src/cpp/mip/mip_packet.hpp b/src/cpp/mip/mip_packet.hpp index 62972fec8..3f8297fdf 100644 --- a/src/cpp/mip/mip_packet.hpp +++ b/src/cpp/mip/mip_packet.hpp @@ -95,7 +95,7 @@ class PacketView : public C::mip_packet_view bool ok = isOk(); if(ok) - ok &= C::mip_packet_realloc_last_field(&m_packet, basePointer(), (uint8_t)length()) >= 0; + ok &= C::mip_packet_realloc_last_field(&m_packet, basePointer(), (uint8_t)usedLength()) >= 0; if(!ok) C::mip_packet_cancel_last_field(&m_packet, basePointer()); From 2f10ff2a5573d986a5ef96b5ef1bbfa1146cc04f Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 3 Sep 2024 15:39:26 -0400 Subject: [PATCH 096/147] Add missing #include . --- src/c/microstrain/common/embedded_time.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/c/microstrain/common/embedded_time.h b/src/c/microstrain/common/embedded_time.h index b7c2d64c6..54c91adb8 100644 --- a/src/c/microstrain/common/embedded_time.h +++ b/src/c/microstrain/common/embedded_time.h @@ -7,6 +7,8 @@ #ifdef __cplusplus namespace microstrain { namespace C { +#else +#include #endif ///@brief Type used for packet timestamps and timeouts. From 9ede2d9c3258dd156457c1a8348cb6dcd32cb364 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Thu, 5 Sep 2024 09:14:26 -0400 Subject: [PATCH 097/147] Updated Jenkinsfile Added timeouts and Mac builders Uncommented ARM builders Fixed MSVC toolset version 2019 (v142) --> 2022 (v143) --- Jenkinsfile | 124 +++++++++++++++++++++++++++++++++++++++++----------- 1 file changed, 99 insertions(+), 25 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 0358a2320..67a6ab9a6 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -25,21 +25,29 @@ def checkoutRepo() { pipeline { agent none + options { + // Set a timeout for the whole pipeline. The timer starts when the project is queued + timeout(time: 1, unit: 'HOURS') + } stages { stage('Build') { - // Run the windows and linux builds in parallel + // Run all the builds in parallel parallel { stage('Windows x86') { agent { label 'windows10' } - options { skipDefaultCheckout() } + options { + skipDefaultCheckout() + timeout(time: 5, activity: true, unit: 'MINUTES') + } steps { checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) powershell """ mkdir build_Win32 cd build_Win32 cmake .. ` -A "Win32" ` - -T "v142" ` + -T "v143" ` -DBUILD_DOCUMENTATION=ON ` -DBUILD_PACKAGE=ON if(\$?) { cmake --build . } @@ -51,15 +59,19 @@ pipeline { } stage('Windows x64') { agent { label 'windows10' } - options { skipDefaultCheckout() } + options { + skipDefaultCheckout() + timeout(time: 5, activity: true, unit: 'MINUTES') + } steps { checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) powershell """ mkdir build_x64 cd build_x64 cmake .. ` -A "x64" ` - -T "v142" ` + -T "v143" ` -DBUILD_PACKAGE=ON if(\$?) { cmake --build . } if(\$?) { cmake --build . --target package } @@ -69,40 +81,102 @@ pipeline { } stage('Ubuntu amd64') { agent { label 'linux-amd64' } - options { skipDefaultCheckout() } + options { + skipDefaultCheckout() + timeout(time: 5, activity: true, unit: 'MINUTES') + } steps { checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) sh "./.devcontainer/docker_build.sh --os ubuntu --arch amd64" archiveArtifacts artifacts: 'build_ubuntu_amd64/mipsdk_*' } } stage('Centos amd64') { agent { label 'linux-amd64' } - options { skipDefaultCheckout() } + options { + skipDefaultCheckout() + timeout(time: 5, activity: true, unit: 'MINUTES') + } steps { checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) sh "./.devcontainer/docker_build.sh --os centos --arch amd64" archiveArtifacts artifacts: 'build_centos_amd64/mipsdk_*' } } - // stage('Ubuntu arm64') { - // agent { label 'linux-arm64' } - // options { skipDefaultCheckout() } - // steps { - // checkoutRepo() - // sh "./.devcontainer/docker_build.sh --os ubuntu --arch arm64v8" - // archiveArtifacts artifacts: 'build_ubuntu_arm64v8/mipsdk_*' - // } - // } - // stage('Ubuntu arm32') { - // agent { label 'linux-arm64' } - // options { skipDefaultCheckout() } - // steps { - // checkoutRepo() - // sh "./.devcontainer/docker_build.sh --os ubuntu --arch arm32v7" - // archiveArtifacts artifacts: 'build_ubuntu_arm32v7/mipsdk_*' - // } - // } + stage('Ubuntu arm64') { + agent { label 'linux-arm64' } + options { + skipDefaultCheckout() + timeout(time: 5, activity: true, unit: 'MINUTES') + } + steps { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + sh "./.devcontainer/docker_build.sh --os ubuntu --arch arm64v8" + archiveArtifacts artifacts: 'build_ubuntu_arm64v8/mipsdk_*' + } + } + stage('Ubuntu arm32') { + agent { label 'linux-arm64' } + options { + skipDefaultCheckout() + timeout(time: 5, activity: true, unit: 'MINUTES') + } + steps { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + sh "./.devcontainer/docker_build.sh --os ubuntu --arch arm32v7" + archiveArtifacts artifacts: 'build_ubuntu_arm32v7/mipsdk_*' + } + } + stage("Mac M2") { + agent { label 'mac-m2' } + options { + skipDefaultCheckout() + timeout(time: 5, activity: true, unit: 'MINUTES') + } + steps { + script { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + sh ''' + mkdir build_mac_arm64 + cd build_mac_arm64 + cmake .. \ + -DBUILD_PACKAGE=ON \ + -DCMAKE_BUILD_TYPE=RELEASE \ + cmake --build . -j $(sysctl -n hw.ncpu) + cmake --build . --target package + ''' + archiveArtifacts artifacts: 'build_mac_arm64/mipsdk_*' + } + } + } + stage("Mac Intel") { + agent { label 'mac-intel' } + options { + skipDefaultCheckout() + timeout(time: 5, activity: true, unit: 'MINUTES') + } + steps { + script { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + sh ''' + mkdir build_mac_intel + cd build_mac_intel + cmake .. \ + -DBUILD_PACKAGE=ON \ + -DCMAKE_BUILD_TYPE=RELEASE \ + cmake --build . -j $(sysctl -n hw.ncpu) + cmake --build . --target package + ''' + archiveArtifacts artifacts: 'build_mac_intel/mipsdk_*' + } + } + } } } } From 33e368a84c68faa18ecf52983208ea325931abbe Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Thu, 5 Sep 2024 09:28:40 -0400 Subject: [PATCH 098/147] Fixed Jenkinsfile copy/paste error Added utility function for getting the branch name --- Jenkinsfile | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 67a6ab9a6..a298751b2 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -1,3 +1,12 @@ +// Utility function for getting the real branch name even in a pull request +def branchName() { + if (env.CHANGE_BRANCH) { + return env.CHANGE_BRANCH + } else { + return env.BRANCH_NAME + } +} + // Utility function for checking out the repo since we want all the branches and tags def checkoutRepo() { // Clean the workspace @@ -5,11 +14,7 @@ def checkoutRepo() { // Handles both PRs and branches script { - if (env.CHANGE_BRANCH) { - BRANCH_NAME_REAL = env.CHANGE_BRANCH - } else { - BRANCH_NAME_REAL = env.BRANCH_NAME - } + BRANCH_NAME_REAL = branchName(); } // Checkout the code from github @@ -146,7 +151,7 @@ pipeline { cd build_mac_arm64 cmake .. \ -DBUILD_PACKAGE=ON \ - -DCMAKE_BUILD_TYPE=RELEASE \ + -DCMAKE_BUILD_TYPE=RELEASE cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' @@ -169,7 +174,7 @@ pipeline { cd build_mac_intel cmake .. \ -DBUILD_PACKAGE=ON \ - -DCMAKE_BUILD_TYPE=RELEASE \ + -DCMAKE_BUILD_TYPE=RELEASE cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' From b8ceee463ada5a87c897ec298bf2a8c6c6208a4e Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Thu, 5 Sep 2024 09:32:40 -0400 Subject: [PATCH 099/147] Fixed Jenkinsfile script block error --- Jenkinsfile | 100 +++++++++++++++++++++++++++++----------------------- 1 file changed, 56 insertions(+), 44 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index a298751b2..2d3dbc5a3 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -45,21 +45,23 @@ pipeline { timeout(time: 5, activity: true, unit: 'MINUTES') } steps { - checkoutRepo() - env.setProperty('BRANCH_NAME', branchName()) - powershell """ - mkdir build_Win32 - cd build_Win32 - cmake .. ` - -A "Win32" ` - -T "v143" ` - -DBUILD_DOCUMENTATION=ON ` - -DBUILD_PACKAGE=ON - if(\$?) { cmake --build . } - if(\$?) { cmake --build . --target package } - if(\$?) { cmake --build . --target package_docs } - """ - archiveArtifacts artifacts: 'build_Win32/mipsdk_*' + script { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + powershell """ + mkdir build_Win32 + cd build_Win32 + cmake .. ` + -A "Win32" ` + -T "v143" ` + -DBUILD_DOCUMENTATION=ON ` + -DBUILD_PACKAGE=ON + if(\$?) { cmake --build . } + if(\$?) { cmake --build . --target package } + if(\$?) { cmake --build . --target package_docs } + """ + archiveArtifacts artifacts: 'build_Win32/mipsdk_*' + } } } stage('Windows x64') { @@ -69,19 +71,21 @@ pipeline { timeout(time: 5, activity: true, unit: 'MINUTES') } steps { - checkoutRepo() - env.setProperty('BRANCH_NAME', branchName()) - powershell """ - mkdir build_x64 - cd build_x64 - cmake .. ` - -A "x64" ` - -T "v143" ` - -DBUILD_PACKAGE=ON - if(\$?) { cmake --build . } - if(\$?) { cmake --build . --target package } - """ - archiveArtifacts artifacts: 'build_x64/mipsdk_*' + script { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + powershell """ + mkdir build_x64 + cd build_x64 + cmake .. ` + -A "x64" ` + -T "v143" ` + -DBUILD_PACKAGE=ON + if(\$?) { cmake --build . } + if(\$?) { cmake --build . --target package } + """ + archiveArtifacts artifacts: 'build_x64/mipsdk_*' + } } } stage('Ubuntu amd64') { @@ -91,10 +95,12 @@ pipeline { timeout(time: 5, activity: true, unit: 'MINUTES') } steps { - checkoutRepo() - env.setProperty('BRANCH_NAME', branchName()) - sh "./.devcontainer/docker_build.sh --os ubuntu --arch amd64" - archiveArtifacts artifacts: 'build_ubuntu_amd64/mipsdk_*' + script { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + sh "./.devcontainer/docker_build.sh --os ubuntu --arch amd64" + archiveArtifacts artifacts: 'build_ubuntu_amd64/mipsdk_*' + } } } stage('Centos amd64') { @@ -104,10 +110,12 @@ pipeline { timeout(time: 5, activity: true, unit: 'MINUTES') } steps { - checkoutRepo() - env.setProperty('BRANCH_NAME', branchName()) - sh "./.devcontainer/docker_build.sh --os centos --arch amd64" - archiveArtifacts artifacts: 'build_centos_amd64/mipsdk_*' + script { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + sh "./.devcontainer/docker_build.sh --os centos --arch amd64" + archiveArtifacts artifacts: 'build_centos_amd64/mipsdk_*' + } } } stage('Ubuntu arm64') { @@ -117,10 +125,12 @@ pipeline { timeout(time: 5, activity: true, unit: 'MINUTES') } steps { - checkoutRepo() - env.setProperty('BRANCH_NAME', branchName()) - sh "./.devcontainer/docker_build.sh --os ubuntu --arch arm64v8" - archiveArtifacts artifacts: 'build_ubuntu_arm64v8/mipsdk_*' + script { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + sh "./.devcontainer/docker_build.sh --os ubuntu --arch arm64v8" + archiveArtifacts artifacts: 'build_ubuntu_arm64v8/mipsdk_*' + } } } stage('Ubuntu arm32') { @@ -130,10 +140,12 @@ pipeline { timeout(time: 5, activity: true, unit: 'MINUTES') } steps { - checkoutRepo() - env.setProperty('BRANCH_NAME', branchName()) - sh "./.devcontainer/docker_build.sh --os ubuntu --arch arm32v7" - archiveArtifacts artifacts: 'build_ubuntu_arm32v7/mipsdk_*' + script { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + sh "./.devcontainer/docker_build.sh --os ubuntu --arch arm32v7" + archiveArtifacts artifacts: 'build_ubuntu_arm32v7/mipsdk_*' + } } } stage("Mac M2") { From 16b766112ebae9e07302135c5f902a76d486272c Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Thu, 5 Sep 2024 13:01:43 -0400 Subject: [PATCH 100/147] Working on CPack/Install Removed private MicroStrain interface library in favor of variable for setting compile options/definitions Created CMake macro for the install step of the libraries --- CMakeLists.txt | 127 +++++++++++------- cmake/microstrain_utilities.cmake | 50 +++++++ examples/CMakeLists.txt | 10 +- src/c/microstrain/common/CMakeLists.txt | 16 ++- .../connections/serial/CMakeLists.txt | 18 ++- .../connections/tcp/CMakeLists.txt | 18 ++- src/c/mip/CMakeLists.txt | 15 ++- src/cpp/microstrain/common/CMakeLists.txt | 6 + .../connections/recording/CMakeLists.txt | 14 +- .../connections/serial/CMakeLists.txt | 6 + .../connections/tcp/CMakeLists.txt | 6 + src/cpp/microstrain/extras/CMakeLists.txt | 18 ++- src/cpp/mip/CMakeLists.txt | 6 + src/cpp/mip/extras/CMakeLists.txt | 18 ++- src/cpp/mip/metadata/CMakeLists.txt | 18 ++- 15 files changed, 262 insertions(+), 84 deletions(-) create mode 100644 cmake/microstrain_utilities.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index 7f71f1e55..c83a4a346 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,6 +16,8 @@ set(SRC_DIR "${CMAKE_CURRENT_LIST_DIR}/src") set(MIP_CMAKE_DIR "${CMAKE_CURRENT_LIST_DIR}/cmake") set(MIP_DIR "${SRC_DIR}/mip") +list(APPEND CMAKE_MODULE_PATH ${MIP_CMAKE_DIR}) + # # Build options # @@ -107,32 +109,30 @@ configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) # # Common preprocessor definitions # -set(MICROSTRAIN_PRIVATE_LIBRARY "microstrain_private") -mark_as_advanced(MICROSTRAIN_PRIVATE_LIBRARY) -add_library(${MICROSTRAIN_PRIVATE_LIBRARY} INTERFACE) -# Disable windows defined min/max -# Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) if(WIN32) - target_compile_definitions(${MICROSTRAIN_PRIVATE_LIBRARY} - INTERFACE + if(MSVC) + set(MICROSTRAIN_PRIVATE_COMPILE_OPTIONS + "/external:anglebrackets" # Treat angle brackets as system includes + "/external:W0" # No warnings from system includes + "/W4" # Enable warnings + "/Zc:__cplusplus" # Enable updated __cplusplus value + ) + endif() + + # Disable windows defined min/max + # Set Windows header version (0x0501 is _WIN32_WINNT_WINXP, required for TCP) + set(MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS "NOMINMAX=1" "_WIN32_WINNT=_WIN32_WINNT_WINXP" ) -endif() - -if(MSVC) - target_compile_options(${MICROSTRAIN_PRIVATE_LIBRARY} INTERFACE - "/external:anglebrackets" # Treat angle brackets as system includes - "/external:W0" # No warnings from system includes - "/W4" # Enable warnings - "/Zc:__cplusplus" # Enable updated __cplusplus value - ) else() - target_compile_options(${MICROSTRAIN_PRIVATE_LIBRARY} INTERFACE - "-Wall" # Extra warnings - "-Wextra" + set(MICROSTRAIN_PRIVATE_COMPILE_OPTIONS + "-Wall" # Enable warnings + "-Wextra" # Enable extra warnings ) + + set(MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS "") endif() # Create "catch-all" interface libraries @@ -152,15 +152,15 @@ cmake_policy(SET CMP0079 NEW) # Add all the C files (required even for C++ API) set(SRC_C_DIR "${CMAKE_CURRENT_LIST_DIR}/src/c") -add_subdirectory(src/c/microstrain) -add_subdirectory(src/c/mip) +add_subdirectory(${SRC_C_DIR}/microstrain) +add_subdirectory(${SRC_C_DIR}/mip) # Add all the C++ files (if C++ enabled) if(MICROSTRAIN_ENABLE_CPP) set(SRC_CPP_DIR "${CMAKE_CURRENT_LIST_DIR}/src/cpp") - add_subdirectory(src/cpp/microstrain) - add_subdirectory(src/cpp/mip) + add_subdirectory(${SRC_CPP_DIR}/microstrain) + add_subdirectory(${SRC_CPP_DIR}/mip) #target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_CPP_C_NAMESPACE=${MICROSTRAIN_ENABLE_CPP_C_NAMESPACE}") endif() @@ -342,46 +342,69 @@ endif() # If we were asked to package, find the generators we can use if(BUILD_PACKAGE) + # Get a list of libraries to package + get_target_property(MICROSTRAIN_PACKAGES ${MICROSTRAIN_LIBRARIES} INTERFACE_LINK_LIBRARIES) + get_target_property(MIP_PACKAGES ${MIP_LIBRARIES} INTERFACE_LINK_LIBRARIES) + + # Filter out directory IDs from (INTERFACE_)LINK_LIBRARIES as well as the MicroStrain libraries from MIP + # https://cmake.org/cmake/help/latest/prop_tgt/LINK_LIBRARIES.html + set(REGEX_MATCH "(::@*)") + list(FILTER MICROSTRAIN_PACKAGES EXCLUDE REGEX ${REGEX_MATCH}) + string(APPEND REGEX_MATCH "|(${MICROSTRAIN_LIBRARIES})") + list(FILTER MIP_PACKAGES EXCLUDE REGEX ${REGEX_MATCH}) + set(FOUND_CPACK_GENERATORS "") - set(7Z_ROOT "" CACHE STRING "Location of the 7zip executable") - set(DPKG_ROOT "" CACHE STRING "Location of the dpkg executable") - set(RPMBUILD_ROOT "" CACHE STRING "Location of the rpmbuild executable") - find_program(7Z_EXECUTABLE - NAMES 7z - PATHS ${7Z_ROOT} - DOC "7zip command line client" - ) - if(NOT ${7Z_EXECUTABLE} STREQUAL "7Z_EXECUTABLE-NOTFOUND") - list(APPEND FOUND_CPACK_GENERATORS "7Z") - endif() - find_program(DPKG_EXECUTABLE - NAMES dpkg - PATHS ${DPKG_ROOT} - DOC "dpkg command line client" - ) - if(NOT ${DPKG_EXECUTABLE} STREQUAL "DPKG_EXECUTABLE-NOTFOUND") - list(APPEND FOUND_CPACK_GENERATORS "DEB") + + if(UNIX AND NOT APPLE) + set(DPKG_ROOT "" CACHE STRING "Location of the dpkg executable") + set(RPMBUILD_ROOT "" CACHE STRING "Location of the rpmbuild executable") + + find_program(DPKG_EXECUTABLE + NAMES dpkg + PATHS ${DPKG_ROOT} + DOC "dpkg command line client" + ) + if(NOT ${DPKG_EXECUTABLE} STREQUAL "DPKG_EXECUTABLE-NOTFOUND") + list(APPEND FOUND_CPACK_GENERATORS "DEB") + endif() + + find_program(RPMBUILD_EXECUTABLE + NAMES rpmbuild + PATHS ${RPMBUILD_ROOT} + DOC "rpmbuild command line client" + ) + if(NOT ${RPMBUILD_EXECUTABLE} STREQUAL "RPMBUILD_EXECUTABLE-NOTFOUND") + list(APPEND FOUND_CPACK_GENERATORS "RPM") + endif() endif() - find_program(RPMBUILD_EXECUTABLE - NAMES rpmbuild - PATHS ${RPMBUILD_ROOT} - DOC "rpmbuild command line client" - ) - if(NOT ${RPMBUILD_EXECUTABLE} STREQUAL "RPMBUILD_EXECUTABLE-NOTFOUND") - list(APPEND FOUND_CPACK_GENERATORS "RPM") + + # Windows always has zip installed, so only look for it on linux and mac + if(WIN32) + list(APPEND FOUND_CPACK_GENERATORS "ZIP") + else() + set(ZIP_ROOT "" CACHE STRING "Location of the zip executable") + find_program(ZIP_EXECUTABLE + NAMES zip + PATHS ${ZIP_ROOT} + DOC "zip command line client" + ) + if(NOT ${ZIP_EXECUTABLE} STREQUAL "ZIP_EXECUTABLE-NOTFOUND") + list(APPEND FOUND_CPACK_GENERATORS "ZIP") + endif() endif() + if(NOT FOUND_CPACK_GENERATORS) message(FATAL_ERROR "Unable to find a suitable package generator, but we were requested to build a package.") + else() + message(STATUS "Packaging using the following generators: ${FOUND_CPACK_GENERATORS}") endif() -endif() -# If we were asked to build packages, include CPack and set up packaging -if(BUILD_PACKAGE) + # Packaging # NOTE: CPack requires all these variables to be set before importing the module. Do not move them after the include(CPack) line set(CPACK_GENERATOR "${FOUND_CPACK_GENERATORS}") set(CPACK_PACKAGE_VENDOR "MicroStrain by HBK") set(CPACK_PACKAGE_CONTACT "MicroStrain Support ") - set(CPACK_COMPONENTS_ALL ${MIP_LIBRARY}) + set(CPACK_COMPONENTS_ALL ${MIP_LIBRARY} ${MIP_LIBRARIES}) set(CPACK_PACKAGE_VERSION ${MIP_GIT_VERSION_CLEAN}) diff --git a/cmake/microstrain_utilities.cmake b/cmake/microstrain_utilities.cmake new file mode 100644 index 000000000..ad6142f87 --- /dev/null +++ b/cmake/microstrain_utilities.cmake @@ -0,0 +1,50 @@ +macro(microstrain_setup_install_headers LIBRARY) +# message(WARNING "Lib headers: ${LIBRARY}") + + # Only install headers that we build the source files for + get_target_property(ALL_HEADERS ${LIBRARY} SOURCES) + list(FILTER ALL_HEADERS INCLUDE REGEX "^.*\.(h|hpp)$") +# message(WARNING "${LIBRARY} Headers: ${ALL_HEADERS}") +# foreach(HEADER ${ALL_HEADERS}) +# string(REPLACE "${CMAKE_CURRENT_LIST_DIR}/" "" HEADER_RELATIVE "${HEADER}") +# set(HEADER_DESTINATION_FULL "${CMAKE_INSTALL_INCLUDEDIR}/${HEADER_RELATIVE}") +# get_filename_component(HEADER_DESTINATION "${HEADER_DESTINATION_FULL}" DIRECTORY) +# install( +# FILES "${HEADER}" +# DESTINATION "${HEADER_DESTINATION}" +# COMPONENT ${LIBRARY} +# ) +# endforeach() +endmacro() + +macro(microstrain_setup_library_install LIBRARY EXPORT_TARGET) +# message(WARNING "Lib install: ${LIBRARY}") + + microstrain_setup_install_headers(${LIBRARY}) + + install( + TARGETS ${LIBRARY} + EXPORT mip-targets + ARCHIVE + COMPONENT ${LIBRARY} + DESTINATION ${CMAKE_INSTALL_LIBDIR}/ + ) +# message(WARNING "${LIBRARY} install dir: ${CMAKE_INSTALL_LIBDIR}") + + include(CMakePackageConfigHelpers) + + set(CONFIG_EXPORT_DIR "${CMAKE_INSTALL_DATADIR}/cmake/${LIBRARY}") +# message(WARNING "${LIBRARY} config dir: ${CONFIG_EXPORT_DIR}") + +# install( +# EXPORT mip-targets +# COMPONENT ${LIBRARY} +# DESTINATION ${CONFIG_EXPORT_DIR} +# ) + + install( + FILES "${CMAKE_BINARY_DIR}/${LIBRARY}-config.cmake" "${CMAKE_BINARY_DIR}/${LIBRARY}-config-version.cmake" + DESTINATION ${CONFIG_EXPORT_DIR} + COMPONENT ${LIBRARY} + ) +endmacro() diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 5f46c2f0d..5b50212cd 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -31,9 +31,15 @@ endif() set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) -target_compile_definitions(${MIP_EXAMPLE_UTILS_LIBRARY} PUBLIC ${MIP_EXAMPLE_DEFS}) +target_compile_definitions(${MIP_EXAMPLE_UTILS_LIBRARY} + PUBLIC ${MIP_EXAMPLE_DEFS} + PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS} +) + +target_compile_options(${MICROSTRAIN_SERIAL_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) + #target_include_directories(${MIP_EXAMPLE_UTILS_LIBRARY} PRIVATE ${SRC_DIR}) -target_link_libraries(${MIP_EXAMPLE_UTILS_LIBRARY} PUBLIC ${MIP_LIBRARY} ${EXAMPLE_LIBS} ${MICROSTRAIN_PRIVATE_LIBRARY}) +target_link_libraries(${MIP_EXAMPLE_UTILS_LIBRARY} PUBLIC ${MIP_LIBRARY} ${EXAMPLE_LIBS}) list(APPEND EXAMPLE_LIBS ${MIP_EXAMPLE_UTILS_LIBRARY}) diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index 49aba92c5..d5b1b7974 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -11,9 +11,15 @@ add_library(${MICROSTRAIN_COMMON_LIBRARY} "serialization.c" "serialization.h" ) -target_link_libraries(${MICROSTRAIN_COMMON_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY}) + target_compile_features(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC c_std_11) -target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}") + +target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} + PUBLIC "MICROSTRAIN_TIMESTAMP_TYPE=${MICROSTRAIN_TIMESTAMP_TYPE}" + PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS} +) + +target_compile_options(${MICROSTRAIN_COMMON_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) # Logging is a little weird since we need to install the header no matter what if(MICROSTRAIN_ENABLE_LOGGING) @@ -28,3 +34,9 @@ endif() target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${SRC_C_DIR}) target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_COMMON_LIBRARY}) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_library_install(${MICROSTRAIN_COMMON_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) diff --git a/src/c/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt index 1675a191c..957fa09c3 100644 --- a/src/c/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -7,10 +7,20 @@ add_library(${MICROSTRAIN_SERIAL_LIBRARY} ) target_compile_features(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC c_std_11) -target_link_libraries(${MICROSTRAIN_SERIAL_LIBRARY} - PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} - PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} + +target_link_libraries(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC ${MICROSTRAIN_COMMON_LIBRARY}) + +target_compile_definitions(${MICROSTRAIN_SERIAL_LIBRARY} + PUBLIC "MICROSTRAIN_ENABLE_SERIAL=1" + PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS} ) -target_compile_definitions(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_SERIAL=1") + +target_compile_options(${MICROSTRAIN_SERIAL_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_SERIAL_LIBRARY}) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_library_install(${MICROSTRAIN_SERIAL_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) diff --git a/src/c/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt index 75725e392..dd068e6f6 100644 --- a/src/c/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -7,14 +7,24 @@ add_library(${MICROSTRAIN_SOCKET_LIBRARY} ) target_compile_features(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC c_std_11) -target_link_libraries(${MICROSTRAIN_SOCKET_LIBRARY} - PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} - PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} + +target_link_libraries(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC ${MICROSTRAIN_COMMON_LIBRARY}) + +target_compile_definitions(${MICROSTRAIN_SOCKET_LIBRARY} + PUBLIC "MICROSTRAIN_ENABLE_TCP=1" + PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS} ) -target_compile_definitions(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_TCP=1") + +target_compile_options(${MICROSTRAIN_SOCKET_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) if(WIN32) target_link_libraries(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC "ws2_32") endif() target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_SOCKET_LIBRARY}) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_library_install(${MICROSTRAIN_SOCKET_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index a2ebf62d7..6ccc52a9b 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -39,15 +39,16 @@ add_library(${MIP_LIBRARY} ) target_compile_features(${MIP_LIBRARY} PUBLIC c_std_11) -target_link_libraries(${MIP_LIBRARY} - PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} - PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} -) +target_link_libraries(${MIP_LIBRARY} PUBLIC ${MICROSTRAIN_COMMON_LIBRARY}) if(${MIP_ENABLE_DIAGNOSTICS}) target_compile_definitions(${MIP_LIBRARY} PUBLIC "MIP_ENABLE_DIAGNOSTICS=1") endif() +target_compile_definitions(${MIP_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS}) + +target_compile_options(${MIP_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) + # # Mip definition files @@ -85,3 +86,9 @@ endif() target_sources(${MIP_LIBRARY} PRIVATE ${MIP_DEF_SOURCES}) target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_LIBRARY}) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_library_install(${MIP_LIBRARY} ${MIP_LIBRARY}) diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index f25bf4d11..2a9af847b 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -11,3 +11,9 @@ target_sources(${MICROSTRAIN_COMMON_LIBRARY} PRIVATE target_compile_features(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC cxx_std_11) target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${SRC_CPP_DIR}) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_install_headers(${MICROSTRAIN_COMMON_LIBRARY}) diff --git a/src/cpp/microstrain/connections/recording/CMakeLists.txt b/src/cpp/microstrain/connections/recording/CMakeLists.txt index 6560170f3..cc9900131 100644 --- a/src/cpp/microstrain/connections/recording/CMakeLists.txt +++ b/src/cpp/microstrain/connections/recording/CMakeLists.txt @@ -8,9 +8,15 @@ add_library(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} ) target_compile_features(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} PUBLIC cxx_std_11) -target_link_libraries(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} - PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} - PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} -) + +target_link_libraries(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} PUBLIC ${MICROSTRAIN_COMMON_LIBRARY}) + +target_compile_options(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY}) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_library_install(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) diff --git a/src/cpp/microstrain/connections/serial/CMakeLists.txt b/src/cpp/microstrain/connections/serial/CMakeLists.txt index 007c012f0..efac71755 100644 --- a/src/cpp/microstrain/connections/serial/CMakeLists.txt +++ b/src/cpp/microstrain/connections/serial/CMakeLists.txt @@ -6,3 +6,9 @@ target_sources(${MICROSTRAIN_SERIAL_LIBRARY} PRIVATE ) target_compile_features(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC cxx_std_11) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_install_headers(${MICROSTRAIN_SERIAL_LIBRARY}) diff --git a/src/cpp/microstrain/connections/tcp/CMakeLists.txt b/src/cpp/microstrain/connections/tcp/CMakeLists.txt index de092a4c4..4dff797a9 100644 --- a/src/cpp/microstrain/connections/tcp/CMakeLists.txt +++ b/src/cpp/microstrain/connections/tcp/CMakeLists.txt @@ -6,3 +6,9 @@ target_sources(${MICROSTRAIN_SOCKET_LIBRARY} PRIVATE ) target_compile_features(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC cxx_std_11) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_install_headers(${MICROSTRAIN_SOCKET_LIBRARY}) diff --git a/src/cpp/microstrain/extras/CMakeLists.txt b/src/cpp/microstrain/extras/CMakeLists.txt index c403895b0..daf38d654 100644 --- a/src/cpp/microstrain/extras/CMakeLists.txt +++ b/src/cpp/microstrain/extras/CMakeLists.txt @@ -9,10 +9,20 @@ set(SOURCES add_library(${MICROSTRAIN_EXTRAS_LIBRARY} ${SOURCES}) target_compile_features(${MICROSTRAIN_EXTRAS_LIBRARY} PUBLIC cxx_std_11) -target_link_libraries(${MICROSTRAIN_EXTRAS_LIBRARY} - PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} - PUBLIC ${MICROSTRAIN_COMMON_LIBRARY} + +target_link_libraries(${MICROSTRAIN_EXTRAS_LIBRARY} PUBLIC ${MICROSTRAIN_COMMON_LIBRARY}) + +target_compile_definitions(${MICROSTRAIN_EXTRAS_LIBRARY} + PUBLIC "MICROSTRAIN_ENABLE_EXTRAS=1" + PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS} ) -target_compile_definitions(${MICROSTRAIN_EXTRAS_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_EXTRAS=1") + +target_compile_options(${MICROSTRAIN_EXTRAS_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_EXTRAS_LIBRARY}) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_library_install(${MICROSTRAIN_EXTRAS_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index e353aa23a..2e33108a2 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -40,3 +40,9 @@ endif() if(MIP_ENABLE_EXTRAS) add_subdirectory(extras) endif() + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_install_headers(${MIP_LIBRARY}) diff --git a/src/cpp/mip/extras/CMakeLists.txt b/src/cpp/mip/extras/CMakeLists.txt index e64ac5663..71fd144ed 100644 --- a/src/cpp/mip/extras/CMakeLists.txt +++ b/src/cpp/mip/extras/CMakeLists.txt @@ -9,10 +9,20 @@ add_library(${MIP_EXTRAS_LIBRARY} ) target_compile_features(${MIP_EXTRAS_LIBRARY} PUBLIC cxx_std_11) -target_link_libraries(${MIP_EXTRAS_LIBRARY} - PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} - PUBLIC ${MIP_LIBRARY} ${MICROSTRAIN_EXTRAS_LIBRARY} + +target_link_libraries(${MIP_EXTRAS_LIBRARY} PUBLIC ${MIP_LIBRARY} ${MICROSTRAIN_EXTRAS_LIBRARY}) + +target_compile_definitions(${MIP_EXTRAS_LIBRARY} + PUBLIC "MIP_ENABLE_EXTRAS=1" + PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS} ) -target_compile_definitions(${MIP_EXTRAS_LIBRARY} PUBLIC "MIP_ENABLE_EXTRAS=1") + +target_compile_options(${MIP_EXTRAS_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_EXTRAS_LIBRARY}) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_library_install(${MIP_EXTRAS_LIBRARY} ${MIP_LIBRARY}) diff --git a/src/cpp/mip/metadata/CMakeLists.txt b/src/cpp/mip/metadata/CMakeLists.txt index eb993e53b..f2b2c0b7d 100644 --- a/src/cpp/mip/metadata/CMakeLists.txt +++ b/src/cpp/mip/metadata/CMakeLists.txt @@ -24,10 +24,20 @@ add_library(${MIP_METADATA_LIBRARY} ) target_compile_features(${MIP_METADATA_LIBRARY} PUBLIC cxx_std_20) -target_link_libraries(${MIP_METADATA_LIBRARY} - PRIVATE ${MICROSTRAIN_PRIVATE_LIBRARY} - PUBLIC ${MIP_LIBRARY} + +target_link_libraries(${MIP_METADATA_LIBRARY} PUBLIC ${MIP_LIBRARY}) + +target_compile_definitions(${MIP_METADATA_LIBRARY} + PUBLIC "MIP_ENABLE_METADATA=1" + PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS} ) -target_compile_definitions(${MIP_METADATA_LIBRARY} PUBLIC "MIP_ENABLE_METADATA=1") + +target_compile_options(${MIP_METADATA_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_METADATA_LIBRARY}) + +# +# Installation +# +include(microstrain_utilities) +microstrain_setup_library_install(${MIP_METADATA_LIBRARY} ${MIP_LIBRARY}) From 1dbcf588ed6e4c335d91df65e99a89dfcb94f38f Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 6 Sep 2024 14:26:23 -0400 Subject: [PATCH 101/147] Fixed package/install Updated all CMake variables to prepend MIP or MICROSTRAIN where needed Moved some utility functions to the microstrain_utilities.cmake file for use across projects --- .devcontainer/docker_build.sh | 4 +- CMakeLists.txt | 267 +++++------------- Jenkinsfile | 10 +- README.md | 22 +- cmake/microstrain_utilities.cmake | 168 ++++++++--- cmake/mip_version.h.in | 2 +- src/c/microstrain/common/CMakeLists.txt | 13 +- .../connections/serial/CMakeLists.txt | 7 +- .../connections/tcp/CMakeLists.txt | 7 +- src/c/mip/CMakeLists.txt | 78 ++--- src/cpp/microstrain/common/CMakeLists.txt | 19 +- .../connections/recording/CMakeLists.txt | 9 +- .../connections/serial/CMakeLists.txt | 9 +- .../connections/tcp/CMakeLists.txt | 9 +- src/cpp/microstrain/extras/CMakeLists.txt | 10 +- src/cpp/mip/CMakeLists.txt | 31 +- src/cpp/mip/extras/CMakeLists.txt | 11 +- src/cpp/mip/metadata/CMakeLists.txt | 23 +- test/CMakeLists.txt | 2 +- 19 files changed, 352 insertions(+), 349 deletions(-) diff --git a/.devcontainer/docker_build.sh b/.devcontainer/docker_build.sh index 2ffb17adf..4fcff3308 100755 --- a/.devcontainer/docker_build.sh +++ b/.devcontainer/docker_build.sh @@ -62,7 +62,7 @@ docker run \ mkdir ${docker_project_dir}/${build_dir_name}; \ cd ${docker_project_dir}/${build_dir_name}; \ cmake ${docker_project_dir} \ - -DBUILD_PACKAGE=ON; \ + -DMICROSTRAIN_BUILD_PACKAGE=ON; \ cmake --build . -j; \ cmake --build . --target package; \ - " \ No newline at end of file + " diff --git a/CMakeLists.txt b/CMakeLists.txt index c83a4a346..d116afcd7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.10) +cmake_minimum_required(VERSION 3.12) set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) @@ -6,22 +6,22 @@ set(CMAKE_C_STANDARD 11) set(CMAKE_C_STANDARD_REQUIRED ON) project( - "MIP SDK" + "MIP_SDK" VERSION "3.0.00" DESCRIPTION "MicroStrain Communications Library for embedded systems" LANGUAGES C CXX ) -set(SRC_DIR "${CMAKE_CURRENT_LIST_DIR}/src") -set(MIP_CMAKE_DIR "${CMAKE_CURRENT_LIST_DIR}/cmake") -set(MIP_DIR "${SRC_DIR}/mip") +set(MICROSTRAIN_SRC_DIR "${CMAKE_CURRENT_LIST_DIR}/src") -list(APPEND CMAKE_MODULE_PATH ${MIP_CMAKE_DIR}) +# Add our cmake directory to the available cmake modules path +list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/cmake") # # Build options # +# MicroStrain options option(MICROSTRAIN_ENABLE_LOGGING "Build with logging functions enabled" ON) set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_INFO" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") @@ -34,77 +34,31 @@ option(MICROSTRAIN_ENABLE_EXTRAS "Build extra support into the library including option(MICROSTRAIN_ENABLE_SERIAL "Build serial connection support into the library and examples" ON) option(MICROSTRAIN_ENABLE_TCP "Build TCP connection support into the library and examples" ON) -# MIP options -option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) - -if(NOT DEFINED MIP_ENABLE_METADATA) - include("${MIP_CMAKE_DIR}/check_metadata.cmake") - message("MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") -endif() -option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" ${MIP_COMPILER_SUPPORTS_METADATA}) -option(MIP_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ${MICROSTRAIN_ENABLE_EXTRAS}) +option(MICROSTRAIN_BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) +option(MICROSTRAIN_BUILD_EXAMPLES "Builds the example programs." OFF) -# Build options -option(BUILD_PACKAGE "Whether to build a package from the resulting binaries" OFF) -option(BUILD_EXAMPLES "Builds the example programs." ON) # CTest defines this option to ON by default, so override it to OFF here. -option(BUILD_TESTS "Build the testing tree." OFF) -option(BUILD_DOCUMENTATION "Build the documentation." OFF) -option(BUILD_DOCUMENTATION_FULL "Build the full (internal) documentation." OFF) -option(BUILD_DOCUMENTATION_QUIET "Suppress doxygen standard output." ON) +option(MICROSTRAIN_BUILD_TESTS "Build the testing tree." OFF) + +option(MICROSTRAIN_BUILD_DOCUMENTATION "Build the documentation." OFF) +option(MICROSTRAIN_BUILD_DOCUMENTATION_FULL "Build the full (internal) documentation." OFF) +option(MICROSTRAIN_BUILD_DOCUMENTATION_QUIET "Suppress doxygen standard output." ON) option(MICROSTRAIN_CMAKE_DEBUG "If set, prints build system debug info such as source files and preprocessor definitions." ON) # TODO: off by default mark_as_advanced(MICROSTRAIN_CMAKE_DEBUG) -# -# Version numbering -# - -# Use Git to find the version -find_package(Git) -set(DEFAULT_MIP_GIT_VERSION "v0.0.0") -if(NOT GIT_FOUND) - message(STATUS "Unable to find git, will build with unknown version") - set(MIP_GIT_VERSION ${DEFAULT_MSCL_GIT_VERSION}) -else() - execute_process( - COMMAND ${CMAKE_COMMAND} -E env ${GIT_EXECUTABLE} describe --tags - WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - OUTPUT_VARIABLE MIP_GIT_VERSION_OUT - ERROR_VARIABLE MIP_GIT_VERSION_ERR - RESULT_VARIABLE MIP_GIT_VERSION_RET - ) - if(NOT ${MIP_GIT_VERSION_RET} EQUAL 0) - message(STATUS "Unable to determine version from Git, defaulting to version ${DEFAULT_MIP_GIT_VERSION}") - set(MIP_GIT_VERSION ${DEFAULT_MIP_GIT_VERSION}) - else() - set(MIP_GIT_VERSION ${MIP_GIT_VERSION_OUT}) - string(REGEX REPLACE "\n" "" MIP_GIT_VERSION "${MIP_GIT_VERSION}") - message(STATUS "MIP SDK Version: ${MIP_GIT_VERSION}") - endif() -endif() +# MIP options +option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) -# Massage the version number a little so we can use it in a couple places -string(REGEX REPLACE "^v?([0-9]+)\\.([0-9]+)\\.([0-9]+).*" "\\1.\\2.\\3" MIP_GIT_VERSION_CLEAN ${MIP_GIT_VERSION}) -string(REPLACE "." ";" MIP_GIT_VERSION_LIST ${MIP_GIT_VERSION_CLEAN}) -list(LENGTH MIP_GIT_VERSION_LIST MIP_GIT_VERSION_LIST_LENGTH) -if (MIP_GIT_VERSION_LIST_LENGTH GREATER_EQUAL 3) - list(GET MIP_GIT_VERSION_LIST 0 MIP_GIT_VERSION_MAJOR) - list(GET MIP_GIT_VERSION_LIST 1 MIP_GIT_VERSION_MINOR) - list(GET MIP_GIT_VERSION_LIST 2 MIP_GIT_VERSION_PATCH) -else() - message(WARNING "MIP version cannot be parsed into a semantic version string.\nPlease run 'git fetch --tags' to get a properly tagged build") - set(MIP_GIT_VERSION_CLEAN "0.0.0") - set(MIP_GIT_VERSION_MAJOR 0) - set(MIP_GIT_VERSION_MINOR 0) - set(MIP_GIT_VERSION_PATCH 0) +if(NOT DEFINED MIP_ENABLE_METADATA) + include(check_metadata) + message("MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") endif() +option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" ${MIP_COMPILER_SUPPORTS_METADATA}) +option(MIP_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ${MICROSTRAIN_ENABLE_EXTRAS}) -# Generate the version header file -set(VERSION_IN_FILE "${CMAKE_CURRENT_LIST_DIR}/cmake/mip_version.h.in") -set(VERSION_OUT_FILE "${SRC_DIR}/c/mip/mip_version.h") -configure_file(${VERSION_IN_FILE} ${VERSION_OUT_FILE}) - +# Include some utilities used for MicroStrain projects +include(microstrain_utilities) # # Common preprocessor definitions @@ -150,17 +104,17 @@ cmake_policy(SET CMP0079 NEW) # Add all the C files (required even for C++ API) -set(SRC_C_DIR "${CMAKE_CURRENT_LIST_DIR}/src/c") +set(MICROSTRAIN_SRC_C_DIR "${MICROSTRAIN_SRC_DIR}/c") -add_subdirectory(${SRC_C_DIR}/microstrain) -add_subdirectory(${SRC_C_DIR}/mip) +add_subdirectory(${MICROSTRAIN_SRC_C_DIR}/microstrain) +add_subdirectory(${MICROSTRAIN_SRC_C_DIR}/mip) # Add all the C++ files (if C++ enabled) if(MICROSTRAIN_ENABLE_CPP) - set(SRC_CPP_DIR "${CMAKE_CURRENT_LIST_DIR}/src/cpp") + set(MICROSTRAIN_SRC_CPP_DIR "${MICROSTRAIN_SRC_DIR}/cpp") - add_subdirectory(${SRC_CPP_DIR}/microstrain) - add_subdirectory(${SRC_CPP_DIR}/mip) + add_subdirectory(${MICROSTRAIN_SRC_CPP_DIR}/microstrain) + add_subdirectory(${MICROSTRAIN_SRC_CPP_DIR}/mip) #target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_CPP_C_NAMESPACE=${MICROSTRAIN_ENABLE_CPP_C_NAMESPACE}") endif() @@ -178,7 +132,7 @@ target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MICROSTRAIN_LIBRARIES}) include(CTest) -if(BUILD_TESTS) +if(MICROSTRAIN_BUILD_TESTS) add_subdirectory("test") endif() @@ -186,22 +140,28 @@ endif() # EXAMPLES # -if(BUILD_EXAMPLES) +if(MICROSTRAIN_BUILD_EXAMPLES) add_subdirectory("examples") endif() +# +# Version numbering +# + +microstrain_get_git_version(MICROSTRAIN_GIT_VERSION MICROSTRAIN_GIT_VERSION_CLEAN) + # # DOCUMENTATION # -find_package(Doxygen) +if(MICROSTRAIN_BUILD_DOCUMENTATION) + find_package(Doxygen) -if(BUILD_DOCUMENTATION) if(NOT DOXYGEN_FOUND) message(FATAL_ERROR "Doxygen is required to build documentation.") endif() - set(DOXYGEN_PROJECT_NUMBER "${MIP_GIT_VERSION}") + set(DOXYGEN_PROJECT_NUMBER "${MICROSTRAIN_GIT_VERSION}") set(DOXYGEN_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/documentation") set(DOXYGEN_IMAGE_PATH "${CMAKE_CURRENT_LIST_DIR}/docs") @@ -214,7 +174,7 @@ if(BUILD_DOCUMENTATION) set(DOXYGEN_EXTRACT_ALL YES) - if(BUILD_DOCUMENTATION_FULL) + if(MICROSTRAIN_BUILD_DOCUMENTATION_FULL) set(DOXYGEN_INTERNAL_DOCS YES) # set(DOXYGEN_WARN_AS_ERROR YES) else() @@ -222,12 +182,12 @@ if(BUILD_DOCUMENTATION) set(DOXYGEN_HIDE_UNDOC_CLASSES YES) endif() - if(BUILD_DOCUMENTATION_QUIET) + if(MICROSTRAIN_BUILD_DOCUMENTATION_QUIET) set(DOXYGEN_QUIET YES) endif() doxygen_add_docs(docs - "${SRC_DIR}" "${CMAKE_CURRENT_LIST_DIR}/docs" + "${MICROSTRAIN_SRC_DIR}" "${CMAKE_CURRENT_LIST_DIR}/docs" COMMENT "Generating documentation." ) @@ -235,9 +195,9 @@ if(BUILD_DOCUMENTATION) add_custom_target(package_docs WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/documentation/html DEPENDS docs - COMMAND ${CMAKE_COMMAND} -E tar "cf" "${CMAKE_CURRENT_BINARY_DIR}/mipsdk_${MIP_GIT_VERSION}_Documentation.zip" --format=zip "." + COMMAND ${CMAKE_COMMAND} -E tar "cf" "${CMAKE_CURRENT_BINARY_DIR}/mipsdk_${MICROSTRAIN_GIT_VERSION}_Documentation.zip" --format=zip "." ) -endif(BUILD_DOCUMENTATION) +endif() # # Packaging @@ -262,96 +222,9 @@ write_basic_package_version_file( COMPATIBILITY AnyNewerVersion ) -# -# Installation -# - -## Only install headers that we build the source files for -#set(ALL_MIP_HEADERS "${ALL_MIP_SOURCES}") -#list(FILTER ALL_MIP_HEADERS INCLUDE REGEX "^.*\.(h|hpp)$") -#foreach(MIP_HEADER ${ALL_MIP_HEADERS}) -# string(REPLACE "${SRC_DIR}/" "" MIP_HEADER_RELATIVE "${MIP_HEADER}") -# if(INT_DIR) -# string(REPLACE "${INT_DIR}/" "" MIP_HEADER_RELATIVE "${MIP_HEADER_RELATIVE}") -# endif() -# set(MIP_HEADER_DESTINATION_FULL "${CMAKE_INSTALL_INCLUDEDIR}/${MIP_HEADER_RELATIVE}") -# get_filename_component(MIP_HEADER_DESTINATION "${MIP_HEADER_DESTINATION_FULL}" DIRECTORY) -# install( -# FILES "${MIP_HEADER}" -# DESTINATION "${MIP_HEADER_DESTINATION}" -# COMPONENT ${MIP_LIBRARY} -# ) -#endforeach() -# -#install(TARGETS -# ${MIP_LIBRARY} -# EXPORT mip-targets -# ARCHIVE -# COMPONENT ${MIP_LIBRARY} -# DESTINATION "${CMAKE_INSTALL_LIBDIR}/" -#) -# -#install(EXPORT -# mip-targets -# COMPONENT ${MIP_LIBRARY} -# DESTINATION "${CONFIG_EXPORT_DIR}" -#) -# -#install(FILES -# "${CMAKE_BINARY_DIR}/mip-config.cmake" -# "${CMAKE_BINARY_DIR}/mip-config-version.cmake" -# COMPONENT ${MIP_LIBRARY} -# DESTINATION "${CONFIG_EXPORT_DIR}" -#) - -# Try to determine what architecture we are building for based on the compiler output -if(MSVC) - # Detect if this is a x64 or x86 build - if(CMAKE_SIZEOF_VOID_P EQUAL 8) - set(MIP_ARCH "x64") - elseif(CMAKE_SIZEOF_VOID_P EQUAL 4) - set(MIP_ARCH "x86") - endif() -elseif(UNIX) - if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") - # The dumpmachine command from gcc should contain information on the architecture - execute_process( - COMMAND ${CMAKE_COMMAND} -E env /bin/bash -c "${CMAKE_CXX_COMPILER} -dumpmachine" - OUTPUT_VARIABLE GCC_ARCHITECTURE_OUT - WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - ERROR_VARIABLE GCC_ARCHITECTURE_ERR - RESULT_VARIABLE GCC_ARCHITECTURE_RET - ) - - # Convert the GCC architecture to the format that we use - if("${GCC_ARCHITECTURE_OUT}" MATCHES ".*x86_64.*") - set(MIP_ARCH "amd64") - elseif("${GCC_ARCHITECTURE_OUT}" MATCHES ".*aarch64.*") - set(MIP_ARCH "arm64") - elseif("${GCC_ARCHITECTURE_OUT}" MATCHES ".*arm.*") - set(MIP_ARCH "armhf") - else() - message(STATUS "Unrecognized GCC architecture ${GCC_ARCHITECTURE_OUT}. Using CMAKE_SYSTEM_PROCESSOR for architecture") - endif() - endif() -endif() -if(NOT DEFINED MIP_ARCH) - message(STATUS "Defaulting MIP_ARCH to ${CMAKE_SYSTEM_PROCESSOR}") - set(MIP_ARCH ${CMAKE_SYSTEM_PROCESSOR}) -endif() - # If we were asked to package, find the generators we can use -if(BUILD_PACKAGE) - # Get a list of libraries to package - get_target_property(MICROSTRAIN_PACKAGES ${MICROSTRAIN_LIBRARIES} INTERFACE_LINK_LIBRARIES) - get_target_property(MIP_PACKAGES ${MIP_LIBRARIES} INTERFACE_LINK_LIBRARIES) - - # Filter out directory IDs from (INTERFACE_)LINK_LIBRARIES as well as the MicroStrain libraries from MIP - # https://cmake.org/cmake/help/latest/prop_tgt/LINK_LIBRARIES.html - set(REGEX_MATCH "(::@*)") - list(FILTER MICROSTRAIN_PACKAGES EXCLUDE REGEX ${REGEX_MATCH}) - string(APPEND REGEX_MATCH "|(${MICROSTRAIN_LIBRARIES})") - list(FILTER MIP_PACKAGES EXCLUDE REGEX ${REGEX_MATCH}) +if(MICROSTRAIN_BUILD_PACKAGE) + microstrain_get_architecture(MICROSTRAIN_ARCH) set(FOUND_CPACK_GENERATORS "") @@ -364,18 +237,32 @@ if(BUILD_PACKAGE) PATHS ${DPKG_ROOT} DOC "dpkg command line client" ) + if(NOT ${DPKG_EXECUTABLE} STREQUAL "DPKG_EXECUTABLE-NOTFOUND") list(APPEND FOUND_CPACK_GENERATORS "DEB") endif() + # DEB specific configuration + # Build different deb packages for each target + set(CPACK_DEBIAN_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}.deb") + set(CPACK_DEB_COMPONENT_INSTALL ON) + set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) + find_program(RPMBUILD_EXECUTABLE NAMES rpmbuild PATHS ${RPMBUILD_ROOT} DOC "rpmbuild command line client" ) + if(NOT ${RPMBUILD_EXECUTABLE} STREQUAL "RPMBUILD_EXECUTABLE-NOTFOUND") list(APPEND FOUND_CPACK_GENERATORS "RPM") endif() + + # RPM specific configuration + # Build different RPM packages for each target + set(CPACK_RPM_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}.rpm") + set(CPACK_RPM_COMPONENT_INSTALL ON) + set(CPACK_RPM_PACKAGE_AUTOREQ ON) endif() # Windows always has zip installed, so only look for it on linux and mac @@ -404,43 +291,29 @@ if(BUILD_PACKAGE) set(CPACK_GENERATOR "${FOUND_CPACK_GENERATORS}") set(CPACK_PACKAGE_VENDOR "MicroStrain by HBK") set(CPACK_PACKAGE_CONTACT "MicroStrain Support ") - set(CPACK_COMPONENTS_ALL ${MIP_LIBRARY} ${MIP_LIBRARIES}) - set(CPACK_PACKAGE_VERSION ${MIP_GIT_VERSION_CLEAN}) + set(CPACK_PACKAGE_VERSION ${MICROSTRAIN_GIT_VERSION_CLEAN}) # Shared configuration - set(MIP_FILE_NAME_PREFIX "mipsdk_${MIP_GIT_VERSION}_${MIP_ARCH}") - - # DEB specific configuration - # Build different deb packages for each target - set(CPACK_DEBIAN_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}.deb") - set(CPACK_DEB_COMPONENT_INSTALL ON) - set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) - - # RPM specific configuration - # Build different RPM packages for each target - set(CPACK_RPM_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}.rpm") - set(CPACK_RPM_COMPONENT_INSTALL ON) - set(CPACK_RPM_PACKAGE_AUTOREQ ON) + set(MIP_FILE_NAME_PREFIX "mipsdk_${MICROSTRAIN_GIT_VERSION}_${MICROSTRAIN_ARCH}") # Zip specific configuration # Build different zip packages for each target if(MSVC) - set(CPACK_ARCHIVE_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}_MSVC_v${MSVC_TOOLSET_VERSION}") + set(CPACK_PACKAGE_FILE_NAME "${MIP_FILE_NAME_PREFIX}_MSVC_v${MSVC_TOOLSET_VERSION}") elseif(APPLE) - set(CPACK_ARCHIVE_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}_OSX") + set(CPACK_PACKAGE_FILE_NAME "${MIP_FILE_NAME_PREFIX}_OSX") elseif(UNIX) - set(CPACK_ARCHIVE_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}_Linux") + set(CPACK_PACKAGE_FILE_NAME "${MIP_FILE_NAME_PREFIX}_Linux") else() - set(CPACK_ARCHIVE_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}") + set(CPACK_PACKAGE_FILE_NAME "${MIP_FILE_NAME_PREFIX}") endif() + set(CPACK_ARCHIVE_COMPONENT_INSTALL ON) + # Package everything into a single group (includes all MIP and MicroStrain SDK files/libs in one package) + set(CPACK_COMPONENTS_GROUPING ALL_COMPONENTS_IN_ONE) + # Finally include cpack which should have taken all of the previous variables into consideration include(CPack) - - cpack_add_component(${MIP_LIBRARY} - DESCRIPTION "MIP SDK static library and header files" - GROUP ${MIP_LIBRARY} - ) endif() diff --git a/Jenkinsfile b/Jenkinsfile index 2d3dbc5a3..2f9bf5366 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -54,8 +54,8 @@ pipeline { cmake .. ` -A "Win32" ` -T "v143" ` - -DBUILD_DOCUMENTATION=ON ` - -DBUILD_PACKAGE=ON + -DMICROSTRAIN_BUILD_DOCUMENTATION=ON ` + -DMICROSTRAIN_BUILD_PACKAGE=ON if(\$?) { cmake --build . } if(\$?) { cmake --build . --target package } if(\$?) { cmake --build . --target package_docs } @@ -80,7 +80,7 @@ pipeline { cmake .. ` -A "x64" ` -T "v143" ` - -DBUILD_PACKAGE=ON + -DMICROSTRAIN_BUILD_PACKAGE=ON if(\$?) { cmake --build . } if(\$?) { cmake --build . --target package } """ @@ -162,7 +162,7 @@ pipeline { mkdir build_mac_arm64 cd build_mac_arm64 cmake .. \ - -DBUILD_PACKAGE=ON \ + -DMICROSTRAIN_BUILD_PACKAGE=ON \ -DCMAKE_BUILD_TYPE=RELEASE cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package @@ -185,7 +185,7 @@ pipeline { mkdir build_mac_intel cd build_mac_intel cmake .. \ - -DBUILD_PACKAGE=ON \ + -DMICROSTRAIN_BUILD_PACKAGE=ON \ -DCMAKE_BUILD_TYPE=RELEASE cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package diff --git a/README.md b/README.md index efdaa9fa2..c243fc3db 100644 --- a/README.md +++ b/README.md @@ -125,20 +125,22 @@ How to Build ### CMake Build Configuration The following options may be specified when configuring the build with CMake (e.g. `cmake .. -DOPTION=VALUE`): -* MICROSTRAIN_ENABLE_SERIAL - Builds the included serial port library (default enabled). -* MICROSTRAIN_ENABLE_TCP - Builds the included socket library (default enabled). * MICROSTRAIN_ENABLE_LOGGING - Builds logging functionality into the library. The user is responsible for configuring a logging callback (default enabled) * MICROSTRAIN_LOGGING_MAX_LEVEL - Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration. Useful if you want some logs, but do not want the overhead compiled into the code. * MICROSTRAIN_TIMESTAMP_TYPE - Overrides the default timestamp type. See [Timestamps](https://lord-microstrain.github.io/mip_sdk_documentation/latest/timestamps.html) in the documentation. * MICROSTRAIN_ENABLE_CPP - Causes the src/cpp directory to be included in the build (default enabled). Disable to turn off the C++ api. -* MIP_ENABLE_EXTRAS - Builds some higher level utility classes and functions that may use dynamic memory. +* MICROSTRAIN_ENABLE_EXTRAS - Builds some higher level utility classes and functions that may use dynamic memory. +* MICROSTRAIN_ENABLE_SERIAL - Builds the included serial port library (default enabled). +* MICROSTRAIN_ENABLE_TCP - Builds the included socket library (default enabled). +* MICROSTRAIN_BUILD_PACKAGE - Adds a `package` target to the project that will build a `.deb`, `.rpm`, or `.zip` file containing the library +* MICROSTRAIN_BUILD_EXAMPLES - If enabled (`-DMICROSTRAIN_BUILD_EXAMPLES=ON`), the example projects will be built (default disabled). +* MICROSTRAIN_BUILD_TESTING - If enabled (`-DMICROSTRAIN_BUILD_TESTING=ON`), the test programs in the /test directory will be compiled and linked. Run the tests with `ctest`. +* MICROSTRAIN_BUILD_DOCUMENTATION - If enabled, the documentation will be built with doxygen. You must have doxygen installed. +* MICROSTRAIN_BUILD_DOCUMENTATION_FULL - Builds internal documentation (default disabled). +* MICROSTRAIN_BUILD_DOCUMENTATION_QUIET - Suppress standard doxygen output (default enabled). * MIP_ENABLE_DIAGNOSTICS - Adds some counters to various entities which can serve as a debugging aid. -* BUILD_EXAMPLES - If enabled (`-DBUILD_EXAMPLES=ON`), the example projects will be built (default disabled). -* BUILD_TESTING - If enabled (`-DBUILD_TESTING=ON`), the test programs in the /test directory will be compiled and linked. Run the tests with `ctest`. -* BUILD_DOCUMENTATION - If enabled, the documentation will be built with doxygen. You must have doxygen installed. -* BUILD_DOCUMENTATION_FULL - Builds internal documentation (default disabled). -* BUILD_DOCUMENTATION_QUIET - Suppress standard doxygen output (default enabled). -* BUILD_PACKAGE - Adds a `package` target to the project that will build a `.deb`, `.rpm`, or `.7z` file containing the library +* MIP_ENABLE_METADATA - Builds metadata for MIP commands. If not set, the system will try to determine if C++20 is available to enable it. C++20 is required for the metadata module. +* MIP_ENABLE_EXTRAS - Builds some higher level utility classes and functions that may use dynamic memory. (default MICROSTRAIN_ENABLE_EXTRAS) ### Compilation @@ -148,7 +150,7 @@ The following options may be specified when configuring the build with CMake (e. * You can use `cmake-gui ..` instead if you'd prefer to use the GUI tool (and have it installed). * An alternative generator may be used, such as ninja, code blocks, etc. by specifying `-G ` 3. Invoke `cmake --build .` in the build directory -4. (Optional, if BUILD_PACKAGE was enabled) Run `cmake --build . --target package` to build the packages. +4. (Optional, if MICROSTRAIN_BUILD_PACKAGE was enabled) Run `cmake --build . --target package` to build the packages. ### Building without CMake diff --git a/cmake/microstrain_utilities.cmake b/cmake/microstrain_utilities.cmake index ad6142f87..57282ab3f 100644 --- a/cmake/microstrain_utilities.cmake +++ b/cmake/microstrain_utilities.cmake @@ -1,50 +1,152 @@ -macro(microstrain_setup_install_headers LIBRARY) -# message(WARNING "Lib headers: ${LIBRARY}") - +# Install the headers in their +macro(microstrain_setup_install_headers LIBRARY ROOT_DIR) # Only install headers that we build the source files for get_target_property(ALL_HEADERS ${LIBRARY} SOURCES) list(FILTER ALL_HEADERS INCLUDE REGEX "^.*\.(h|hpp)$") -# message(WARNING "${LIBRARY} Headers: ${ALL_HEADERS}") -# foreach(HEADER ${ALL_HEADERS}) -# string(REPLACE "${CMAKE_CURRENT_LIST_DIR}/" "" HEADER_RELATIVE "${HEADER}") -# set(HEADER_DESTINATION_FULL "${CMAKE_INSTALL_INCLUDEDIR}/${HEADER_RELATIVE}") -# get_filename_component(HEADER_DESTINATION "${HEADER_DESTINATION_FULL}" DIRECTORY) -# install( -# FILES "${HEADER}" -# DESTINATION "${HEADER_DESTINATION}" -# COMPONENT ${LIBRARY} -# ) -# endforeach() -endmacro() -macro(microstrain_setup_library_install LIBRARY EXPORT_TARGET) -# message(WARNING "Lib install: ${LIBRARY}") + # Setup the include directory for each header within a MicroStrain subdirectory + foreach(HEADER ${ALL_HEADERS}) + # Replace the source directory with the installer include directory (within a MicroStrain subdirectory) + string(REPLACE + "${ROOT_DIR}" + "${CMAKE_INSTALL_INCLUDEDIR}/microstrain" + HEADER_DESTINATION_FULL + "${HEADER}" + ) + + # Get the install directory without the file + get_filename_component(HEADER_DESTINATION "${HEADER_DESTINATION_FULL}" DIRECTORY) - microstrain_setup_install_headers(${LIBRARY}) + install( + FILES "${HEADER}" + DESTINATION "${HEADER_DESTINATION}" + COMPONENT "${LIBRARY}" + ) + endforeach() +endmacro() + +macro(microstrain_setup_library_install LIBRARY ROOT_DIR) + microstrain_setup_install_headers(${LIBRARY} ${ROOT_DIR}) install( TARGETS ${LIBRARY} - EXPORT mip-targets - ARCHIVE - COMPONENT ${LIBRARY} - DESTINATION ${CMAKE_INSTALL_LIBDIR}/ + EXPORT ${LIBRARY}-targets + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} ) -# message(WARNING "${LIBRARY} install dir: ${CMAKE_INSTALL_LIBDIR}") - include(CMakePackageConfigHelpers) +# include(CMakePackageConfigHelpers) - set(CONFIG_EXPORT_DIR "${CMAKE_INSTALL_DATADIR}/cmake/${LIBRARY}") -# message(WARNING "${LIBRARY} config dir: ${CONFIG_EXPORT_DIR}") +# set(CONFIG_EXPORT_DIR "${CMAKE_INSTALL_DATADIR}/cmake/${LIBRARY}") + # TODO: Do we want this configure step? What is it used for? # install( -# EXPORT mip-targets -# COMPONENT ${LIBRARY} +# FILES "${CMAKE_BINARY_DIR}/${LIBRARY}-config.cmake" "${CMAKE_BINARY_DIR}/${LIBRARY}-config-version.cmake" # DESTINATION ${CONFIG_EXPORT_DIR} +# COMPONENT ${LIBRARY} # ) +endmacro() - install( - FILES "${CMAKE_BINARY_DIR}/${LIBRARY}-config.cmake" "${CMAKE_BINARY_DIR}/${LIBRARY}-config-version.cmake" - DESTINATION ${CONFIG_EXPORT_DIR} - COMPONENT ${LIBRARY} - ) +# +# Utility macros to write to output variables +# Do not call these in the conventional way I.E. macro_name(${VARIABLE_NAME}) +# Instead, do macro_name(VARIABLE_NAME) which will do `set(${PARAM_OUT} value)` and is equivalent to set(VARIABLE_NAME value) +# + +macro(microstrain_get_git_version GIT_VERSION_OUT GIT_VERSION_CLEAN_OUT) + # Use Git to find the version + find_package(Git) + + set(MICROSTRAIN_DEFAULT_GIT_VERSION "v0.0.0") + + if(NOT GIT_FOUND) + message(WARNING "Unable to find Git, will build with unknown version") + set(${GIT_VERSION_OUT} ${MICROSTRAIN_DEFAULT_GIT_VERSION}) + else() + execute_process( + COMMAND ${CMAKE_COMMAND} -E env ${GIT_EXECUTABLE} describe --tags + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + OUTPUT_VARIABLE MICROSTRAIN_GIT_VERSION_OUT + ERROR_VARIABLE MICROSTRAIN_GIT_VERSION_ERR + RESULT_VARIABLE MICROSTRAIN_GIT_VERSION_RET + ) + if(NOT ${MICROSTRAIN_GIT_VERSION_RET} EQUAL 0) + message(STATUS "Unable to determine version from Git, defaulting to version ${MICROSTRAIN_DEFAULT_GIT_VERSION}") + set(${GIT_VERSION_OUT} ${MICROSTRAIN_DEFAULT_GIT_VERSION}) + else() + set(${GIT_VERSION_OUT} ${MICROSTRAIN_GIT_VERSION_OUT}) + string(REGEX REPLACE "\n" "" ${GIT_VERSION_OUT} "${${GIT_VERSION_OUT}}") + message(STATUS "Determined version from Git: ${${GIT_VERSION_OUT}}") + endif() + endif() + + # Massage the version number a little so we can use it in a couple places + string(REGEX REPLACE "^v?([0-9]+)\\.([0-9]+)\\.([0-9]+).*" "\\1.\\2.\\3" ${GIT_VERSION_CLEAN_OUT} ${${GIT_VERSION_OUT}}) +endmacro() + +# Use the variable name not value for GIT_VERSION_CLEAN to lookup the version and also set it +# This is a followup macro for microstrain_get_git_version +# I.E. microstrain_extract_git_version(MICROSTRAIN_GIT_VERSION_CLEAN MICROSTRAIN_GIT_VERSION_MAJOR ...) +macro(microstrain_extract_git_version GIT_VERSION_CLEAN GIT_VERSION_MAJOR_OUT GIT_VERSION_MINOR_OUT GIT_VERSION_PATCH_OUT) + if(NOT DEFINED ${GIT_VERSION_CLEAN}) + message(WARNING "Use the name to use for the variable GIT_VERSION_CLEAN instead of passing the value") + endif() + + string(REPLACE "." ";" MICROSTRAIN_GIT_VERSION_LIST ${${GIT_VERSION_CLEAN}}) + list(LENGTH MICROSTRAIN_GIT_VERSION_LIST MICROSTRAIN_GIT_VERSION_LIST_LENGTH) + + if(MICROSTRAIN_GIT_VERSION_LIST_LENGTH GREATER_EQUAL 3) + list(GET MICROSTRAIN_GIT_VERSION_LIST 0 ${GIT_VERSION_MAJOR_OUT}) + list(GET MICROSTRAIN_GIT_VERSION_LIST 1 ${GIT_VERSION_MINOR_OUT}) + list(GET MICROSTRAIN_GIT_VERSION_LIST 2 ${GIT_VERSION_PATCH_OUT}) + else() + message(WARNING "Version cannot be parsed into a semantic version string.\nPlease run 'git fetch --tags' to get a properly tagged build") + set(${GIT_VERSION_CLEAN} "0.0.0") + set(${GIT_VERSION_MAJOR_OUT} 0) + set(${GIT_VERSION_MINOR_OUT} 0) + set(${GIT_VERSION_PATCH_OUT} 0) + endif() +endmacro() + +# Try to determine what architecture we are building for based on the compiler output +# Specify the variable to set as the parameter +macro(microstrain_get_architecture SYS_ARCH_OUT) + if(MSVC) + # Detect if this is a x64 or x86 build + if(CMAKE_SIZEOF_VOID_P EQUAL 8) + set(${SYS_ARCH_OUT} "x64") + elseif(CMAKE_SIZEOF_VOID_P EQUAL 4) + set(${SYS_ARCH_OUT} "x86") + endif() + elseif(UNIX) + if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") + # The dumpmachine command from gcc should contain information on the architecture + execute_process( + COMMAND ${CMAKE_COMMAND} -E env /bin/bash -c "${CMAKE_CXX_COMPILER} -dumpmachine" + OUTPUT_VARIABLE MICROSTRAIN_GCC_ARCHITECTURE_OUT + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + ERROR_VARIABLE MICROSTRAIN_GCC_ARCHITECTURE_ERR + RESULT_VARIABLE MICROSTRAIN_GCC_ARCHITECTURE_RET + ) + + # Convert the GCC architecture to the format that we use + if("${MICROSTRAIN_GCC_ARCHITECTURE_OUT}" MATCHES ".*x86_64.*") + set(${SYS_ARCH_OUT} "amd64") + elseif("${MICROSTRAIN_GCC_ARCHITECTURE_OUT}" MATCHES ".*aarch64.*") + set(${SYS_ARCH_OUT} "arm64") + elseif("${MICROSTRAIN_GCC_ARCHITECTURE_OUT}" MATCHES ".*arm.*") + set(${SYS_ARCH_OUT} "armhf") + else() + message(STATUS "Unrecognized GCC architecture ${MICROSTRAIN_GCC_ARCHITECTURE_OUT}. Using CMAKE_SYSTEM_PROCESSOR for architecture") + endif() + endif() + endif() + + if(NOT DEFINED ${SYS_ARCH_OUT}) + message(STATUS "Defaulting ${SYS_ARCH_OUT} to ${CMAKE_SYSTEM_PROCESSOR}") + set(${SYS_ARCH_OUT} ${CMAKE_SYSTEM_PROCESSOR}) + else() + message(STATUS "Detected system architecture ${${SYS_ARCH_OUT}}") + endif() endmacro() diff --git a/cmake/mip_version.h.in b/cmake/mip_version.h.in index 95cdf4df6..18ed3a5ea 100644 --- a/cmake/mip_version.h.in +++ b/cmake/mip_version.h.in @@ -7,4 +7,4 @@ #define MIP_SDK_VERSION "${MIP_GIT_VERSION_CLEAN}" #define MIP_SDK_VERSION_MAJOR ${MIP_GIT_VERSION_MAJOR} #define MIP_SDK_VERSION_MINOR ${MIP_GIT_VERSION_MINOR} -#define MIP_SDK_VERSION_PATCH ${MIP_GIT_VERSION_PATCH} \ No newline at end of file +#define MIP_SDK_VERSION_PATCH ${MIP_GIT_VERSION_PATCH} diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index d5b1b7974..033fb90fe 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -6,10 +6,10 @@ set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_WARN" CACHE STRING "Max set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") add_library(${MICROSTRAIN_COMMON_LIBRARY} - "logging.h" - "platform.h" - "serialization.c" - "serialization.h" + "${CMAKE_CURRENT_LIST_DIR}/logging.h" + "${CMAKE_CURRENT_LIST_DIR}/platform.h" + "${CMAKE_CURRENT_LIST_DIR}/serialization.c" + "${CMAKE_CURRENT_LIST_DIR}/serialization.h" ) target_compile_features(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC c_std_11) @@ -31,12 +31,13 @@ if(MICROSTRAIN_ENABLE_LOGGING) target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_LOGGING" "MICROSTRAIN_LOGGING_MAX_LEVEL=${MICROSTRAIN_LOGGING_MAX_LEVEL}") endif() -target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${SRC_C_DIR}) +target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${MICROSTRAIN_SRC_C_DIR}) target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_COMMON_LIBRARY}) # # Installation # + include(microstrain_utilities) -microstrain_setup_library_install(${MICROSTRAIN_COMMON_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) +microstrain_setup_library_install(${MICROSTRAIN_COMMON_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/c/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt index 957fa09c3..6b505a7c4 100644 --- a/src/c/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -2,8 +2,8 @@ set(MICROSTRAIN_SERIAL_LIBRARY "microstrain_serial" CACHE INTERNAL "Name of the mark_as_advanced(MICROSTRAIN_SERIAL_LIBRARY) add_library(${MICROSTRAIN_SERIAL_LIBRARY} - "serial_port.h" - "serial_port.c" + "${CMAKE_CURRENT_LIST_DIR}/serial_port.h" + "${CMAKE_CURRENT_LIST_DIR}/serial_port.c" ) target_compile_features(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC c_std_11) @@ -22,5 +22,6 @@ target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_SERIAL_LI # # Installation # + include(microstrain_utilities) -microstrain_setup_library_install(${MICROSTRAIN_SERIAL_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) +microstrain_setup_library_install(${MICROSTRAIN_SERIAL_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/c/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt index dd068e6f6..6eedc41b6 100644 --- a/src/c/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -2,8 +2,8 @@ set(MICROSTRAIN_SOCKET_LIBRARY "microstrain_socket" CACHE INTERNAL "Name of the mark_as_advanced(MICROSTRAIN_SOCKET_LIBRARY) add_library(${MICROSTRAIN_SOCKET_LIBRARY} - "tcp_socket.h" - "tcp_socket.c" + "${CMAKE_CURRENT_LIST_DIR}/tcp_socket.h" + "${CMAKE_CURRENT_LIST_DIR}/tcp_socket.c" ) target_compile_features(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC c_std_11) @@ -26,5 +26,6 @@ target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_SOCKET_LI # # Installation # + include(microstrain_utilities) -microstrain_setup_library_install(${MICROSTRAIN_SOCKET_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) +microstrain_setup_library_install(${MICROSTRAIN_SOCKET_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index 6ccc52a9b..6d6437885 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -1,41 +1,50 @@ set(MIP_LIBRARY "mip" CACHE INTERNAL "Name of the MIP library") mark_as_advanced(MIP_LIBRARY) +include(microstrain_utilities) +microstrain_get_git_version(MIP_GIT_VERSION MIP_GIT_VERSION_CLEAN) +microstrain_extract_git_version(MIP_GIT_VERSION_CLEAN MIP_GIT_VERSION_MAJOR MIP_GIT_VERSION_MINOR MIP_GIT_VERSION_PATCH) + +# Generate the version header file +set(MIP_VERSION_IN_FILE "${CMAKE_CURRENT_LIST_DIR}/../../../cmake/mip_version.h.in") +set(MIP_VERSION_OUT_FILE "${CMAKE_CURRENT_LIST_DIR}/mip_version.h") +configure_file(${MIP_VERSION_IN_FILE} ${MIP_VERSION_OUT_FILE}) + # # Core MIP C library # add_library(${MIP_LIBRARY} - "${VERSION_OUT_FILE}" - - "mip_cmdqueue.c" - "mip_cmdqueue.h" - "mip_descriptors.c" - "mip_descriptors.h" - "mip_device_models.c" - "mip_device_models.h" - "mip_dispatch.c" - "mip_dispatch.h" - "mip_field.c" - "mip_field.h" - "mip_interface.c" - "mip_interface.h" - "mip_offsets.h" - "mip_packet.c" - "mip_packet.h" - "mip_parser.c" - "mip_parser.h" - "mip_result.c" - "mip_result.h" - "mip_types.h" - "mip_serialization.c" - "mip_serialization.h" - "definitions/common.c" - "definitions/common.h" - "mip_all.h" - - "utils/byte_ring.c" - "utils/byte_ring.h" + "${MIP_VERSION_OUT_FILE}" + + "${CMAKE_CURRENT_LIST_DIR}/mip_cmdqueue.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_cmdqueue.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_descriptors.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_descriptors.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_device_models.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_device_models.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_dispatch.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_dispatch.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_field.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_field.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_interface.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_interface.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_offsets.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_packet.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_packet.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_parser.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_parser.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_result.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_result.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_types.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_serialization.c" + "${CMAKE_CURRENT_LIST_DIR}/mip_serialization.h" + "${CMAKE_CURRENT_LIST_DIR}/definitions/common.c" + "${CMAKE_CURRENT_LIST_DIR}/definitions/common.h" + "${CMAKE_CURRENT_LIST_DIR}/mip_all.h" + + "${CMAKE_CURRENT_LIST_DIR}/utils/byte_ring.c" + "${CMAKE_CURRENT_LIST_DIR}/utils/byte_ring.h" ) target_compile_features(${MIP_LIBRARY} PUBLIC c_std_11) @@ -77,10 +86,12 @@ set(MIP_DEF_SOURCES ${MIP_DEFS}) list(TRANSFORM MIP_DEF_HEADERS APPEND ".h") list(TRANSFORM MIP_DEF_SOURCES APPEND ".c") list(APPEND MIP_DEF_SOURCES ${MIP_DEF_HEADERS}) -list(TRANSFORM MIP_DEF_SOURCES PREPEND "definitions/") +list(TRANSFORM MIP_DEF_SOURCES PREPEND "${CMAKE_CURRENT_LIST_DIR}/definitions/") if(MICROSTRAIN_CMAKE_DEBUG) - message("C definitions = ${MIP_DEF_SOURCES}") + set(INCLUDED_DEF_SOURCES ${MIP_DEF_SOURCES}) + list(TRANSFORM INCLUDED_DEF_SOURCES REPLACE "${CMAKE_CURRENT_LIST_DIR}/" "") + message("C definitions = ${INCLUDED_DEF_SOURCES}") endif() target_sources(${MIP_LIBRARY} PRIVATE ${MIP_DEF_SOURCES}) @@ -90,5 +101,6 @@ target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_LIBRARY}) # # Installation # + include(microstrain_utilities) -microstrain_setup_library_install(${MIP_LIBRARY} ${MIP_LIBRARY}) +microstrain_setup_library_install(${MIP_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index 2a9af847b..a66e00624 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -1,19 +1,20 @@ # microstrain_common is defined by the C api. target_sources(${MICROSTRAIN_COMMON_LIBRARY} PRIVATE - embedded_time.hpp - index.hpp - logging.hpp - platform.hpp - serialization.hpp - serialization/readwrite.hpp - serialization/serializer.hpp + "${CMAKE_CURRENT_LIST_DIR}/embedded_time.hpp" + "${CMAKE_CURRENT_LIST_DIR}/index.hpp" + "${CMAKE_CURRENT_LIST_DIR}/logging.hpp" + "${CMAKE_CURRENT_LIST_DIR}/platform.hpp" + "${CMAKE_CURRENT_LIST_DIR}/serialization.hpp" + "${CMAKE_CURRENT_LIST_DIR}/serialization/readwrite.hpp" + "${CMAKE_CURRENT_LIST_DIR}/serialization/serializer.hpp" ) target_compile_features(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC cxx_std_11) -target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${SRC_CPP_DIR}) +target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${MICROSTRAIN_SRC_CPP_DIR}) # # Installation # + include(microstrain_utilities) -microstrain_setup_install_headers(${MICROSTRAIN_COMMON_LIBRARY}) +microstrain_setup_install_headers(${MICROSTRAIN_COMMON_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/cpp/microstrain/connections/recording/CMakeLists.txt b/src/cpp/microstrain/connections/recording/CMakeLists.txt index cc9900131..c63eabd54 100644 --- a/src/cpp/microstrain/connections/recording/CMakeLists.txt +++ b/src/cpp/microstrain/connections/recording/CMakeLists.txt @@ -2,9 +2,9 @@ set(MICROSTRAIN_RECORDING_CONNECTION_LIBRARY "microstrain_recording_connection" mark_as_advanced(MICROSTRAIN_RECORDING_CONNECTION_LIBRARY) add_library(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} - recording_connection.cpp - recording_connection.hpp - ../connection.hpp + "${CMAKE_CURRENT_LIST_DIR}/recording_connection.cpp" + "${CMAKE_CURRENT_LIST_DIR}/recording_connection.hpp" + "${CMAKE_CURRENT_LIST_DIR}/../connection.hpp" ) target_compile_features(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} PUBLIC cxx_std_11) @@ -18,5 +18,6 @@ target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_RECORDING # # Installation # + include(microstrain_utilities) -microstrain_setup_library_install(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) +microstrain_setup_library_install(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/cpp/microstrain/connections/serial/CMakeLists.txt b/src/cpp/microstrain/connections/serial/CMakeLists.txt index efac71755..0ac119d42 100644 --- a/src/cpp/microstrain/connections/serial/CMakeLists.txt +++ b/src/cpp/microstrain/connections/serial/CMakeLists.txt @@ -1,8 +1,8 @@ # Add to existing C library. target_sources(${MICROSTRAIN_SERIAL_LIBRARY} PRIVATE - serial_connection.cpp - serial_connection.hpp - ../connection.hpp + "${CMAKE_CURRENT_LIST_DIR}/serial_connection.cpp" + "${CMAKE_CURRENT_LIST_DIR}/serial_connection.hpp" + "${CMAKE_CURRENT_LIST_DIR}/../connection.hpp" ) target_compile_features(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC cxx_std_11) @@ -10,5 +10,6 @@ target_compile_features(${MICROSTRAIN_SERIAL_LIBRARY} PUBLIC cxx_std_11) # # Installation # + include(microstrain_utilities) -microstrain_setup_install_headers(${MICROSTRAIN_SERIAL_LIBRARY}) +microstrain_setup_install_headers(${MICROSTRAIN_SERIAL_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/cpp/microstrain/connections/tcp/CMakeLists.txt b/src/cpp/microstrain/connections/tcp/CMakeLists.txt index 4dff797a9..1558d4822 100644 --- a/src/cpp/microstrain/connections/tcp/CMakeLists.txt +++ b/src/cpp/microstrain/connections/tcp/CMakeLists.txt @@ -1,8 +1,8 @@ # Add to existing C library. target_sources(${MICROSTRAIN_SOCKET_LIBRARY} PRIVATE - tcp_connection.cpp - tcp_connection.hpp - ../connection.hpp + "${CMAKE_CURRENT_LIST_DIR}/tcp_connection.cpp" + "${CMAKE_CURRENT_LIST_DIR}/tcp_connection.hpp" + "${CMAKE_CURRENT_LIST_DIR}/../connection.hpp" ) target_compile_features(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC cxx_std_11) @@ -10,5 +10,6 @@ target_compile_features(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC cxx_std_11) # # Installation # + include(microstrain_utilities) -microstrain_setup_install_headers(${MICROSTRAIN_SOCKET_LIBRARY}) +microstrain_setup_install_headers(${MICROSTRAIN_SOCKET_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/cpp/microstrain/extras/CMakeLists.txt b/src/cpp/microstrain/extras/CMakeLists.txt index daf38d654..a7205c431 100644 --- a/src/cpp/microstrain/extras/CMakeLists.txt +++ b/src/cpp/microstrain/extras/CMakeLists.txt @@ -1,12 +1,11 @@ set(MICROSTRAIN_EXTRAS_LIBRARY "microstrain_extras" CACHE INTERNAL "Name of the MicroStrain extras library") mark_as_advanced(MICROSTRAIN_EXTRAS_LIBRARY) -set(SOURCES - scope_helper.cpp - scope_helper.hpp +add_library(${MICROSTRAIN_EXTRAS_LIBRARY} + "${CMAKE_CURRENT_LIST_DIR}/scope_helper.cpp" + "${CMAKE_CURRENT_LIST_DIR}/scope_helper.hpp" ) -add_library(${MICROSTRAIN_EXTRAS_LIBRARY} ${SOURCES}) target_compile_features(${MICROSTRAIN_EXTRAS_LIBRARY} PUBLIC cxx_std_11) @@ -24,5 +23,6 @@ target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_EXTRAS_LI # # Installation # + include(microstrain_utilities) -microstrain_setup_library_install(${MICROSTRAIN_EXTRAS_LIBRARY} ${MICROSTRAIN_COMMON_LIBRARY}) +microstrain_setup_library_install(${MICROSTRAIN_EXTRAS_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index 2e33108a2..d3affcf04 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -1,17 +1,17 @@ set(MIP_INCLUDE_DIR "${CMAKE_CURRENT_LIST_DIR}/..") target_sources(${MIP_LIBRARY} PRIVATE - mip.hpp - mip_all.hpp - mip_cmdqueue.hpp - mip_descriptors.hpp - mip_field.hpp - mip_interface.hpp - mip_interface.cpp - mip_packet.hpp - mip_parser.hpp - mip_result.hpp - mip_serialization.hpp + "${CMAKE_CURRENT_LIST_DIR}/mip.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_all.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_cmdqueue.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_descriptors.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_field.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_interface.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_interface.cpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_packet.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_parser.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_result.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_serialization.hpp" ) target_compile_features(${MIP_LIBRARY} PUBLIC cxx_std_11) @@ -25,10 +25,12 @@ set(MIP_DEF_SOURCES ${MIP_DEFS}) list(TRANSFORM MIP_DEF_HEADERS APPEND ".hpp") list(TRANSFORM MIP_DEF_SOURCES APPEND ".cpp") list(APPEND MIP_DEF_SOURCES ${MIP_DEF_HEADERS}) -list(TRANSFORM MIP_DEF_SOURCES PREPEND "definitions/") +list(TRANSFORM MIP_DEF_SOURCES PREPEND "${CMAKE_CURRENT_LIST_DIR}/definitions/") if(MICROSTRAIN_CMAKE_DEBUG) - message("C++ definitions = ${MIP_DEF_SOURCES}") + set(INCLUDED_DEF_SOURCES ${MIP_DEF_SOURCES}) + list(TRANSFORM INCLUDED_DEF_SOURCES REPLACE "${CMAKE_CURRENT_LIST_DIR}/" "") + message("C++ definitions = ${INCLUDED_DEF_SOURCES}") endif() target_sources(${MIP_LIBRARY} PRIVATE ${MIP_DEF_SOURCES}) @@ -44,5 +46,6 @@ endif() # # Installation # + include(microstrain_utilities) -microstrain_setup_install_headers(${MIP_LIBRARY}) +microstrain_setup_install_headers(${MIP_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/cpp/mip/extras/CMakeLists.txt b/src/cpp/mip/extras/CMakeLists.txt index 71fd144ed..a638a321f 100644 --- a/src/cpp/mip/extras/CMakeLists.txt +++ b/src/cpp/mip/extras/CMakeLists.txt @@ -2,10 +2,10 @@ set(MIP_EXTRAS_LIBRARY "mip_extras" CACHE INTERNAL "Name of the MIP extras libra mark_as_advanced(MIP_EXTRAS_LIBRARY) add_library(${MIP_EXTRAS_LIBRARY} - composite_result.hpp - descriptor_id.hpp - firmware_version.cpp - firmware_version.hpp + "${CMAKE_CURRENT_LIST_DIR}/composite_result.hpp" + "${CMAKE_CURRENT_LIST_DIR}/descriptor_id.hpp" + "${CMAKE_CURRENT_LIST_DIR}/firmware_version.cpp" + "${CMAKE_CURRENT_LIST_DIR}/firmware_version.hpp" ) target_compile_features(${MIP_EXTRAS_LIBRARY} PUBLIC cxx_std_11) @@ -24,5 +24,6 @@ target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_EXTRAS_LIBRARY}) # # Installation # + include(microstrain_utilities) -microstrain_setup_library_install(${MIP_EXTRAS_LIBRARY} ${MIP_LIBRARY}) +microstrain_setup_library_install(${MIP_EXTRAS_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/src/cpp/mip/metadata/CMakeLists.txt b/src/cpp/mip/metadata/CMakeLists.txt index f2b2c0b7d..9efa6a844 100644 --- a/src/cpp/mip/metadata/CMakeLists.txt +++ b/src/cpp/mip/metadata/CMakeLists.txt @@ -6,20 +6,22 @@ get_target_property(MIP_DEFS ${MIP_LIBRARY} definitions) set(MIP_DEF_HEADERS ${MIP_DEFS}) list(TRANSFORM MIP_DEF_HEADERS APPEND ".hpp") -list(TRANSFORM MIP_DEF_HEADERS PREPEND "definitions/") +list(TRANSFORM MIP_DEF_HEADERS PREPEND "${CMAKE_CURRENT_LIST_DIR}/definitions/") if(MICROSTRAIN_CMAKE_DEBUG) - message("C++ metadata definitions = ${MIP_DEF_HEADERS}") + set(INCLUDED_DEF_HEADERS ${MIP_DEF_HEADERS}) + list(TRANSFORM INCLUDED_DEF_HEADERS REPLACE "${CMAKE_CURRENT_LIST_DIR}/" "") + message("C++ metadata definitions = ${INCLUDED_DEF_HEADERS}") endif() add_library(${MIP_METADATA_LIBRARY} - "mip_all_definitions.hpp" - "mip_definitions.hpp" - "mip_definitions.cpp" - "mip_metadata.hpp" - "mip_structures.hpp" - "mip_meta_utils.hpp" - "definitions/common.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_all_definitions.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_definitions.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_definitions.cpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_metadata.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_structures.hpp" + "${CMAKE_CURRENT_LIST_DIR}/mip_meta_utils.hpp" + "${CMAKE_CURRENT_LIST_DIR}/definitions/common.hpp" ${MIP_DEF_HEADERS} ) @@ -39,5 +41,6 @@ target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_METADATA_LIBRARY}) # # Installation # + include(microstrain_utilities) -microstrain_setup_library_install(${MIP_METADATA_LIBRARY} ${MIP_LIBRARY}) +microstrain_setup_library_install(${MIP_METADATA_LIBRARY} ${MICROSTRAIN_SRC_DIR}) diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 0c96aabe0..aced30acf 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -7,7 +7,7 @@ set(TEST_DIR "${CMAKE_CURRENT_LIST_DIR}") macro(add_mip_test name sources command) add_executable(${name} ${sources}) - target_include_directories(${name} PRIVATE ${SRC_DIR}) + target_include_directories(${name} PRIVATE ${MICROSTRAIN_SRC_DIR}) target_link_libraries(${name} ${MIP_LIBRARY}) add_test(${name} ${command} ${ARGN}) From 695a90d99768cf03cd1d8bf4d8007ae221c85b7d Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 6 Sep 2024 14:48:29 -0400 Subject: [PATCH 102/147] Added GNU install dirs for install process --- CMakeLists.txt | 2 +- cmake/microstrain_utilities.cmake | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d116afcd7..d71cba6f4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -52,7 +52,7 @@ option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip lib if(NOT DEFINED MIP_ENABLE_METADATA) include(check_metadata) - message("MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") + message(STATUS "MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") endif() option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" ${MIP_COMPILER_SUPPORTS_METADATA}) option(MIP_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ${MICROSTRAIN_ENABLE_EXTRAS}) diff --git a/cmake/microstrain_utilities.cmake b/cmake/microstrain_utilities.cmake index 57282ab3f..cef40db10 100644 --- a/cmake/microstrain_utilities.cmake +++ b/cmake/microstrain_utilities.cmake @@ -1,5 +1,9 @@ # Install the headers in their macro(microstrain_setup_install_headers LIBRARY ROOT_DIR) + if(UNIX AND NOT APPLE) + include(GNUInstallDirs) + endif() + # Only install headers that we build the source files for get_target_property(ALL_HEADERS ${LIBRARY} SOURCES) list(FILTER ALL_HEADERS INCLUDE REGEX "^.*\.(h|hpp)$") From bb0e59bc2fe4ee68e824e0ff9d02a6711ec7563b Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 6 Sep 2024 14:58:59 -0400 Subject: [PATCH 103/147] Updated Jenkins builds to only build release --- .devcontainer/docker_build.sh | 3 ++- Jenkinsfile | 8 ++++---- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/.devcontainer/docker_build.sh b/.devcontainer/docker_build.sh index 4fcff3308..187ba6fef 100755 --- a/.devcontainer/docker_build.sh +++ b/.devcontainer/docker_build.sh @@ -62,7 +62,8 @@ docker run \ mkdir ${docker_project_dir}/${build_dir_name}; \ cd ${docker_project_dir}/${build_dir_name}; \ cmake ${docker_project_dir} \ - -DMICROSTRAIN_BUILD_PACKAGE=ON; \ + -DMICROSTRAIN_BUILD_PACKAGE=ON \ + -DCMAKE_BUILD_TYPE=RELEASE; \ cmake --build . -j; \ cmake --build . --target package; \ " diff --git a/Jenkinsfile b/Jenkinsfile index 2f9bf5366..40e3cd696 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -56,8 +56,8 @@ pipeline { -T "v143" ` -DMICROSTRAIN_BUILD_DOCUMENTATION=ON ` -DMICROSTRAIN_BUILD_PACKAGE=ON - if(\$?) { cmake --build . } - if(\$?) { cmake --build . --target package } + if(\$?) { cmake --build . --config Release } + if(\$?) { cmake --build . --config Release --target package } if(\$?) { cmake --build . --target package_docs } """ archiveArtifacts artifacts: 'build_Win32/mipsdk_*' @@ -81,8 +81,8 @@ pipeline { -A "x64" ` -T "v143" ` -DMICROSTRAIN_BUILD_PACKAGE=ON - if(\$?) { cmake --build . } - if(\$?) { cmake --build . --target package } + if(\$?) { cmake --build . --config Release } + if(\$?) { cmake --build . --config Release --target package } """ archiveArtifacts artifacts: 'build_x64/mipsdk_*' } From 52dfed4f3a931c22157de8a4f8d5e287da9bcd2a Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 6 Sep 2024 17:45:00 -0400 Subject: [PATCH 104/147] Fix warnings about unrecognized escape sequence in generated comments. --- src/c/mip/definitions/commands_3dm.h | 4 ++-- src/c/mip/definitions/commands_filter.h | 4 ++-- src/c/mip/definitions/data_filter.h | 2 +- src/c/mip/definitions/data_sensor.h | 2 +- src/cpp/mip/definitions/commands_3dm.hpp | 4 ++-- src/cpp/mip/definitions/commands_filter.hpp | 4 ++-- src/cpp/mip/definitions/data_filter.hpp | 2 +- src/cpp/mip/definitions/data_sensor.hpp | 2 +- 8 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/c/mip/definitions/commands_3dm.h b/src/c/mip/definitions/commands_3dm.h index 3e2b5cfa0..e8fe54b3c 100644 --- a/src/c/mip/definitions/commands_3dm.h +++ b/src/c/mip/definitions/commands_3dm.h @@ -2084,7 +2084,7 @@ mip_cmd_result mip_3dm_default_mag_hard_iron_offset(mip_interface* device); /// The matrix is applied to the scaled magnetometer vector prior to output. /// /// The matrix is in row major order: -/// EQSTART M = \begin{bmatrix} 0 & 1 & 2 \\ 3 & 4 & 5 \\ 6 & 7 & 8 \end{bmatrix} EQEND +/// EQSTART M = \\begin{bmatrix} 0 & 1 & 2 \\\\ 3 & 4 & 5 \\\\ 6 & 7 & 8 \\end{bmatrix} EQEND /// /// ///@{ @@ -2287,7 +2287,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(mip_interfa /// EQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
/// EQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
///
-/// The matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND +/// The matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND /// The transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not /// be exactly equal to array used to set the transformation, but it is functionally equivalent.
///

diff --git a/src/c/mip/definitions/commands_filter.h b/src/c/mip/definitions/commands_filter.h index 770ce2a60..1fc6f8081 100644 --- a/src/c/mip/definitions/commands_filter.h +++ b/src/c/mip/definitions/commands_filter.h @@ -610,7 +610,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(mip_interface ///
/// Matrix element order:

/// -/// EQSTART T_{SEN}^{VEH} = \begin{bmatrix} 0 & 1 & 2\\ 3 & 4 & 5\\ 6 & 7 & 8 \end{bmatrix} EQEND +/// EQSTART T_{SEN}^{VEH} = \\begin{bmatrix} 0 & 1 & 2\\\\ 3 & 4 & 5\\\\ 6 & 7 & 8 \\end{bmatrix} EQEND /// ///

/// This rotation affects the following output quantities:

@@ -671,7 +671,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(mip_interface* ///
/// Quaternion element definition:

///
-/// EQSTART Q_{SEN}^{VEH} = \begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \end{bmatrix} EQEND +/// EQSTART Q_{SEN}^{VEH} = \\begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \\end{bmatrix} EQEND ///

/// This rotation affects the following output quantities:

/// IMU:
diff --git a/src/c/mip/definitions/data_filter.h b/src/c/mip/definitions/data_filter.h index c1df6518b..b88f2345c 100644 --- a/src/c/mip/definitions/data_filter.h +++ b/src/c/mip/definitions/data_filter.h @@ -356,7 +356,7 @@ bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field_view /// EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
/// EQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
///
-/// The matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND +/// The matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND /// ///@{ diff --git a/src/c/mip/definitions/data_sensor.h b/src/c/mip/definitions/data_sensor.h index c1312f828..ff79e525c 100644 --- a/src/c/mip/definitions/data_sensor.h +++ b/src/c/mip/definitions/data_sensor.h @@ -280,7 +280,7 @@ bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field_view* fie /// EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
/// EQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
///
-/// The matrix elements are stored is row-major order: EQSTART M = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND +/// The matrix elements are stored is row-major order: EQSTART M = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND /// ///@{ diff --git a/src/cpp/mip/definitions/commands_3dm.hpp b/src/cpp/mip/definitions/commands_3dm.hpp index 8a335d16e..f2f1e90be 100644 --- a/src/cpp/mip/definitions/commands_3dm.hpp +++ b/src/cpp/mip/definitions/commands_3dm.hpp @@ -3380,7 +3380,7 @@ TypedResult defaultMagHardIronOffset(C::mip_interface& device /// The matrix is applied to the scaled magnetometer vector prior to output. /// /// The matrix is in row major order: -/// EQSTART M = \begin{bmatrix} 0 & 1 & 2 \\ 3 & 4 & 5 \\ 6 & 7 & 8 \end{bmatrix} EQEND +/// EQSTART M = \\begin{bmatrix} 0 & 1 & 2 \\\\ 3 & 4 & 5 \\\\ 6 & 7 & 8 \\end{bmatrix} EQEND /// /// ///@{ @@ -3763,7 +3763,7 @@ TypedResult defaultSensor2VehicleTransformQua /// EQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
/// EQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
///
-/// The matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND +/// The matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND /// The transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not /// be exactly equal to array used to set the transformation, but it is functionally equivalent.
///

diff --git a/src/cpp/mip/definitions/commands_filter.hpp b/src/cpp/mip/definitions/commands_filter.hpp index 1a62baeee..b175b27ec 100644 --- a/src/cpp/mip/definitions/commands_filter.hpp +++ b/src/cpp/mip/definitions/commands_filter.hpp @@ -876,7 +876,7 @@ TypedResult defaultSensorToVehicleRotationEuler(C: ///
/// Matrix element order:

/// -/// EQSTART T_{SEN}^{VEH} = \begin{bmatrix} 0 & 1 & 2\\ 3 & 4 & 5\\ 6 & 7 & 8 \end{bmatrix} EQEND +/// EQSTART T_{SEN}^{VEH} = \\begin{bmatrix} 0 & 1 & 2\\\\ 3 & 4 & 5\\\\ 6 & 7 & 8 \\end{bmatrix} EQEND /// ///

/// This rotation affects the following output quantities:

@@ -982,7 +982,7 @@ TypedResult defaultSensorToVehicleRotationDcm(C::mip ///
/// Quaternion element definition:

///
-/// EQSTART Q_{SEN}^{VEH} = \begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \end{bmatrix} EQEND +/// EQSTART Q_{SEN}^{VEH} = \\begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \\end{bmatrix} EQEND ///

/// This rotation affects the following output quantities:

/// IMU:
diff --git a/src/cpp/mip/definitions/data_filter.hpp b/src/cpp/mip/definitions/data_filter.hpp index f2ef29d4c..d08d42c3b 100644 --- a/src/cpp/mip/definitions/data_filter.hpp +++ b/src/cpp/mip/definitions/data_filter.hpp @@ -494,7 +494,7 @@ struct AttitudeQuaternion /// EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
/// EQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
///
-/// The matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND +/// The matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND /// ///@{ diff --git a/src/cpp/mip/definitions/data_sensor.hpp b/src/cpp/mip/definitions/data_sensor.hpp index 832a659ea..4e1a28bd2 100644 --- a/src/cpp/mip/definitions/data_sensor.hpp +++ b/src/cpp/mip/definitions/data_sensor.hpp @@ -459,7 +459,7 @@ struct DeltaVelocity /// EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
/// EQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
///
-/// The matrix elements are stored is row-major order: EQSTART M = \begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \end{bmatrix} EQEND +/// The matrix elements are stored is row-major order: EQSTART M = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND /// ///@{ From 5b9d43421164b2c6ceace25c1c663c36ebcb0699 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Mon, 9 Sep 2024 12:23:44 -0400 Subject: [PATCH 105/147] Documentation cleanup (warnings) Attempting to fix Jenkins Windows builds --- Jenkinsfile | 40 ++++++++++++------- src/c/microstrain/common/logging.h | 14 +++---- src/c/mip/mip_field.c | 2 - .../recording/recording_connection.cpp | 8 ++-- .../connections/serial/serial_connection.cpp | 6 +-- .../connections/serial/serial_connection.hpp | 4 +- .../connections/tcp/tcp_connection.cpp | 4 +- .../connections/tcp/tcp_connection.hpp | 4 +- src/cpp/mip/mip_field.hpp | 4 +- src/cpp/mip/mip_interface.cpp | 10 +++-- src/cpp/mip/mip_interface.hpp | 16 ++++---- 11 files changed, 62 insertions(+), 50 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 40e3cd696..e54670cd5 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -38,6 +38,26 @@ pipeline { stage('Build') { // Run all the builds in parallel parallel { + stage('Documentation') { + agent { label 'windows10' } + options { + skipDefaultCheckout() + timeout(time: 5, activity: true, unit: 'MINUTES') + } + steps { + script { + checkoutRepo() + env.setProperty('BRANCH_NAME', branchName()) + powershell """ + mkdir build_docs + cd build_docs + cmake .. -DMICROSTRAIN_BUILD_DOCUMENTATION=ON + cmake --build . --target package_docs + """ + archiveArtifacts artifacts: 'build_docs/mipsdk_*' + } + } + } stage('Windows x86') { agent { label 'windows10' } options { @@ -51,14 +71,9 @@ pipeline { powershell """ mkdir build_Win32 cd build_Win32 - cmake .. ` - -A "Win32" ` - -T "v143" ` - -DMICROSTRAIN_BUILD_DOCUMENTATION=ON ` - -DMICROSTRAIN_BUILD_PACKAGE=ON - if(\$?) { cmake --build . --config Release } - if(\$?) { cmake --build . --config Release --target package } - if(\$?) { cmake --build . --target package_docs } + cmake .. -A "Win32" -DMICROSTRAIN_BUILD_PACKAGE=ON + cmake --build . --config Release + cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_Win32/mipsdk_*' } @@ -77,12 +92,9 @@ pipeline { powershell """ mkdir build_x64 cd build_x64 - cmake .. ` - -A "x64" ` - -T "v143" ` - -DMICROSTRAIN_BUILD_PACKAGE=ON - if(\$?) { cmake --build . --config Release } - if(\$?) { cmake --build . --config Release --target package } + cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON + cmake --build . --config Release + cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_x64/mipsdk_*' } diff --git a/src/c/microstrain/common/logging.h b/src/c/microstrain/common/logging.h index 7110a58e4..986be635a 100644 --- a/src/c/microstrain/common/logging.h +++ b/src/c/microstrain/common/logging.h @@ -66,7 +66,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MicroStrain SDK. Prefer specific /// log level functions like MICROSTRAIN_LOG_INFO, etc. when possible. -///@copydetails microstrain::C::microstrain_log_callback +///@copydetails microstrain_log_callback /// #ifdef MICROSTRAIN_ENABLE_LOGGING #define MICROSTRAIN_LOG_LOG(level, ...) microstrain_logging_log(level, __VA_ARGS__) @@ -93,7 +93,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MicroStrain SDK at error level -///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL +///@copydetails MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_ERROR #define MICROSTRAIN_LOG_ERROR(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_ERROR, __VA_ARGS__) #else @@ -102,7 +102,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MicroStrain SDK at warn level -///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL +///@copydetails MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_WARN #define MICROSTRAIN_LOG_WARN(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_WARN, __VA_ARGS__) #else @@ -111,7 +111,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MicroStrain SDK at info level -///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL +///@copydetails MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_INFO #define MICROSTRAIN_LOG_INFO(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_INFO, __VA_ARGS__) #else @@ -120,7 +120,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MicroStrain SDK at debug level -///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL +///@copydetails MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_DEBUG #define MICROSTRAIN_LOG_DEBUG(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_DEBUG, __VA_ARGS__) #else @@ -129,7 +129,7 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); //////////////////////////////////////////////////////////////////////////////// ///@brief Helper macro used to log data inside the MicroStrain SDK at trace level -///@copydetails microstrain::C::MICROSTRAIN_LOG_FATAL +///@copydetails MICROSTRAIN_LOG_FATAL #if MICROSTRAIN_LOGGING_MAX_LEVEL >= MICROSTRAIN_LOG_LEVEL_TRACE #define MICROSTRAIN_LOG_TRACE(...) MICROSTRAIN_LOG_LOG(MICROSTRAIN_LOG_LEVEL_TRACE, __VA_ARGS__) #else @@ -142,4 +142,4 @@ void microstrain_logging_log(microstrain_log_level level, const char* fmt, ...); #ifdef __cplusplus } // extern "C" -#endif \ No newline at end of file +#endif diff --git a/src/c/mip/mip_field.c b/src/c/mip/mip_field.c index d2d11ce31..72a4e9e4c 100644 --- a/src/c/mip/mip_field.c +++ b/src/c/mip/mip_field.c @@ -25,8 +25,6 @@ ///@param payload_length /// The length of the payload. Cannot exceed MIP_FIELD_PAYLOAD_LENGTH_MAX. /// -///@returns A %mip_field initialized with the specified values. -/// void mip_field_init(mip_field_view* field, uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) { assert( payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX ); diff --git a/src/cpp/microstrain/connections/recording/recording_connection.cpp b/src/cpp/microstrain/connections/recording/recording_connection.cpp index b5f842344..f3f7fd2a4 100644 --- a/src/cpp/microstrain/connections/recording/recording_connection.cpp +++ b/src/cpp/microstrain/connections/recording/recording_connection.cpp @@ -33,14 +33,14 @@ bool RecordingConnection::sendToDevice(const uint8_t* data, size_t length) } ///@copydoc microstrain::Connection::recvFromDevice -bool RecordingConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* count_out, EmbeddedTimestamp* timestamp_out) +bool RecordingConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) { - const bool ok = mConnection->recvFromDevice(buffer, max_length, wait_time_ms, count_out, timestamp_out); + const bool ok = mConnection->recvFromDevice(buffer, max_length, wait_time_ms, length_out, timestamp_out); if (ok && mRecvFile != nullptr) { - mRecvFile->write(reinterpret_cast(buffer), static_cast(*count_out)); - mRecvFileWritten += *count_out; + mRecvFile->write(reinterpret_cast(buffer), static_cast(*length_out)); + mRecvFileWritten += *length_out; } return ok; diff --git a/src/cpp/microstrain/connections/serial/serial_connection.cpp b/src/cpp/microstrain/connections/serial/serial_connection.cpp index e34973e8e..54e7e1edc 100644 --- a/src/cpp/microstrain/connections/serial/serial_connection.cpp +++ b/src/cpp/microstrain/connections/serial/serial_connection.cpp @@ -55,11 +55,11 @@ bool SerialConnection::disconnect() ///@copydoc microstrain::Connection::recvFromDevice -bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, EmbeddedTimestamp* timestamp) +bool SerialConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) { - *timestamp = std::chrono::duration_cast(std::chrono::steady_clock::now().time_since_epoch()).count(); + *timestamp_out = std::chrono::duration_cast(std::chrono::steady_clock::now().time_since_epoch()).count(); - return serial_port_read(&mPort, buffer, max_length, wait_time, length_out); + return serial_port_read(&mPort, buffer, max_length, wait_time_ms, length_out); } ///@copydoc microstrain::Connection::sendToDevice diff --git a/src/cpp/microstrain/connections/serial/serial_connection.hpp b/src/cpp/microstrain/connections/serial/serial_connection.hpp index b68d2fb6e..cc1af1df9 100644 --- a/src/cpp/microstrain/connections/serial/serial_connection.hpp +++ b/src/cpp/microstrain/connections/serial/serial_connection.hpp @@ -27,7 +27,7 @@ class SerialConnection : public microstrain::Connection SerialConnection(std::string portName, uint32_t baudrate); ~SerialConnection(); - bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, EmbeddedTimestamp* timestamp_out) final; + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) final; bool sendToDevice(const uint8_t* data, size_t length) final; bool isConnected() const override; @@ -65,4 +65,4 @@ class UsbSerialConnection : public SerialConnection //////////////////////////////////////////////////////////////////////////////// } // namespace connections -} // namespace microstrain \ No newline at end of file +} // namespace microstrain diff --git a/src/cpp/microstrain/connections/tcp/tcp_connection.cpp b/src/cpp/microstrain/connections/tcp/tcp_connection.cpp index b77fa2cf5..80a2b78bc 100644 --- a/src/cpp/microstrain/connections/tcp/tcp_connection.cpp +++ b/src/cpp/microstrain/connections/tcp/tcp_connection.cpp @@ -55,7 +55,7 @@ bool TcpConnection::disconnect() return tcp_socket_close(&mSocket); } -///@copydoc microstrain::Connection::sendToDevice +///@copydoc microstrain::Connection::recvFromDevice bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) { (void)wait_time_ms; // Not used, timeout is always fixed @@ -65,7 +65,7 @@ bool TcpConnection::recvFromDevice(uint8_t* buffer, size_t max_length, unsigned return tcp_socket_recv(&mSocket, buffer, max_length, length_out); } -///@copydoc microstrain::Connection::recvFromDevice +///@copydoc microstrain::Connection::sendToDevice bool TcpConnection::sendToDevice(const uint8_t* data, size_t length) { size_t length_out; diff --git a/src/cpp/microstrain/connections/tcp/tcp_connection.hpp b/src/cpp/microstrain/connections/tcp/tcp_connection.hpp index 67cf5f407..60efb4000 100644 --- a/src/cpp/microstrain/connections/tcp/tcp_connection.hpp +++ b/src/cpp/microstrain/connections/tcp/tcp_connection.hpp @@ -29,7 +29,7 @@ class TcpConnection : public microstrain::Connection TcpConnection(const TcpConnection&) = delete; TcpConnection& operator=(const TcpConnection&) = delete; - bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time, size_t* length_out, EmbeddedTimestamp* timestamp_out) override; + bool recvFromDevice(uint8_t* buffer, size_t max_length, unsigned int wait_time_ms, size_t* length_out, EmbeddedTimestamp* timestamp_out) override; bool sendToDevice(const uint8_t* data, size_t length) override; bool isConnected() const override; @@ -56,4 +56,4 @@ class TcpConnection : public microstrain::Connection //////////////////////////////////////////////////////////////////////////////// }; // namespace microstrain -}; // namespace connections \ No newline at end of file +}; // namespace connections diff --git a/src/cpp/mip/mip_field.hpp b/src/cpp/mip/mip_field.hpp index 0bb460fed..ca3b9bfc0 100644 --- a/src/cpp/mip/mip_field.hpp +++ b/src/cpp/mip/mip_field.hpp @@ -67,9 +67,9 @@ class FieldView : public C::mip_field_view ///@copydoc mip_field_is_valid bool isValid() const { return C::mip_field_is_valid(this); } - ///@copydoc mip_field_next_after + ///@copybrief mip_field_next_after FieldView nextAfter() const { return C::mip_field_next_after(this); } - ///@copydoc mip_field_next + ///@copybrief mip_field_next bool next() { return C::mip_field_next(this); } // diff --git a/src/cpp/mip/mip_interface.cpp b/src/cpp/mip/mip_interface.cpp index cca500369..f21627dea 100644 --- a/src/cpp/mip/mip_interface.cpp +++ b/src/cpp/mip/mip_interface.cpp @@ -20,10 +20,11 @@ namespace mip { /// ///@brief Receives bytes from the device /// -///@param buffer Buffer to store the received data in -///@param max_length Max number of bytes that can be read. Should be at most the length of buffer. -///@param length_out Number of bytes actually read. -///@param timestamp Timestamp of when the data was received +///@param buffer Buffer to store the received data in +///@param max_length Max number of bytes that can be read. Should be at most the length of buffer. +///@param wait_time_ms Time to wait for data in milliseconds. +///@param length_out Number of bytes actually read. +///@param timestamp_out Timestamp of when the data was received //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// @@ -32,6 +33,7 @@ namespace mip { ///@note This sets the interface's user pointer to this connection object. /// ///@param device Device to configure. +///@param conn The connection to set /// void connect_interface(mip::Interface& device, microstrain::Connection& conn) { diff --git a/src/cpp/mip/mip_interface.hpp b/src/cpp/mip/mip_interface.hpp index a247706b7..5b4f3de10 100644 --- a/src/cpp/mip/mip_interface.hpp +++ b/src/cpp/mip/mip_interface.hpp @@ -588,14 +588,14 @@ void Interface::registerFieldCallback(C::mip_dispatch_handler& handler, uint8_t /// function pointer. /// ///@param handler -/// This must exist as long as the hander remains registered. +/// This must exist as long as the handler remains registered. /// ///@param userData /// Optional data to pass to the callback function. /// ///@param descriptorSet /// If specified, overrides the descriptor set. Intended to be used with -/// with shared data quantities. +/// shared data quantities. /// /// Example usage: ///@code{.cpp} @@ -647,14 +647,14 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* use /// function pointer. /// ///@param handler -/// This must exist as long as the hander remains registered. +/// This must exist as long as the handler remains registered. /// ///@param userData /// Optional data to pass to the callback function. /// ///@param descriptorSet /// If specified, overrides the descriptor set. Intended to be used with -/// with shared data quantities. +/// shared data quantities. /// /// Example usage: ///@code{.cpp} @@ -706,7 +706,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* use /// member function pointer. /// ///@param handler -/// This must exist as long as the hander remains registered. +/// This must exist as long as the handler remains registered. /// ///@param object /// A pointer to the object. The object must exist while the handler @@ -714,7 +714,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, void* use /// ///@param descriptorSet /// If specified, overrides the descriptor set. Intended to be used with -/// with shared data quantities. +/// shared data quantities. /// /// Example usage: ///@code{.cpp} @@ -767,7 +767,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* o /// member function pointer. /// ///@param handler -/// This must exist as long as the hander remains registered. +/// This must exist as long as the handler remains registered. /// ///@param object /// A pointer to the object. The object must exist while the handler @@ -775,7 +775,7 @@ void Interface::registerDataCallback(C::mip_dispatch_handler& handler, Object* o /// ///@param descriptorSet /// If specified, overrides the descriptor set. Intended to be used with -/// with shared data quantities. +/// shared data quantities. /// /// Example usage: ///@code{.cpp} From 96be273f5388a0d7fecc1954198af208a50f3e7d Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Mon, 9 Sep 2024 13:25:07 -0400 Subject: [PATCH 106/147] Windows Jenkins package fix Configure CMake 2x on Windows for proper packaging --- Jenkinsfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index e54670cd5..5c3447317 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -72,7 +72,7 @@ pipeline { mkdir build_Win32 cd build_Win32 cmake .. -A "Win32" -DMICROSTRAIN_BUILD_PACKAGE=ON - cmake --build . --config Release + cmake .. -A "Win32" -DMICROSTRAIN_BUILD_PACKAGE=ON # cmake does not configure correctly on the first pass for install cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_Win32/mipsdk_*' @@ -93,7 +93,7 @@ pipeline { mkdir build_x64 cd build_x64 cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON - cmake --build . --config Release + cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON # cmake does not configure correctly on the first pass for install cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_x64/mipsdk_*' From 05c80b063e58d4a1a8cdbe143d1c0bff870b579c Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Mon, 9 Sep 2024 14:08:29 -0400 Subject: [PATCH 107/147] Fixed Mac builds Span doesn't work with forward declarations (MIP metadata) --- src/cpp/mip/metadata/mip_structures.hpp | 102 ++++++++++++------------ 1 file changed, 51 insertions(+), 51 deletions(-) diff --git a/src/cpp/mip/metadata/mip_structures.hpp b/src/cpp/mip/metadata/mip_structures.hpp index fb79873e6..6db3628c9 100644 --- a/src/cpp/mip/metadata/mip_structures.hpp +++ b/src/cpp/mip/metadata/mip_structures.hpp @@ -10,12 +10,12 @@ namespace mip::metadata { -struct EnumInfo; -struct BitfieldInfo; -struct UnionInfo; -struct StructInfo; -struct FieldInfo; -struct ParameterInfo; +//struct EnumInfo; +//struct BitfieldInfo; +//struct UnionInfo; +//struct StructInfo; +//struct FieldInfo; +//struct ParameterInfo; enum class Type @@ -78,7 +78,7 @@ struct EnumInfo struct BitfieldInfo : public EnumInfo {}; -struct ParameterInfo; // Defined below +//struct ParameterInfo; // Defined below struct FuncBits { @@ -109,6 +109,50 @@ static constexpr inline FuncBits ALL_FUNCTIONS = {true,true,true,true,true}; static constexpr inline FuncBits NO_FUNCTIONS = {false, false, false, false, false}; + struct ParameterInfo + { + struct Count + { + constexpr Count() = default; + constexpr Count(uint8_t n) : count(n) {} + constexpr Count(uint8_t n, microstrain::Id id) : count(n), paramIdx(id) {} + + uint8_t count = 1; ///< Fixed size if paramIdx unassigned. + microstrain::Id paramIdx = {}; ///< If assigned, specifies parameter that holds the actual runtime count. + + constexpr bool isFixed() const { return count > 0 && !paramIdx.isAssigned(); } + constexpr bool hasCounter() const { return paramIdx.isAssigned(); } + }; + + struct Condition + { + enum class Type : uint8_t + { + NONE = 0, ///< No condition, member always valid + ENUM = 1, ///< Enum value selector (e.g. for parameters in unions) + //PRODUCT = 2, ///< Depends on product variant (TBD) + //OPTIONAL = 2, ///< Parameter can be omitted (TBD) + }; + + Type type = Type::NONE; ///< Type of condition. + microstrain::Id paramIdx = {}; ///< Index of enum parameter identifying whether this parameter is enabled. + uint16_t value = 0; ///< Value of the enum parameter which activates this parameter. + + constexpr bool hasCondition() const { return type != Type::NONE; } + }; + + using Accessor = void* (*)(void*); + + const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). + const char* docs = nullptr; ///< Human-readable documentation. + TypeInfo type; ///< Data type. + Accessor accessor = nullptr; ///< Obtains a reference to the member variable. + FuncBits functions; ///< This parameter is required for the specified function selectors. + Count count; ///< Number of instances for arrays. + Condition condition; ///< For conditionally-enabled parameters like those in unions. + }; + + struct StructInfo { const char* name = nullptr; @@ -168,48 +212,4 @@ constexpr size_t sizeForBasicType(Type type, const void* info=nullptr) constexpr size_t sizeForBasicType(const TypeInfo& type) { return sizeForBasicType(type.type, type.infoPtr); } -struct ParameterInfo -{ - struct Count - { - constexpr Count() = default; - constexpr Count(uint8_t n) : count(n) {} - constexpr Count(uint8_t n, microstrain::Id id) : count(n), paramIdx(id) {} - - uint8_t count = 1; ///< Fixed size if paramIdx unassigned. - microstrain::Id paramIdx = {}; ///< If assigned, specifies parameter that holds the actual runtime count. - - constexpr bool isFixed() const { return count > 0 && !paramIdx.isAssigned(); } - constexpr bool hasCounter() const { return paramIdx.isAssigned(); } - }; - - struct Condition - { - enum class Type : uint8_t - { - NONE = 0, ///< No condition, member always valid - ENUM = 1, ///< Enum value selector (e.g. for parameters in unions) - //PRODUCT = 2, ///< Depends on product variant (TBD) - //OPTIONAL = 2, ///< Parameter can be omitted (TBD) - }; - - Type type = Type::NONE; ///< Type of condition. - microstrain::Id paramIdx = {}; ///< Index of enum parameter identifying whether this parameter is enabled. - uint16_t value = 0; ///< Value of the enum parameter which activates this parameter. - - constexpr bool hasCondition() const { return type != Type::NONE; } - }; - - using Accessor = void* (*)(void*); - - const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). - const char* docs = nullptr; ///< Human-readable documentation. - TypeInfo type; ///< Data type. - Accessor accessor = nullptr; ///< Obtains a reference to the member variable. - FuncBits functions; ///< This parameter is required for the specified function selectors. - Count count; ///< Number of instances for arrays. - Condition condition; ///< For conditionally-enabled parameters like those in unions. -}; - - } // namespace mip::metadata From e1c9242d519e3bea8ef9f78b607fe252b7294a61 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Mon, 9 Sep 2024 14:13:41 -0400 Subject: [PATCH 108/147] Fixed Mac package install Mac also doesn't configure CMake correctly on first pass for install --- Jenkinsfile | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 5c3447317..d80db4d78 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -173,9 +173,8 @@ pipeline { sh ''' mkdir build_mac_arm64 cd build_mac_arm64 - cmake .. \ - -DMICROSTRAIN_BUILD_PACKAGE=ON \ - -DCMAKE_BUILD_TYPE=RELEASE + cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE + cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE # cmake does not configure correctly on the first pass for install cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' @@ -196,9 +195,8 @@ pipeline { sh ''' mkdir build_mac_intel cd build_mac_intel - cmake .. \ - -DMICROSTRAIN_BUILD_PACKAGE=ON \ - -DCMAKE_BUILD_TYPE=RELEASE + cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE + cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE # cmake does not configure correctly on the first pass for install cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' From 1561c5e6f64b357646deb2199d0cbe558be4f42a Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 9 Sep 2024 16:04:31 -0400 Subject: [PATCH 109/147] Update metadata files from definitions (title field "None"). --- .../mip/metadata/definitions/commands_3dm.hpp | 120 +++++++++--------- .../metadata/definitions/commands_aiding.hpp | 6 +- .../metadata/definitions/commands_base.hpp | 12 +- .../metadata/definitions/commands_filter.hpp | 86 ++++++------- .../metadata/definitions/commands_gnss.hpp | 24 ++-- .../mip/metadata/definitions/commands_rtk.hpp | 28 ++-- .../metadata/definitions/commands_system.hpp | 4 +- .../mip/metadata/definitions/data_filter.hpp | 82 ++++++------ .../mip/metadata/definitions/data_gnss.hpp | 38 +++--- .../mip/metadata/definitions/data_sensor.hpp | 34 ++--- .../mip/metadata/definitions/data_shared.hpp | 18 +-- .../mip/metadata/definitions/data_system.hpp | 8 +- 12 files changed, 230 insertions(+), 230 deletions(-) diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index 5205ee054..81476866b 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -47,7 +47,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollImuMessage", - /* .title = */ "None", + /* .title = */ "poll_imu_message", /* .docs = */ "Poll the device for an IMU message with the specified format\n\nThis function polls for an IMU message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set IMU Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an IMU Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -94,7 +94,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollGnssMessage", - /* .title = */ "None", + /* .title = */ "poll_gnss_message", /* .docs = */ "Poll the device for an GNSS message with the specified format\n\nThis function polls for a GNSS message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set GNSS Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a GNSS Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -141,7 +141,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollFilterMessage", - /* .title = */ "None", + /* .title = */ "poll_filter_message", /* .docs = */ "Poll the device for an Estimation Filter message with the specified format\n\nThis function polls for an Estimation Filter message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Estimation Filter Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as an Estimation Filter Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -179,7 +179,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuMessageFormat::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -218,7 +218,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuMessageFormat", - /* .title = */ "None", + /* .title = */ "imu_message_format", /* .docs = */ "Set, read, or save the format of the IMU data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -256,7 +256,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpsMessageFormat::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -295,7 +295,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpsMessageFormat", - /* .title = */ "None", + /* .title = */ "gps_message_format", /* .docs = */ "Set, read, or save the format of the GNSS data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -333,7 +333,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FilterMessageFormat::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -372,7 +372,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FilterMessageFormat", - /* .title = */ "None", + /* .title = */ "filter_message_format", /* .docs = */ "Set, read, or save the format of the Estimation Filter data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -401,7 +401,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuGetBaseRate::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -447,7 +447,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpsGetBaseRate::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -493,7 +493,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FilterGetBaseRate::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -566,7 +566,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PollData", - /* .title = */ "None", + /* .title = */ "poll_data", /* .docs = */ "Poll the device for a message with the specified descriptor set and format.\n\nThis function polls for a message using the provided format. The resulting message\nwill maintain the order of descriptors sent in the command and any unrecognized\ndescriptors are ignored. If the format is not provided, the device will attempt to use the\nstored format (set with the Set Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as a normal Data packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -604,7 +604,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GetBaseRate::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -680,7 +680,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MessageFormat::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -728,7 +728,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MessageFormat", - /* .title = */ "None", + /* .title = */ "message_format", /* .docs = */ "Set, read, or save the format for a given data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -875,7 +875,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::NmeaPollData", - /* .title = */ "None", + /* .title = */ "nmea_poll_data", /* .docs = */ "Poll the device for a NMEA message with the specified format.\n\nThis function polls for a NMEA message using the provided format.\nIf the format is not provided, the device will attempt to use the\nstored format (set with the Set NMEA Message Format command.) If no format is provided\nand there is no stored format, the device will respond with a NACK. The reply packet contains\nan ACK/NACK field. The polled data packet is sent separately as normal NMEA messages.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -913,7 +913,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::NmeaMessageFormat::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -952,7 +952,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::NmeaMessageFormat", - /* .title = */ "None", + /* .title = */ "nmea_message_format", /* .docs = */ "Set, read, or save the NMEA message format.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -974,7 +974,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::DeviceSettings", - /* .title = */ "None", + /* .title = */ "device_settings", /* .docs = */ "Save, Load, or Reset to Default the values for all device settings.\n\nWhen a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory.\n\nThis command should have a long timeout as it may take up to 1 second to complete.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1003,7 +1003,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::UartBaudrate::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1033,7 +1033,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::UartBaudrate", - /* .title = */ "None", + /* .title = */ "uart_baudrate", /* .docs = */ "Read, Save, Load, or Reset to Default the baud rate of the main communication channel.\n\nFor all functions except 0x01 (use new settings), the new baud rate value is ignored.\nPlease see the device user manual for supported baud rates.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1091,7 +1091,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::FactoryStreaming", - /* .title = */ "None", + /* .title = */ "factory_streaming", /* .docs = */ "Configures the device for recording data for technical support.\n\nThis command will configure all available data streams to predefined\nformats designed to be used with technical support.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1129,7 +1129,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::DatastreamControl::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1168,7 +1168,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::DatastreamControl", - /* .title = */ "None", + /* .title = */ "datastream_control", /* .docs = */ "Enable/disable the selected data stream.\n\nEach data stream (descriptor set) can be enabled or disabled.\nThe default for the device is all streams enabled.\nFor all functions except 0x01 (use new setting),\nthe new enable flag value is ignored and can be omitted.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1326,7 +1326,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ConstellationSettings::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1374,7 +1374,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ConstellationSettings", - /* .title = */ "None", + /* .title = */ "constellation_settings", /* .docs = */ "This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation.\n\nMaximum number of tracking channels to use (total for all constellations):\n0 to max_channels_available (from reply message)\n\nFor each constellation you wish to use, include a ConstellationSettings struct. Note the following:\n\nTotal number of tracking channels (sum of 'reserved_channels' for all constellations) must be <= 32:\n0 -> 32 Number of reserved channels\n0 -> 32 Max number of channels (>= reserved channels)\n\nThe factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3.\n\nWarning: SBAS functionality shall not be used in 'safety of life' applications!\nWarning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK.\nWarning: You cannot enable GLONASS and BeiDou at the same time.\nNote: Enabling SBAS and QZSS augments GPS accuracy.\nNote: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1450,7 +1450,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssSbasSettings::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1564,7 +1564,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssAssistedFix::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1650,7 +1650,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssTimeAssistance::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1698,7 +1698,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GnssTimeAssistance", - /* .title = */ "None", + /* .title = */ "gnss_time_assistance", /* .docs = */ "Provide the GNSS subsystem with initial time information.\n\nThis message is required immediately after power up if GNSS Assist was enabled when the device was powered off.\nThis will initialize the subsystem clock to help reduce the time to first fix (TTFF).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1763,7 +1763,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ImuLowpassFilter::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1880,7 +1880,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PpsSource::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1910,7 +1910,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::PpsSource", - /* .title = */ "None", + /* .title = */ "pps_source", /* .docs = */ "Controls the Pulse Per Second (PPS) source.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2041,7 +2041,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpioConfig::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2136,7 +2136,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GpioState::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2241,7 +2241,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Odometer::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2398,7 +2398,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GetEventSupport::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2486,7 +2486,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::EventControl::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2617,7 +2617,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GetEventTriggerStatus::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2727,7 +2727,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GetEventActionStatus::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3029,7 +3029,7 @@ struct MetadataFor static constexpr inline StructInfo value = { /* .name = */ "Parameters", - /* .title = */ "None", + /* .title = */ "Parameters", /* .docs = */ "", /* .parameters = */ parameters, }; @@ -3072,7 +3072,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::EventTrigger::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3287,7 +3287,7 @@ struct MetadataFor static constexpr inline StructInfo value = { /* .name = */ "Parameters", - /* .title = */ "None", + /* .title = */ "Parameters", /* .docs = */ "", /* .parameters = */ parameters, }; @@ -3339,7 +3339,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::EventAction::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3425,7 +3425,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::AccelBias::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3484,7 +3484,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::GyroBias::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3543,7 +3543,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::CaptureGyroBias::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3601,7 +3601,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagHardIronOffset::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3632,7 +3632,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagHardIronOffset", /* .title = */ "Magnetometer Hard Iron Offset", - /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using Microstrain software tools.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", + /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3660,7 +3660,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagSoftIronMatrix::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3691,7 +3691,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagSoftIronMatrix", /* .title = */ "Magnetometer Soft Iron Matrix", - /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using Microstrain software tools.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \\begin{bmatrix} 0 & 1 & 2 \\\ 3 & 4 & 5 \\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n", + /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \\begin{bmatrix} 0 & 1 & 2 \\\\ 3 & 4 & 5 \\\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -3719,7 +3719,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ConingScullingEnable::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3796,7 +3796,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformEuler::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3873,7 +3873,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformQuaternion::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3932,7 +3932,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::Sensor2VehicleTransformDcm::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -4018,7 +4018,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::ComplementaryFilter::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -4135,7 +4135,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::SensorRange::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -4255,7 +4255,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::CalibratedSensorRanges::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -4349,7 +4349,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::LowpassFilter::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/commands_aiding.hpp b/src/cpp/mip/metadata/definitions/commands_aiding.hpp index a0f98d3d1..681530ef3 100644 --- a/src/cpp/mip/metadata/definitions/commands_aiding.hpp +++ b/src/cpp/mip/metadata/definitions/commands_aiding.hpp @@ -57,7 +57,7 @@ struct MetadataFor static constexpr inline StructInfo value = { /* .name = */ "Rotation", - /* .title = */ "None", + /* .title = */ "Rotation", /* .docs = */ "", /* .parameters = */ parameters, }; @@ -118,7 +118,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_aiding::FrameConfig::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -233,7 +233,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_aiding::EchoControl::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index 658b31d9e..bb6f150a2 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -133,7 +133,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetDeviceInfo::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -179,7 +179,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetDeviceDescriptors::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -225,7 +225,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::BuiltInTest::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -288,7 +288,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::GetExtendedDescriptors::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -334,7 +334,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::ContinuousBit::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -389,7 +389,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_base::CommSpeed::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/commands_filter.hpp b/src/cpp/mip/metadata/definitions/commands_filter.hpp index 0dba5bcd6..c9539bc36 100644 --- a/src/cpp/mip/metadata/definitions/commands_filter.hpp +++ b/src/cpp/mip/metadata/definitions/commands_filter.hpp @@ -117,7 +117,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::EstimationControl::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -400,7 +400,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::TareOrientation::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -480,7 +480,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::VehicleDynamicsMode::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -557,7 +557,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationEuler::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -634,7 +634,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationDcm::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -665,7 +665,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationDcm", /* .title = */ "Sensor to Vehicle Frame Rotation DCM", - /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \\begin{bmatrix} 0 & 1 & 2\\\ 3 & 4 & 5\\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", + /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \\begin{bmatrix} 0 & 1 & 2\\\\ 3 & 4 & 5\\\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, /* .functions = */ {true, true, true, true, true, true}, @@ -693,7 +693,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleRotationQuaternion::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -752,7 +752,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SensorToVehicleOffset::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -811,7 +811,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AntennaOffset::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -891,7 +891,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GnssSource::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -975,7 +975,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::HeadingSource::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1034,7 +1034,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AutoInitControl::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1093,7 +1093,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AccelNoise::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1152,7 +1152,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GyroNoise::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1220,7 +1220,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AccelBiasModel::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1297,7 +1297,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GyroBiasModel::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1384,7 +1384,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AltitudeAiding::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1462,7 +1462,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::PitchRollAiding::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1530,7 +1530,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AutoZupt::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1607,7 +1607,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AutoAngularZupt::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1731,7 +1731,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GravityNoise::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1790,7 +1790,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::PressureAltitudeNoise::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1849,7 +1849,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::HardIronOffsetNoise::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1908,7 +1908,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SoftIronMatrixNoise::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1967,7 +1967,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagNoise::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2055,7 +2055,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::InclinationSource::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2132,7 +2132,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagneticDeclinationSource::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2209,7 +2209,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MagFieldMagnitudeSource::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2304,7 +2304,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::ReferencePosition::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2464,7 +2464,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AidingMeasurementEnable::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3014,7 +3014,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::KinematicConstraint::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3224,7 +3224,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::InitializationConfiguration::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3364,7 +3364,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::AdaptiveFilterOptions::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3441,7 +3441,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::MultiAntennaOffset::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3527,7 +3527,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::RelPosConfiguration::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3631,7 +3631,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::RefPointLeverArm::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3764,7 +3764,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::SpeedLeverArm::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3832,7 +3832,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::WheeledVehicleConstraintControl::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3891,7 +3891,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::VerticalGyroConstraintControl::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3959,7 +3959,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_filter::GnssAntennaCalControl::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/commands_gnss.hpp b/src/cpp/mip/metadata/definitions/commands_gnss.hpp index 5d0d1139c..ced5aa613 100644 --- a/src/cpp/mip/metadata/definitions/commands_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/commands_gnss.hpp @@ -81,7 +81,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::ReceiverInfo::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -98,7 +98,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::ReceiverInfo", - /* .title = */ "None", + /* .title = */ "receiver_info", /* .docs = */ "Return information about the GNSS receivers in the device.\n", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, @@ -116,7 +116,7 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "gps_enable", - /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5", + /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -134,7 +134,7 @@ struct MetadataFor }, { /* .name = */ "galileo_enable", - /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A", + /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -143,7 +143,7 @@ struct MetadataFor }, { /* .name = */ "beidou_enable", - /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A", + /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -163,7 +163,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::SignalConfiguration::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -182,7 +182,7 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "gps_enable", - /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5", + /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -200,7 +200,7 @@ struct MetadataFor }, { /* .name = */ "galileo_enable", - /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A", + /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -209,7 +209,7 @@ struct MetadataFor }, { /* .name = */ "beidou_enable", - /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A", + /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, /* .functions = */ {true, false, false, false, false, true}, @@ -229,7 +229,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::SignalConfiguration", - /* .title = */ "None", + /* .title = */ "signal_configuration", /* .docs = */ "Configure the GNSS signals used by the device.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -267,7 +267,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::RtkDongleConfiguration::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -306,7 +306,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_gnss::RtkDongleConfiguration", - /* .title = */ "None", + /* .title = */ "rtk_dongle_configuration", /* .docs = */ "Configure the communications with the RTK Dongle connected to the device.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/commands_rtk.hpp b/src/cpp/mip/metadata/definitions/commands_rtk.hpp index eddf293a5..126b2c81d 100644 --- a/src/cpp/mip/metadata/definitions/commands_rtk.hpp +++ b/src/cpp/mip/metadata/definitions/commands_rtk.hpp @@ -86,7 +86,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::GetStatusFlags::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -132,7 +132,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::GetImei::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -178,7 +178,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::GetImsi::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -224,7 +224,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::GetIccid::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -289,7 +289,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::ConnectedDeviceType::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -348,7 +348,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::GetActCode::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -394,7 +394,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::GetModemFirmwareVersion::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -458,7 +458,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::GetRssi::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -475,7 +475,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::GetRssi", - /* .title = */ "None", + /* .title = */ "get_rssi", /* .docs = */ "Get the RSSI and connected/disconnected status of modem", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, @@ -551,7 +551,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::ServiceStatus::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -589,7 +589,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::ServiceStatus", - /* .title = */ "None", + /* .title = */ "service_status", /* .docs = */ "The 3DMRTK will send this message to the server to indicate that the connection should remain open. The Server will respond with information and status.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -637,7 +637,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::ProdEraseStorage", - /* .title = */ "None", + /* .title = */ "prod_erase_storage", /* .docs = */ "This command will erase the selected media to a raw and uninitialized state. ALL DATA WILL BE LOST.\nThis command is only available in calibration mode.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -713,7 +713,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::LedControl", - /* .title = */ "None", + /* .title = */ "led_control", /* .docs = */ "This command allows direct control of the LED on the 3DM RTK. This command is only available in calibration mode or Production Test Mode.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -730,7 +730,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_rtk::ModemHardReset", - /* .title = */ "None", + /* .title = */ "modem_hard_reset", /* .docs = */ "This command will clear the modem flash. THIS MUST NOT BE DONE OFTEN AS IT CAN DAMAGE THE FLASH!\nThis command is only available in calibration mode.", /* .parameters = */ {}, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/commands_system.hpp b/src/cpp/mip/metadata/definitions/commands_system.hpp index 2a9f7adcf..62904d125 100644 --- a/src/cpp/mip/metadata/definitions/commands_system.hpp +++ b/src/cpp/mip/metadata/definitions/commands_system.hpp @@ -29,7 +29,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_system::CommMode::Response", - /* .title = */ "None", + /* .title = */ "response", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -59,7 +59,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_system::CommMode", - /* .title = */ "None", + /* .title = */ "comm_mode", /* .docs = */ "Advanced specialized communication modes.\n\nThis command allows the user to communicate directly with various subsystems which may be present in MIP devices (i.e. IMU, GNSS, etc.)\nPlease see the specific device's user manual for possible modes.\n\nThis command responds with an ACK/NACK just prior to switching to the new protocol.\nFor all functions except 0x01 (use new settings), the new communications mode value is ignored.\n\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/data_filter.hpp b/src/cpp/mip/metadata/definitions/data_filter.hpp index f50c4e187..bec980709 100644 --- a/src/cpp/mip/metadata/definitions/data_filter.hpp +++ b/src/cpp/mip/metadata/definitions/data_filter.hpp @@ -112,7 +112,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::VelocityNed", - /* .title = */ "None", + /* .title = */ "velocity_ned", /* .docs = */ "Filter reported velocity in the NED local-level frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -150,7 +150,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AttitudeQuaternion", - /* .title = */ "None", + /* .title = */ "attitude_quaternion", /* .docs = */ "4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame.\nThis quaternion satisfies the following relationship:\n\nEQSTART p^{veh} = q^{-1} p^{ned} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the rotation.
\nEQSTART p^ned = (0, v^{ned}_x, v^{ned}_y, v^{ned}_z) EQEND and EQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART p^veh = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -188,7 +188,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AttitudeDcm", - /* .title = */ "None", + /* .title = */ "attitude_dcm", /* .docs = */ "3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame.\nThis matrix satisfies the following relationship:\n\nEQSTART v^{veh} = M_{ned}^{veh} v^{ned} EQEND
\n\nWhere:
\n\nEQSTART v^{ned} EQEND is a 3-element vector expressed in the NED frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{ned}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -244,7 +244,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::EulerAngles", - /* .title = */ "None", + /* .title = */ "euler_angles", /* .docs = */ "Filter reported Euler angles describing the orientation of the device with respect to the NED local-level frame.\nThe Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -282,7 +282,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::GyroBias", - /* .title = */ "None", + /* .title = */ "gyro_bias", /* .docs = */ "Filter reported gyro bias expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -320,7 +320,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AccelBias", - /* .title = */ "None", + /* .title = */ "accel_bias", /* .docs = */ "Filter reported accelerometer bias expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -488,7 +488,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::EulerAnglesUncertainty", - /* .title = */ "None", + /* .title = */ "euler_angles_uncertainty", /* .docs = */ "Filter reported 1-sigma Euler angle uncertainties.\nThe uncertainties are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -526,7 +526,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::GyroBiasUncertainty", - /* .title = */ "None", + /* .title = */ "gyro_bias_uncertainty", /* .docs = */ "Filter reported 1-sigma gyro bias uncertainties expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -564,7 +564,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AccelBiasUncertainty", - /* .title = */ "None", + /* .title = */ "accel_bias_uncertainty", /* .docs = */ "Filter reported 1-sigma accelerometer bias uncertainties expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -611,7 +611,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::Timestamp", - /* .title = */ "None", + /* .title = */ "timestamp", /* .docs = */ "GPS timestamp of the Filter data\n\nShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.\nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.\nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.\n\nNote: this data field may be deprecated in the future. The more flexible shared data field (0x82, 0xD3) should be used instead.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -749,7 +749,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::Status", - /* .title = */ "None", + /* .title = */ "status", /* .docs = */ "Device-specific filter status indicators.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -787,7 +787,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::LinearAccel", - /* .title = */ "None", + /* .title = */ "linear_accel", /* .docs = */ "Filter-compensated linear acceleration expressed in the vehicle frame.\nNote: The estimated gravity has been removed from this data leaving only linear acceleration.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -825,7 +825,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::GravityVector", - /* .title = */ "None", + /* .title = */ "gravity_vector", /* .docs = */ "Filter reported gravity vector expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -901,7 +901,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::CompAngularRate", - /* .title = */ "None", + /* .title = */ "comp_angular_rate", /* .docs = */ "Filter-compensated angular rate expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -939,7 +939,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::QuaternionAttitudeUncertainty", - /* .title = */ "None", + /* .title = */ "quaternion_attitude_uncertainty", /* .docs = */ "Filter reported quaternion uncertainties.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -977,7 +977,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::Wgs84GravityMag", - /* .title = */ "None", + /* .title = */ "wgs84_gravity_mag", /* .docs = */ "Filter reported WGS84 gravity magnitude.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1055,7 +1055,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::HeadingUpdateState", - /* .title = */ "None", + /* .title = */ "heading_update_state", /* .docs = */ "Filter reported heading update state.\n\nHeading updates can be applied from the sources listed below. Note, some of these sources may be combined.\nThe heading value is always relative to true north.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1129,7 +1129,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagneticModel", - /* .title = */ "None", + /* .title = */ "magnetic_model", /* .docs = */ "The World Magnetic Model is used for this data. Please refer to the device user manual for the current version of the model.\nA valid GNSS location is required for the model to be valid.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1167,7 +1167,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AccelScaleFactor", - /* .title = */ "None", + /* .title = */ "accel_scale_factor", /* .docs = */ "Filter reported accelerometer scale factor expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1205,7 +1205,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AccelScaleFactorUncertainty", - /* .title = */ "None", + /* .title = */ "accel_scale_factor_uncertainty", /* .docs = */ "Filter reported 1-sigma accelerometer scale factor uncertainty expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1243,7 +1243,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::GyroScaleFactor", - /* .title = */ "None", + /* .title = */ "gyro_scale_factor", /* .docs = */ "Filter reported gyro scale factor expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1281,7 +1281,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::GyroScaleFactorUncertainty", - /* .title = */ "None", + /* .title = */ "gyro_scale_factor_uncertainty", /* .docs = */ "Filter reported 1-sigma gyro scale factor uncertainty expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1319,7 +1319,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagBias", - /* .title = */ "None", + /* .title = */ "mag_bias", /* .docs = */ "Filter reported magnetometer bias expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1357,7 +1357,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagBiasUncertainty", - /* .title = */ "None", + /* .title = */ "mag_bias_uncertainty", /* .docs = */ "Filter reported 1-sigma magnetometer bias uncertainty expressed in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1431,7 +1431,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::StandardAtmosphere", - /* .title = */ "None", + /* .title = */ "standard_atmosphere", /* .docs = */ "Filter reported standard atmosphere parameters.\n\nThe US 1976 Standard Atmosphere Model is used. A valid GNSS location is required for the model to be valid.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1469,7 +1469,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::PressureAltitude", - /* .title = */ "None", + /* .title = */ "pressure_altitude", /* .docs = */ "Filter reported pressure altitude.\n\nThe US 1976 Standard Atmosphere Model is used to calculate the pressure altitude in meters.\nA valid pressure sensor reading is required for the pressure altitude to be valid.\nThe minimum pressure reading supported by the model is 0.0037 mBar, corresponding to an altitude of 84,852 meters.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1507,7 +1507,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::DensityAltitude", - /* .title = */ "None", + /* .title = */ "density_altitude", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1545,7 +1545,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AntennaOffsetCorrection", - /* .title = */ "None", + /* .title = */ "antenna_offset_correction", /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.\n\nThis offset added to any previously stored offset vector to compensate for errors in definition.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1583,7 +1583,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AntennaOffsetCorrectionUncertainty", - /* .title = */ "None", + /* .title = */ "antenna_offset_correction_uncertainty", /* .docs = */ "Filter reported 1-sigma GNSS antenna offset uncertainties in vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1630,7 +1630,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MultiAntennaOffsetCorrection", - /* .title = */ "None", + /* .title = */ "multi_antenna_offset_correction", /* .docs = */ "Filter reported GNSS antenna offset in vehicle frame.\n\nThis offset added to any previously stored offset vector to compensate for errors in definition.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1677,7 +1677,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MultiAntennaOffsetCorrectionUncertainty", - /* .title = */ "None", + /* .title = */ "multi_antenna_offset_correction_uncertainty", /* .docs = */ "Filter reported 1-sigma GNSS antenna offset uncertainties in vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1715,7 +1715,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerOffset", - /* .title = */ "None", + /* .title = */ "magnetometer_offset", /* .docs = */ "Filter reported magnetometer hard iron offset in sensor frame.\n\nThis offset added to any previously stored hard iron offset vector to compensate for magnetometer in-run bias errors.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1753,7 +1753,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerMatrix", - /* .title = */ "None", + /* .title = */ "magnetometer_matrix", /* .docs = */ "Filter reported magnetometer soft iron matrix in sensor frame.\n\nThis matrix is post multiplied to any previously stored soft iron matrix to compensate for magnetometer in-run errors.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1791,7 +1791,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerOffsetUncertainty", - /* .title = */ "None", + /* .title = */ "magnetometer_offset_uncertainty", /* .docs = */ "Filter reported 1-sigma magnetometer hard iron offset uncertainties in sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1829,7 +1829,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerMatrixUncertainty", - /* .title = */ "None", + /* .title = */ "magnetometer_matrix_uncertainty", /* .docs = */ "Filter reported 1-sigma magnetometer soft iron matrix uncertainties in sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1867,7 +1867,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerCovarianceMatrix", - /* .title = */ "None", + /* .title = */ "magnetometer_covariance_matrix", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1905,7 +1905,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::MagnetometerResidualVector", - /* .title = */ "None", + /* .title = */ "magnetometer_residual_vector", /* .docs = */ "Filter reported magnetometer measurement residuals in vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1961,7 +1961,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::ClockCorrection", - /* .title = */ "None", + /* .title = */ "clock_correction", /* .docs = */ "Filter reported GNSS receiver clock error parameters.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2017,7 +2017,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::ClockCorrectionUncertainty", - /* .title = */ "None", + /* .title = */ "clock_correction_uncertainty", /* .docs = */ "Filter reported 1-sigma GNSS receiver clock error parameters.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2219,7 +2219,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::HeadAidStatus", - /* .title = */ "None", + /* .title = */ "head_aid_status", /* .docs = */ "Filter reported GNSS heading aiding status", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2520,7 +2520,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_filter::AidingMeasurementSummary", - /* .title = */ "None", + /* .title = */ "aiding_measurement_summary", /* .docs = */ "Filter reported aiding measurement summary. This message contains a summary of the specified aiding measurement over the previous measurement interval ending at the specified time.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/data_gnss.hpp b/src/cpp/mip/metadata/definitions/data_gnss.hpp index 5b9d66848..c4517e0d0 100644 --- a/src/cpp/mip/metadata/definitions/data_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/data_gnss.hpp @@ -464,7 +464,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::Dop", - /* .title = */ "None", + /* .title = */ "dop", /* .docs = */ "GNSS reported dilution of precision information.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -576,7 +576,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::UtcTime", - /* .title = */ "None", + /* .title = */ "utc_time", /* .docs = */ "GNSS reported Coordinated Universal Time", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -643,7 +643,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::GpsTime", - /* .title = */ "None", + /* .title = */ "gps_time", /* .docs = */ "GNSS reported GPS Time", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -720,7 +720,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::ClockInfo", - /* .title = */ "None", + /* .title = */ "clock_info", /* .docs = */ "GNSS reported receiver clock parameters", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -841,7 +841,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::FixInfo", - /* .title = */ "None", + /* .title = */ "fix_info", /* .docs = */ "GNSS reported position fix type", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -967,7 +967,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::SvInfo", - /* .title = */ "None", + /* .title = */ "sv_info", /* .docs = */ "GNSS reported space vehicle information\n\nWhen enabled, these fields will arrive in separate MIP packets", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1193,7 +1193,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::DgpsInfo", - /* .title = */ "None", + /* .title = */ "dgps_info", /* .docs = */ "GNSS reported DGNSS status\n\n
Possible Base Station Status Values:
\n
  0 - UDRE Scale Factor = 1.0
\n
  1 - UDRE Scale Factor = 0.75
\n
  2 - UDRE Scale Factor = 0.5
\n
  3 - UDRE Scale Factor = 0.3
\n
  4 - UDRE Scale Factor = 0.2
\n
  5 - UDRE Scale Factor = 0.1
\n
  6 - Reference Station Transmission Not Monitored
\n
  7 - Reference Station Not Working
\n\n(UDRE = User Differential Range Error)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1280,7 +1280,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::DgpsChannel", - /* .title = */ "None", + /* .title = */ "dgps_channel", /* .docs = */ "GNSS reported DGPS Channel Status status\n\nWhen enabled, a separate field for each active space vehicle will be sent in the packet.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1367,7 +1367,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::ClockInfo2", - /* .title = */ "None", + /* .title = */ "clock_info_2", /* .docs = */ "GNSS reported receiver clock parameters\n\nThis supersedes MIP_DATA_DESC_GNSS_CLOCK_INFO with additional information.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1423,7 +1423,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::GpsLeapSeconds", - /* .title = */ "None", + /* .title = */ "gps_leap_seconds", /* .docs = */ "GNSS reported leap seconds (difference between GPS and UTC Time)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1573,7 +1573,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::SbasInfo", - /* .title = */ "None", + /* .title = */ "sbas_info", /* .docs = */ "GNSS SBAS status", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1727,7 +1727,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::SbasCorrection", - /* .title = */ "None", + /* .title = */ "sbas_correction", /* .docs = */ "GNSS calculated SBAS Correction\n\nUDREI - the variance of a normal distribution associated with the user differential range errors for a\nsatellite after application of fast and long-term corrections, excluding atmospheric effects\n\n
UDREI  Variance
\n
-----------------------
\n
0      0.0520 m^2
\n
1      0.0924 m^2
\n
2      0.1444 m^2
\n
3      0.2830 m^2
\n
4      0.4678 m^2
\n
5      0.8315 m^2
\n
6      1.2992 m^2
\n
7      1.8709 m^2
\n
8      2.5465 m^2
\n
9      3.3260 m^2
\n
10     5.1968 m^2
\n
11     20.7870 m^2
\n
12     230.9661 m^2
\n
13     2078.695 m^2
\n
14     'Not Monitored'
\n
15     'Do Not Use'
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -1876,7 +1876,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::RfErrorDetection", - /* .title = */ "None", + /* .title = */ "rf_error_detection", /* .docs = */ "GNSS Error Detection subsystem status", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2009,7 +2009,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::BaseStationInfo", - /* .title = */ "None", + /* .title = */ "base_station_info", /* .docs = */ "RTCM reported base station information (sourced from RTCM Message 1005 or 1006)\n\nValid Flag Mapping:", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2171,7 +2171,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::RtkCorrectionsStatus", - /* .title = */ "None", + /* .title = */ "rtk_corrections_status", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2306,7 +2306,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::SatelliteStatus", - /* .title = */ "None", + /* .title = */ "satellite_status", /* .docs = */ "Status information for a GNSS satellite.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2636,7 +2636,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::Raw", - /* .title = */ "None", + /* .title = */ "raw", /* .docs = */ "GNSS Raw observation.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2982,7 +2982,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::GpsEphemeris", - /* .title = */ "None", + /* .title = */ "gps_ephemeris", /* .docs = */ "GPS Ephemeris Data", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3328,7 +3328,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::GalileoEphemeris", - /* .title = */ "None", + /* .title = */ "galileo_ephemeris", /* .docs = */ "Galileo Ephemeris Data", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index 727311874..b9595ae90 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -29,7 +29,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawAccel", - /* .title = */ "None", + /* .title = */ "raw_accel", /* .docs = */ "Three element vector representing the sensed acceleration.\nThis quantity is temperature compensated and expressed in the sensor body frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -58,7 +58,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawGyro", - /* .title = */ "None", + /* .title = */ "raw_gyro", /* .docs = */ "Three element vector representing the sensed angular rate.\nThis quantity is temperature compensated and expressed in the sensor body frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -87,7 +87,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawMag", - /* .title = */ "None", + /* .title = */ "raw_mag", /* .docs = */ "Three element vector representing the sensed magnetic field.\nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -116,7 +116,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::RawPressure", - /* .title = */ "None", + /* .title = */ "raw_pressure", /* .docs = */ "Scalar value representing the sensed ambient pressure.\nThis quantity is temperature compensated.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -145,7 +145,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledAccel", - /* .title = */ "None", + /* .title = */ "scaled_accel", /* .docs = */ "3-element vector representing the sensed acceleration.\nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -174,7 +174,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledGyro", - /* .title = */ "None", + /* .title = */ "scaled_gyro", /* .docs = */ "3-element vector representing the sensed angular rate.\nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -203,7 +203,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledMag", - /* .title = */ "None", + /* .title = */ "scaled_mag", /* .docs = */ "3-element vector representing the sensed magnetic field.\nThis quantity is temperature compensated and expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -232,7 +232,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::ScaledPressure", - /* .title = */ "None", + /* .title = */ "scaled_pressure", /* .docs = */ "Scalar value representing the sensed ambient pressure.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -261,7 +261,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::DeltaTheta", - /* .title = */ "None", + /* .title = */ "delta_theta", /* .docs = */ "3-element vector representing the time integral of angular rate.\nThis quantity is the integral of sensed angular rate over the period set by the IMU message format. It is expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -290,7 +290,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::DeltaVelocity", - /* .title = */ "None", + /* .title = */ "delta_velocity", /* .docs = */ "3-element vector representing the time integral of acceleration.\nThis quantity is the integral of sensed acceleration over the period set by the IMU message format. It is expressed in the vehicle frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -453,7 +453,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::OrientationRawTemp", - /* .title = */ "None", + /* .title = */ "orientation_raw_temp", /* .docs = */ "DEPRECATED!", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -482,7 +482,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::InternalTimestamp", - /* .title = */ "None", + /* .title = */ "internal_timestamp", /* .docs = */ "DEPRECATED!", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -589,7 +589,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::GpsTimestamp", - /* .title = */ "None", + /* .title = */ "gps_timestamp", /* .docs = */ "GPS timestamp of the SENSOR data\n\nShould the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time.\nUpon recovering from a PPS outage, the user should expect a jump in the reported GPS time due to the accumulation of internal clock error.\nIf synchronization to an external clock or onboard GNSS receiver (for products that have one) is disabled, this time is equivalent to internal system time.\n\nNote: this data field may be deprecated in the future. The more flexible shared data field (0x80, 0xD3) should be used instead.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -665,7 +665,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::UpVector", - /* .title = */ "None", + /* .title = */ "up_vector", /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimated vertical direction.\nThis quantity is expressed in the vehicle frame.\n\nThis quantity is sensitive to non-gravitational accelerations, which may cause notable deviations from the true vertical direction.\n\nFor legacy reasons, this vector is the inverse of the gravity vector.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -694,7 +694,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::NorthVector", - /* .title = */ "None", + /* .title = */ "north_vector", /* .docs = */ "Gyro-stabilized 3-element vector representing the complementary filter's estimate of magnetic north.\nThis quantity is expressed in the vehicle frame.\n\nThis quantity is sensitive to local magnetic field perturbations, which may cause notable deviations from true magnetic north.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -750,7 +750,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::OverrangeStatus", - /* .title = */ "None", + /* .title = */ "overrange_status", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -797,7 +797,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_sensor::OdometerData", - /* .title = */ "None", + /* .title = */ "odometer_data", /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/data_shared.hpp b/src/cpp/mip/metadata/definitions/data_shared.hpp index 24409e893..cc95762f0 100644 --- a/src/cpp/mip/metadata/definitions/data_shared.hpp +++ b/src/cpp/mip/metadata/definitions/data_shared.hpp @@ -29,7 +29,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::EventSource", - /* .title = */ "None", + /* .title = */ "event_source", /* .docs = */ "Identifies which event trigger caused this packet to be emitted.\n\nGenerally this is used to determine whether a packet was emitted\ndue to scheduled streaming or due to an event.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -58,7 +58,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::Ticks", - /* .title = */ "None", + /* .title = */ "ticks", /* .docs = */ "Time since powerup in multiples of the base rate.\n\nThe counter will wrap around to 0 after approximately 50 days.\nOne tick is equivalent to one base period (reciprocal of the base rate).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -87,7 +87,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::DeltaTicks", - /* .title = */ "None", + /* .title = */ "delta_ticks", /* .docs = */ "Ticks since the last output of this field.\n\nThis field can be used to track the amount of time passed between\nevent occurrences.\nOne tick is equivalent to one base period (reciprocal of the base rate).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -154,7 +154,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::GpsTimestamp", - /* .title = */ "None", + /* .title = */ "gps_timestamp", /* .docs = */ "Outputs the current GPS system time in time-of-week and week number format.\n\nFor events, this is the time of the event trigger.\nIn order to be valid, a PPS signal needs to be present, and both a valid GPS time-of-week and week number command (0x0C, 0x72) need to be received after PPS sync has been achieved.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -183,7 +183,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::DeltaTime", - /* .title = */ "None", + /* .title = */ "delta_time", /* .docs = */ "Time in the synchronized clock domain since the last output of this field within the same descriptor set and event instance.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.\n\nThis field contains the same value as the delta external time field, 0xD8,\nbut is expressed in seconds. Transmission of either of these fields\nrestarts a shared counter, so only one should be streamed at a time to\navoid confusion. The counter is not shared across descriptors sets or\nbetween event instances.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -212,7 +212,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ReferenceTimestamp", - /* .title = */ "None", + /* .title = */ "reference_timestamp", /* .docs = */ "Internal reference timestamp.\n\nThis timestamp represents the time at which the corresponding\ndata was sampled, according to the internal reference clock.\n\nThis is a monotonic clock which never jumps. The value is always valid.\n\nFor events, this is the time of the event trigger.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -241,7 +241,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ReferenceTimeDelta", - /* .title = */ "None", + /* .title = */ "reference_time_delta", /* .docs = */ "Delta time since the last packet.\n\nDifference between the time as reported by the shared reference time field, 0xD5,\nand the previous output of this delta quantity within the same descriptor set and event instance.\n\nThe delta is based on the reference time which never jumps. The value\nis always valid.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -297,7 +297,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ExternalTimestamp", - /* .title = */ "None", + /* .title = */ "external_timestamp", /* .docs = */ "External timestamp in nanoseconds.\n\nThis timestamp represents the time at which the corresponding\ndata was sampled in the external clock domain.\nEquivalent to the GPS Timestamp but in nanoseconds.\n\nFor events, this is the time of the event trigger.\n\nTo be valid, external clock sync must be achieved using the PPS input.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -353,7 +353,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_shared::ExternalTimeDelta", - /* .title = */ "None", + /* .title = */ "external_time_delta", /* .docs = */ "Delta time since the last packet containing delta external (0xFF,0xD4) or delta gps time (0xFF,0xD8).\n\nDifference between the time as reported by the shared external time field, 0xD7,\nand the previous output of this delta quantity within the same descriptor set and event instance.\n\nThis can be used to track the amount of time passed between\nevent occurrences. See the manual page on delta time quantities.\n\nThis field contains the same value as the delta gps time field, 0xD4,\nbut is expressed in nanoseconds. Transmission of either of these fields\nrestarts a shared counter, so only one should be streamed at a time to\navoid confusion. The counter is not shared across descriptors sets or\nbetween event instances.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, diff --git a/src/cpp/mip/metadata/definitions/data_system.hpp b/src/cpp/mip/metadata/definitions/data_system.hpp index de699bd71..ca5aac652 100644 --- a/src/cpp/mip/metadata/definitions/data_system.hpp +++ b/src/cpp/mip/metadata/definitions/data_system.hpp @@ -29,7 +29,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::BuiltInTest", - /* .title = */ "None", + /* .title = */ "built_in_test", /* .docs = */ "Contains the continuous built-in-test (BIT) results.\n\nDue to the large size of this field, it is recommended to stream it at\na low rate or poll it on demand.\n\nThese bits are 'sticky' until the next output message. If a fault occurs\nin between scheduled messages or while the device is idle, the next\npacket with this field will have the corresponding flags set. The flag\nis then cleared unless the fault persists.\n\nUnlike the commanded BIT, some bits may be 1 in certain\nnon-fault situations, so simply checking if the result is all 0s is\nnot very useful. For example, on devices with a built-in GNSS receiver,\na 'solution fault' bit may be set before the receiver has obtained\na position fix. Consult the device manual to determine which bits are\nof interest for your application.\n\nAll unspecified bits are reserved for future use and must be ignored.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -67,7 +67,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::TimeSyncStatus", - /* .title = */ "None", + /* .title = */ "time_sync_status", /* .docs = */ "Indicates whether a sync has been achieved using the PPS signal.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -96,7 +96,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::GpioState", - /* .title = */ "None", + /* .title = */ "gpio_state", /* .docs = */ "Indicates the state of all of the user GPIO pins.\n\nThis message can be used to correlate external signals\nwith the device time or other data quantities. It should\ngenerally be used with slow GPIO signals as brief pulses\nshorter than the scheduled data rate will be missed.\n\nTo synchronize with faster signals and pulses, or for more accurate timestamping,\nutilize the event system and set the GPIO feature to TIMESTAMP in the 3DM GPIO\nConfiguration command (0x0C,0x41).\n\nThese GPIO states are sampled within one base period\nof the system data descriptor set.\n\nTo obtain valid readings, the desired pin(s) must be configured to the GPIO feature\n(either input or output behavior) using the 3DM GPIO Configuration command\n(0x0C,0x41). Other gpio features may work on some devices but this is not guaranteed.\nConsult the factory before producing a design relying on reading pins configured\nto other feature types.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -134,7 +134,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_system::GpioAnalogValue", - /* .title = */ "None", + /* .title = */ "gpio_analog_value", /* .docs = */ "Indicates the analog value of the given user GPIO.\nThe pin must be configured for analog input.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, From a7e84100f7e2d8ea4d802527ee171befc23eed9d Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 9 Sep 2024 16:48:29 -0400 Subject: [PATCH 110/147] Use absolute include path for common.hpp in metadata definitions. --- src/cpp/mip/metadata/definitions/commands_3dm.hpp | 2 +- src/cpp/mip/metadata/definitions/commands_aiding.hpp | 2 +- src/cpp/mip/metadata/definitions/commands_base.hpp | 2 +- src/cpp/mip/metadata/definitions/commands_filter.hpp | 2 +- src/cpp/mip/metadata/definitions/commands_gnss.hpp | 2 +- src/cpp/mip/metadata/definitions/commands_rtk.hpp | 2 +- src/cpp/mip/metadata/definitions/commands_system.hpp | 2 +- src/cpp/mip/metadata/definitions/data_filter.hpp | 2 +- src/cpp/mip/metadata/definitions/data_gnss.hpp | 2 +- src/cpp/mip/metadata/definitions/data_sensor.hpp | 2 +- src/cpp/mip/metadata/definitions/data_shared.hpp | 2 +- src/cpp/mip/metadata/definitions/data_system.hpp | 2 +- 12 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index 81476866b..eb1c48e58 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/commands_aiding.hpp b/src/cpp/mip/metadata/definitions/commands_aiding.hpp index 681530ef3..22eaa35d2 100644 --- a/src/cpp/mip/metadata/definitions/commands_aiding.hpp +++ b/src/cpp/mip/metadata/definitions/commands_aiding.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index bb6f150a2..50152136d 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/commands_filter.hpp b/src/cpp/mip/metadata/definitions/commands_filter.hpp index c9539bc36..391ada0f3 100644 --- a/src/cpp/mip/metadata/definitions/commands_filter.hpp +++ b/src/cpp/mip/metadata/definitions/commands_filter.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/commands_gnss.hpp b/src/cpp/mip/metadata/definitions/commands_gnss.hpp index ced5aa613..1f53daf67 100644 --- a/src/cpp/mip/metadata/definitions/commands_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/commands_gnss.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/commands_rtk.hpp b/src/cpp/mip/metadata/definitions/commands_rtk.hpp index 126b2c81d..98a45ba30 100644 --- a/src/cpp/mip/metadata/definitions/commands_rtk.hpp +++ b/src/cpp/mip/metadata/definitions/commands_rtk.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/commands_system.hpp b/src/cpp/mip/metadata/definitions/commands_system.hpp index 62904d125..6d7ef219f 100644 --- a/src/cpp/mip/metadata/definitions/commands_system.hpp +++ b/src/cpp/mip/metadata/definitions/commands_system.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/data_filter.hpp b/src/cpp/mip/metadata/definitions/data_filter.hpp index bec980709..f12adcbb1 100644 --- a/src/cpp/mip/metadata/definitions/data_filter.hpp +++ b/src/cpp/mip/metadata/definitions/data_filter.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/data_gnss.hpp b/src/cpp/mip/metadata/definitions/data_gnss.hpp index c4517e0d0..87612e9e4 100644 --- a/src/cpp/mip/metadata/definitions/data_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/data_gnss.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index b9595ae90..0249b7517 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/data_shared.hpp b/src/cpp/mip/metadata/definitions/data_shared.hpp index cc95762f0..f3a2f2889 100644 --- a/src/cpp/mip/metadata/definitions/data_shared.hpp +++ b/src/cpp/mip/metadata/definitions/data_shared.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include diff --git a/src/cpp/mip/metadata/definitions/data_system.hpp b/src/cpp/mip/metadata/definitions/data_system.hpp index ca5aac652..2c976c2ab 100644 --- a/src/cpp/mip/metadata/definitions/data_system.hpp +++ b/src/cpp/mip/metadata/definitions/data_system.hpp @@ -1,6 +1,6 @@ #pragma once -#include "common.hpp" +#include #include From fe214748c641e6c7543991d03084d2adac128737 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Mon, 9 Sep 2024 16:51:28 -0400 Subject: [PATCH 111/147] Fixed install include directories --- Jenkinsfile | 4 ---- cmake/microstrain_utilities.cmake | 9 +++------ 2 files changed, 3 insertions(+), 10 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index d80db4d78..fe8562700 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -72,7 +72,6 @@ pipeline { mkdir build_Win32 cd build_Win32 cmake .. -A "Win32" -DMICROSTRAIN_BUILD_PACKAGE=ON - cmake .. -A "Win32" -DMICROSTRAIN_BUILD_PACKAGE=ON # cmake does not configure correctly on the first pass for install cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_Win32/mipsdk_*' @@ -93,7 +92,6 @@ pipeline { mkdir build_x64 cd build_x64 cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON - cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON # cmake does not configure correctly on the first pass for install cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_x64/mipsdk_*' @@ -174,7 +172,6 @@ pipeline { mkdir build_mac_arm64 cd build_mac_arm64 cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE - cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE # cmake does not configure correctly on the first pass for install cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' @@ -196,7 +193,6 @@ pipeline { mkdir build_mac_intel cd build_mac_intel cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE - cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE # cmake does not configure correctly on the first pass for install cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' diff --git a/cmake/microstrain_utilities.cmake b/cmake/microstrain_utilities.cmake index cef40db10..9ceb10885 100644 --- a/cmake/microstrain_utilities.cmake +++ b/cmake/microstrain_utilities.cmake @@ -1,8 +1,6 @@ # Install the headers in their macro(microstrain_setup_install_headers LIBRARY ROOT_DIR) - if(UNIX AND NOT APPLE) - include(GNUInstallDirs) - endif() + include(GNUInstallDirs) # Only install headers that we build the source files for get_target_property(ALL_HEADERS ${LIBRARY} SOURCES) @@ -24,14 +22,11 @@ macro(microstrain_setup_install_headers LIBRARY ROOT_DIR) install( FILES "${HEADER}" DESTINATION "${HEADER_DESTINATION}" - COMPONENT "${LIBRARY}" ) endforeach() endmacro() macro(microstrain_setup_library_install LIBRARY ROOT_DIR) - microstrain_setup_install_headers(${LIBRARY} ${ROOT_DIR}) - install( TARGETS ${LIBRARY} EXPORT ${LIBRARY}-targets @@ -40,6 +35,8 @@ macro(microstrain_setup_library_install LIBRARY ROOT_DIR) RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} ) + microstrain_setup_install_headers(${LIBRARY} ${ROOT_DIR}) + # include(CMakePackageConfigHelpers) # set(CONFIG_EXPORT_DIR "${CMAKE_INSTALL_DATADIR}/cmake/${LIBRARY}") From 4dd69d644e4d431f41c4d24bb7f497a9dd38a322 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Tue, 10 Sep 2024 14:30:38 -0400 Subject: [PATCH 112/147] Fixed CPack install Moved file name prefix to top of install block Removed DEB and RPM options from Linux only check --- CMakeLists.txt | 42 +++++++++++++++++++----------------------- 1 file changed, 19 insertions(+), 23 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d71cba6f4..cc9eb99eb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -226,37 +226,36 @@ write_basic_package_version_file( if(MICROSTRAIN_BUILD_PACKAGE) microstrain_get_architecture(MICROSTRAIN_ARCH) - set(FOUND_CPACK_GENERATORS "") + set(MIP_FILE_NAME_PREFIX "mipsdk_${MICROSTRAIN_GIT_VERSION}_${MICROSTRAIN_ARCH}") - if(UNIX AND NOT APPLE) - set(DPKG_ROOT "" CACHE STRING "Location of the dpkg executable") - set(RPMBUILD_ROOT "" CACHE STRING "Location of the rpmbuild executable") + set(FOUND_CPACK_GENERATORS "") - find_program(DPKG_EXECUTABLE - NAMES dpkg - PATHS ${DPKG_ROOT} - DOC "dpkg command line client" - ) + set(DPKG_ROOT "" CACHE STRING "Location of the dpkg executable") + find_program(DPKG_EXECUTABLE + NAMES dpkg + PATHS ${DPKG_ROOT} + DOC "dpkg command line client" + ) - if(NOT ${DPKG_EXECUTABLE} STREQUAL "DPKG_EXECUTABLE-NOTFOUND") - list(APPEND FOUND_CPACK_GENERATORS "DEB") - endif() + if(NOT ${DPKG_EXECUTABLE} STREQUAL "DPKG_EXECUTABLE-NOTFOUND") + list(APPEND FOUND_CPACK_GENERATORS "DEB") # DEB specific configuration # Build different deb packages for each target set(CPACK_DEBIAN_MIP_FILE_NAME "${MIP_FILE_NAME_PREFIX}.deb") set(CPACK_DEB_COMPONENT_INSTALL ON) set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) + endif() - find_program(RPMBUILD_EXECUTABLE - NAMES rpmbuild - PATHS ${RPMBUILD_ROOT} - DOC "rpmbuild command line client" - ) + set(RPMBUILD_ROOT "" CACHE STRING "Location of the rpmbuild executable") + find_program(RPMBUILD_EXECUTABLE + NAMES rpmbuild + PATHS ${RPMBUILD_ROOT} + DOC "rpmbuild command line client" + ) - if(NOT ${RPMBUILD_EXECUTABLE} STREQUAL "RPMBUILD_EXECUTABLE-NOTFOUND") - list(APPEND FOUND_CPACK_GENERATORS "RPM") - endif() + if(NOT ${RPMBUILD_EXECUTABLE} STREQUAL "RPMBUILD_EXECUTABLE-NOTFOUND") + list(APPEND FOUND_CPACK_GENERATORS "RPM") # RPM specific configuration # Build different RPM packages for each target @@ -294,9 +293,6 @@ if(MICROSTRAIN_BUILD_PACKAGE) set(CPACK_PACKAGE_VERSION ${MICROSTRAIN_GIT_VERSION_CLEAN}) - # Shared configuration - set(MIP_FILE_NAME_PREFIX "mipsdk_${MICROSTRAIN_GIT_VERSION}_${MICROSTRAIN_ARCH}") - # Zip specific configuration # Build different zip packages for each target if(MSVC) From f5553d9c09c9e6fb66a73cc29313b4872dd32af4 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 10 Sep 2024 15:08:14 -0400 Subject: [PATCH 113/147] Enable examples in Jenkins file and fix build. --- Jenkinsfile | 8 ++++---- examples/CMakeLists.txt | 5 +++-- src/cpp/mip/metadata/definitions/common.hpp | 2 +- 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index fe8562700..c0c643d98 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -71,7 +71,7 @@ pipeline { powershell """ mkdir build_Win32 cd build_Win32 - cmake .. -A "Win32" -DMICROSTRAIN_BUILD_PACKAGE=ON + cmake .. -A "Win32" -DMICROSTRAIN_BUILD_PACKAGE=ON -DMICROSTRAIN_BUILD_EXAMPLES=ON cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_Win32/mipsdk_*' @@ -91,7 +91,7 @@ pipeline { powershell """ mkdir build_x64 cd build_x64 - cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON + cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DMICROSTRAIN_BUILD_EXAMPLES=ON cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_x64/mipsdk_*' @@ -171,7 +171,7 @@ pipeline { sh ''' mkdir build_mac_arm64 cd build_mac_arm64 - cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE + cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE -DMICROSTRAIN_BUILD_EXAMPLES=ON cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' @@ -192,7 +192,7 @@ pipeline { sh ''' mkdir build_mac_intel cd build_mac_intel - cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE + cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE -DMICROSTRAIN_BUILD_EXAMPLES=ON cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 5b50212cd..04d02fa87 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -32,8 +32,9 @@ set(MIP_EXAMPLE_DEFS ${MIP_DEFINES} ${SERIAL_DEFS} ${TCP_DEFS} ${EXTRAS_DEFS}) target_compile_definitions(${MIP_EXAMPLE_UTILS_LIBRARY} - PUBLIC ${MIP_EXAMPLE_DEFS} - PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS} + PUBLIC + ${MIP_EXAMPLE_DEFS} + ${MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS} ) target_compile_options(${MICROSTRAIN_SERIAL_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index e74bb224f..7bce3a87c 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -230,7 +230,7 @@ struct MetadataFor> static_assert(std::is_floating_point_v, "Expected either float or double"); static_assert(N >= 2 && N <= 4, "N should be in the range [2,4]."); - static constexpr inline const StructInfo& value = std::is_same_v ? values_d[N-2] : values_f[N-2]; + static constexpr inline const StructInfo& value = [](){ if constexpr( std::is_same_v ) return values_d[N-2]; else return values_f[N-2]; }(); }; From 7ac5095614c334ef593ab1a52e634ce34fae7749 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 10 Sep 2024 15:18:04 -0400 Subject: [PATCH 114/147] Enable examples on linux docker builds and try to fix mac build again. --- .devcontainer/docker_build.sh | 1 + src/cpp/mip/metadata/definitions/common.hpp | 6 +++--- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/.devcontainer/docker_build.sh b/.devcontainer/docker_build.sh index 187ba6fef..7566ef20d 100755 --- a/.devcontainer/docker_build.sh +++ b/.devcontainer/docker_build.sh @@ -64,6 +64,7 @@ docker run \ cmake ${docker_project_dir} \ -DMICROSTRAIN_BUILD_PACKAGE=ON \ -DCMAKE_BUILD_TYPE=RELEASE; \ + -DMICROSTRAIN_BUILD_EXAMPLES=ON \ cmake --build . -j; \ cmake --build . --target package; \ " diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index 7bce3a87c..fccaac0b7 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -186,7 +186,7 @@ struct MetadataFor> }; - static constexpr inline StructInfo values_f[] = { + static constexpr inline StructInfo values_f[3] = { { .name = "Vector2f", .title = "Vector2f", @@ -206,7 +206,7 @@ struct MetadataFor> .parameters = {parameters, 4} }, }; - static constexpr inline StructInfo values_d[] = { + static constexpr inline StructInfo values_d[3] = { { .name = "Vector2d", .title = "Vector2d", @@ -230,7 +230,7 @@ struct MetadataFor> static_assert(std::is_floating_point_v, "Expected either float or double"); static_assert(N >= 2 && N <= 4, "N should be in the range [2,4]."); - static constexpr inline const StructInfo& value = [](){ if constexpr( std::is_same_v ) return values_d[N-2]; else return values_f[N-2]; }(); + static constexpr inline const StructInfo& value = std::is_same_v ? values_d[N-2] : values_f[N-2]; }; From 577470193c53da5e7b90d6eddb5488177801432d Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 19 Sep 2024 16:43:51 -0400 Subject: [PATCH 115/147] Update definitions and fix mip_timestamp errors. --- src/c/microstrain/common/embedded_time.h | 2 +- src/c/mip/definitions/data_gnss.h | 20 +- src/cpp/mip/definitions/data_gnss.hpp | 28 +- .../mip/metadata/definitions/commands_3dm.hpp | 718 +++++------ .../metadata/definitions/commands_aiding.hpp | 198 +-- .../metadata/definitions/commands_base.hpp | 66 +- .../metadata/definitions/commands_filter.hpp | 614 ++++----- .../metadata/definitions/commands_gnss.hpp | 56 +- .../mip/metadata/definitions/commands_rtk.hpp | 118 +- .../metadata/definitions/commands_system.hpp | 8 +- src/cpp/mip/metadata/definitions/common.hpp | 20 +- .../mip/metadata/definitions/data_filter.hpp | 504 ++++---- .../mip/metadata/definitions/data_gnss.hpp | 1135 +++++++++-------- .../mip/metadata/definitions/data_sensor.hpp | 100 +- .../mip/metadata/definitions/data_shared.hpp | 44 +- .../mip/metadata/definitions/data_system.hpp | 14 +- src/cpp/mip/metadata/mip_meta_utils.hpp | 2 +- src/cpp/mip/metadata/mip_structures.hpp | 120 +- 18 files changed, 1904 insertions(+), 1863 deletions(-) diff --git a/src/c/microstrain/common/embedded_time.h b/src/c/microstrain/common/embedded_time.h index 54c91adb8..06ae4b3dd 100644 --- a/src/c/microstrain/common/embedded_time.h +++ b/src/c/microstrain/common/embedded_time.h @@ -29,7 +29,7 @@ static_assert( sizeof(microstrain_embedded_timestamp) >= 8 || (microstrain_embed typedef uint64_t microstrain_embedded_timestamp; #else // If the platform isn't known, assume u32 timestamps. -typedef uint32_t microstrain_timestamp; +typedef uint32_t microstrain_embedded_timestamp; #endif // Timeouts are just an alias for timestamps diff --git a/src/c/mip/definitions/data_gnss.h b/src/c/mip/definitions/data_gnss.h index aa45f2947..84c659db9 100644 --- a/src/c/mip/definitions/data_gnss.h +++ b/src/c/mip/definitions/data_gnss.h @@ -58,7 +58,6 @@ enum MIP_DATA_DESC_GNSS_GLONASS_EPHEMERIS = 0x62, MIP_DATA_DESC_GNSS_GALILEO_EPHEMERIS = 0x63, MIP_DATA_DESC_GNSS_GPS_IONO_CORR = 0x71, - MIP_DATA_DESC_GNSS_GLONASS_IONO_CORR = 0x72, MIP_DATA_DESC_GNSS_GALILEO_IONO_CORR = 0x73, }; @@ -161,6 +160,7 @@ enum mip_gnss_signal_id MIP_GNSS_SIGNAL_ID_BEIDOU_B2I = 166, ///< MIP_GNSS_SIGNAL_ID_BEIDOU_B2Q = 167, ///< MIP_GNSS_SIGNAL_ID_BEIDOU_B2IQ = 168, ///< + MIP_GNSS_SIGNAL_ID_BEIDOU_B2A = 169, ///< }; typedef enum mip_gnss_signal_id mip_gnss_signal_id; @@ -1508,8 +1508,9 @@ typedef uint16_t mip_gnss_gps_ephemeris_data_valid_flags; static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_NONE = 0x0000; static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_EPHEMERIS = 0x0001; ///< static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_MODERN_DATA = 0x0002; ///< -static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< -static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0003; +static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_ISC_L5 = 0x0004; ///< +static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< +static const mip_gnss_gps_ephemeris_data_valid_flags MIP_GNSS_GPS_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0007; static inline void insert_mip_gnss_gps_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_gps_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); @@ -1537,8 +1538,8 @@ struct mip_gnss_gps_ephemeris_data double af1; ///< Clock drift in [s/s]. double af2; ///< Clock drift rate in [s/s^2]. double t_gd; ///< T Group Delay [s]. - double ISC_L1CA; - double ISC_L2C; + double ISC_L1CA; ///< Inter-signal correction (L1). + double ISC_L2C; ///< Inter-signal correction (L2, or L5 if isc_l5 flag is set). double t_oe; ///< Reference time for ephemeris in [s]. double a; ///< Semi-major axis [m]. double a_dot; ///< Semi-major axis rate [m/s]. @@ -1578,8 +1579,9 @@ typedef uint16_t mip_gnss_galileo_ephemeris_data_valid_flags; static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_NONE = 0x0000; static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_EPHEMERIS = 0x0001; ///< static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_MODERN_DATA = 0x0002; ///< -static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0003; ///< -static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0003; +static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_ISC_L5 = 0x0004; ///< +static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_FLAGS = 0x0007; ///< +static const mip_gnss_galileo_ephemeris_data_valid_flags MIP_GNSS_GALILEO_EPHEMERIS_DATA_VALID_FLAGS_ALL = 0x0007; static inline void insert_mip_gnss_galileo_ephemeris_data_valid_flags(microstrain_serializer* serializer, const mip_gnss_galileo_ephemeris_data_valid_flags self) { microstrain_insert_u16(serializer, (uint16_t)(self)); @@ -1607,8 +1609,8 @@ struct mip_gnss_galileo_ephemeris_data double af1; ///< Clock drift in [s/s]. double af2; ///< Clock drift rate in [s/s^2]. double t_gd; ///< T Group Delay [s]. - double ISC_L1CA; - double ISC_L2C; + double ISC_L1CA; ///< Inter-signal correction (L1). + double ISC_L2C; ///< Inter-signal correction (L2, or L5 if isc_l5 flag is set). double t_oe; ///< Reference time for ephemeris in [s]. double a; ///< Semi-major axis [m]. double a_dot; ///< Semi-major axis rate [m/s]. diff --git a/src/cpp/mip/definitions/data_gnss.hpp b/src/cpp/mip/definitions/data_gnss.hpp index c1ca92478..06406b600 100644 --- a/src/cpp/mip/definitions/data_gnss.hpp +++ b/src/cpp/mip/definitions/data_gnss.hpp @@ -57,7 +57,6 @@ enum DATA_GLONASS_EPHEMERIS = 0x62, DATA_GALILEO_EPHEMERIS = 0x63, DATA_GPS_IONO_CORR = 0x71, - DATA_GLONASS_IONO_CORR = 0x72, DATA_GALILEO_IONO_CORR = 0x73, }; @@ -148,6 +147,7 @@ enum class GnssSignalId : uint8_t BEIDOU_B2I = 166, ///< BEIDOU_B2Q = 167, ///< BEIDOU_B2IQ = 168, ///< + BEIDOU_B2A = 169, ///< }; enum class SbasSystem : uint8_t @@ -2244,8 +2244,9 @@ struct GpsEphemeris NONE = 0x0000, EPHEMERIS = 0x0001, ///< MODERN_DATA = 0x0002, ///< - FLAGS = 0x0003, ///< - ALL = 0x0003, + ISC_L5 = 0x0004, ///< + FLAGS = 0x0007, ///< + ALL = 0x0007, }; uint16_t value = NONE; @@ -2261,6 +2262,8 @@ struct GpsEphemeris void ephemeris(bool val) { value &= ~EPHEMERIS; if(val) value |= EPHEMERIS; } bool modernData() const { return (value & MODERN_DATA) > 0; } void modernData(bool val) { value &= ~MODERN_DATA; if(val) value |= MODERN_DATA; } + bool iscL5() const { return (value & ISC_L5) > 0; } + void iscL5(bool val) { value &= ~ISC_L5; if(val) value |= ISC_L5; } uint16_t flags() const { return (value & FLAGS) >> 0; } void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } @@ -2280,8 +2283,8 @@ struct GpsEphemeris double af1 = 0; ///< Clock drift in [s/s]. double af2 = 0; ///< Clock drift rate in [s/s^2]. double t_gd = 0; ///< T Group Delay [s]. - double ISC_L1CA = 0; - double ISC_L2C = 0; + double ISC_L1CA = 0; ///< Inter-signal correction (L1). + double ISC_L2C = 0; ///< Inter-signal correction (L2, or L5 if isc_l5 flag is set). double t_oe = 0; ///< Reference time for ephemeris in [s]. double a = 0; ///< Semi-major axis [m]. double a_dot = 0; ///< Semi-major axis rate [m/s]. @@ -2307,7 +2310,7 @@ struct GpsEphemeris static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GPS_EPHEMERIS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GpsEphemeris"; - static constexpr const char* DOC_NAME = "GpsEphemeris"; + static constexpr const char* DOC_NAME = "GPS Ephemeris"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; auto asTuple() const @@ -2344,8 +2347,9 @@ struct GalileoEphemeris NONE = 0x0000, EPHEMERIS = 0x0001, ///< MODERN_DATA = 0x0002, ///< - FLAGS = 0x0003, ///< - ALL = 0x0003, + ISC_L5 = 0x0004, ///< + FLAGS = 0x0007, ///< + ALL = 0x0007, }; uint16_t value = NONE; @@ -2361,6 +2365,8 @@ struct GalileoEphemeris void ephemeris(bool val) { value &= ~EPHEMERIS; if(val) value |= EPHEMERIS; } bool modernData() const { return (value & MODERN_DATA) > 0; } void modernData(bool val) { value &= ~MODERN_DATA; if(val) value |= MODERN_DATA; } + bool iscL5() const { return (value & ISC_L5) > 0; } + void iscL5(bool val) { value &= ~ISC_L5; if(val) value |= ISC_L5; } uint16_t flags() const { return (value & FLAGS) >> 0; } void flags(uint16_t val) { value = (value & ~FLAGS) | (val << 0); } bool allSet() const { return value == ALL; } @@ -2380,8 +2386,8 @@ struct GalileoEphemeris double af1 = 0; ///< Clock drift in [s/s]. double af2 = 0; ///< Clock drift rate in [s/s^2]. double t_gd = 0; ///< T Group Delay [s]. - double ISC_L1CA = 0; - double ISC_L2C = 0; + double ISC_L1CA = 0; ///< Inter-signal correction (L1). + double ISC_L2C = 0; ///< Inter-signal correction (L2, or L5 if isc_l5 flag is set). double t_oe = 0; ///< Reference time for ephemeris in [s]. double a = 0; ///< Semi-major axis [m]. double a_dot = 0; ///< Semi-major axis rate [m/s]. @@ -2407,7 +2413,7 @@ struct GalileoEphemeris static constexpr const uint8_t FIELD_DESCRIPTOR = ::mip::data_gnss::DATA_GALILEO_EPHEMERIS; static constexpr const CompositeDescriptor DESCRIPTOR = {DESCRIPTOR_SET, FIELD_DESCRIPTOR}; static constexpr const char* NAME = "GalileoEphemeris"; - static constexpr const char* DOC_NAME = "GalileoEphemeris"; + static constexpr const char* DOC_NAME = "Galileo Ephemeris"; static constexpr const bool HAS_FUNCTION_SELECTOR = false; auto asTuple() const diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index eb1c48e58..5d661329c 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -21,7 +21,7 @@ struct MetadataFor /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -30,7 +30,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors in the descriptor list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -39,7 +39,7 @@ struct MetadataFor /* .docs = */ "Descriptor list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, }, @@ -68,7 +68,7 @@ struct MetadataFor /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -77,7 +77,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors in the descriptor list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -86,7 +86,7 @@ struct MetadataFor /* .docs = */ "Descriptor list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, }, @@ -115,7 +115,7 @@ struct MetadataFor /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -124,7 +124,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors in the format list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -133,7 +133,7 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, }, @@ -162,7 +162,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -171,7 +171,7 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, }, @@ -201,7 +201,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -210,7 +210,7 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, }, @@ -222,7 +222,7 @@ struct MetadataFor /* .docs = */ "Set, read, or save the format of the IMU data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -239,7 +239,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -248,7 +248,7 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, }, @@ -278,7 +278,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -287,7 +287,7 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, }, @@ -299,7 +299,7 @@ struct MetadataFor /* .docs = */ "Set, read, or save the format of the GNSS data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -316,7 +316,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -325,7 +325,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, }, @@ -355,7 +355,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -364,7 +364,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, }, @@ -376,7 +376,7 @@ struct MetadataFor /* .docs = */ "Set, read, or save the format of the Estimation Filter data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -393,7 +393,7 @@ struct MetadataFor /* .docs = */ "[hz]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -439,7 +439,7 @@ struct MetadataFor /* .docs = */ "[hz]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -485,7 +485,7 @@ struct MetadataFor /* .docs = */ "[hz]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -531,7 +531,7 @@ struct MetadataFor /* .docs = */ "Data descriptor set. Must be supported.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -540,7 +540,7 @@ struct MetadataFor /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -549,7 +549,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors in the format list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -558,7 +558,7 @@ struct MetadataFor /* .docs = */ "Descriptor format list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(2) /* num_descriptors */}, /* .condition = */ {}, }, @@ -587,7 +587,7 @@ struct MetadataFor /* .docs = */ "Echoes the parameter in the command.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -596,7 +596,7 @@ struct MetadataFor /* .docs = */ "Base rate in Hz (0 = variable, unknown, or user-defined rate. Data will be sent when received).", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -625,7 +625,7 @@ struct MetadataFor /* .docs = */ "This is the data descriptor set. It must be a supported descriptor.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -654,7 +654,7 @@ struct MetadataFor /* .docs = */ "Echoes the descriptor set from the command.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -663,7 +663,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors in the list.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -672,7 +672,7 @@ struct MetadataFor /* .docs = */ "List of descriptors and decimations.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, }, @@ -702,7 +702,7 @@ struct MetadataFor /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -711,7 +711,7 @@ struct MetadataFor /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -720,7 +720,7 @@ struct MetadataFor /* .docs = */ "List of descriptors and decimations.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, }, @@ -732,7 +732,7 @@ struct MetadataFor /* .docs = */ "Set, read, or save the format for a given data packet.\n\nThe resulting data messages will maintain the order of descriptors sent in the command.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -744,15 +744,15 @@ struct MetadataFor using type = commands_3dm::NmeaMessage::MessageID; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "GGA", "GPS System Fix Data. Source can be the Filter or GNSS1/2 datasets." }, - { 2, "GLL", "Geographic Position Lat/Lon. Source can be the Filter or GNSS1/2 datasets." }, - { 3, "GSV", "GNSS Satellites in View. Source must be either GNSS1 or GNSS2 datasets. The talker ID must be set to IGNORED." }, - { 4, "RMC", "Recommended Minimum Specific GNSS Data. Source can be the Filter or GNSS1/2 datasets." }, - { 5, "VTG", "Course over Ground. Source can be the Filter or GNSS1/2 datasets." }, - { 6, "HDT", "Heading, True. Source can be the Filter or GNSS1/2 datasets." }, - { 7, "ZDA", "Time & Date. Source must be the GNSS1 or GNSS2 datasets." }, - { 129, "MSRA", "MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED." }, - { 130, "MSRR", "MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED." }, + { uint32_t(1), "GGA", "GPS System Fix Data. Source can be the Filter or GNSS1/2 datasets." }, + { uint32_t(2), "GLL", "Geographic Position Lat/Lon. Source can be the Filter or GNSS1/2 datasets." }, + { uint32_t(3), "GSV", "GNSS Satellites in View. Source must be either GNSS1 or GNSS2 datasets. The talker ID must be set to IGNORED." }, + { uint32_t(4), "RMC", "Recommended Minimum Specific GNSS Data. Source can be the Filter or GNSS1/2 datasets." }, + { uint32_t(5), "VTG", "Course over Ground. Source can be the Filter or GNSS1/2 datasets." }, + { uint32_t(6), "HDT", "Heading, True. Source can be the Filter or GNSS1/2 datasets." }, + { uint32_t(7), "ZDA", "Time & Date. Source must be the GNSS1 or GNSS2 datasets." }, + { uint32_t(129), "MSRA", "MicroStrain proprietary Euler angles. Source must be the Filter dataset. The talker ID must be set to IGNORED." }, + { uint32_t(130), "MSRR", "MicroStrain proprietary Angular Rate/Acceleration. Source must be the Sensor dataset. The talker ID must be set to IGNORED." }, }; static constexpr inline EnumInfo value = { @@ -770,11 +770,11 @@ struct MetadataFor using type = commands_3dm::NmeaMessage::TalkerID; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "IGNORED", "Talker ID cannot be changed." }, - { 1, "GNSS", "NMEA message will be produced with talker id 'GN'." }, - { 2, "GPS", "NMEA message will be produced with talker id 'GP'." }, - { 3, "GALILEO", "NMEA message will be produced with talker id 'GA'." }, - { 4, "GLONASS", "NMEA message will be produced with talker id 'GL'." }, + { uint32_t(0), "IGNORED", "Talker ID cannot be changed." }, + { uint32_t(1), "GNSS", "NMEA message will be produced with talker id 'GN'." }, + { uint32_t(2), "GPS", "NMEA message will be produced with talker id 'GP'." }, + { uint32_t(3), "GALILEO", "NMEA message will be produced with talker id 'GA'." }, + { uint32_t(4), "GLONASS", "NMEA message will be produced with talker id 'GL'." }, }; static constexpr inline EnumInfo value = { @@ -797,7 +797,7 @@ struct MetadataFor /* .docs = */ "NMEA sentence type.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -806,7 +806,7 @@ struct MetadataFor /* .docs = */ "NMEA talker ID. Ignored for proprietary sentences.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -815,7 +815,7 @@ struct MetadataFor /* .docs = */ "Data descriptor set where the data will be sourced. Available options depend on the sentence.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -824,7 +824,7 @@ struct MetadataFor /* .docs = */ "Decimation from the base rate for source_desc_set. Frequency is limited to 10 Hz or the base rate, whichever is lower. Must be 0 when polling.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -849,7 +849,7 @@ struct MetadataFor /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -858,7 +858,7 @@ struct MetadataFor /* .docs = */ "Number of format entries (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -867,7 +867,7 @@ struct MetadataFor /* .docs = */ "List of format entries.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {40, microstrain::Index(1) /* count */}, /* .condition = */ {}, }, @@ -896,7 +896,7 @@ struct MetadataFor /* .docs = */ "Number of format entries (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -905,7 +905,7 @@ struct MetadataFor /* .docs = */ "List of format entries.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {40, microstrain::Index(0) /* count */}, /* .condition = */ {}, }, @@ -935,7 +935,7 @@ struct MetadataFor /* .docs = */ "Number of format entries (limited by payload size)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -944,7 +944,7 @@ struct MetadataFor /* .docs = */ "List of format entries.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {40, microstrain::Index(0) /* count */}, /* .condition = */ {}, }, @@ -956,7 +956,7 @@ struct MetadataFor /* .docs = */ "Set, read, or save the NMEA message format.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -978,7 +978,7 @@ struct MetadataFor /* .docs = */ "Save, Load, or Reset to Default the values for all device settings.\n\nWhen a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory.\n\nThis command should have a long timeout as it may take up to 1 second to complete.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {false, false, true, true, true, true}, + /* .functions = */ {false, false, true, true, true}, /* .proprietary = */ false, /* .response = */ nullptr, }; @@ -995,7 +995,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1025,7 +1025,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1037,7 +1037,7 @@ struct MetadataFor /* .docs = */ "Read, Save, Load, or Reset to Default the baud rate of the main communication channel.\n\nFor all functions except 0x01 (use new settings), the new baud rate value is ignored.\nPlease see the device user manual for supported baud rates.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1049,9 +1049,9 @@ struct MetadataFor using type = commands_3dm::FactoryStreaming::Action; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "OVERWRITE", "Replaces the message format(s), removing any existing descriptors." }, - { 1, "MERGE", "Merges support descriptors into existing format(s). May reorder descriptors." }, - { 2, "ADD", "Adds descriptors to the current message format(s) without changing existing descriptors. May result in duplicates." }, + { uint32_t(0), "OVERWRITE", "Replaces the message format(s), removing any existing descriptors." }, + { uint32_t(1), "MERGE", "Merges support descriptors into existing format(s). May reorder descriptors." }, + { uint32_t(2), "ADD", "Adds descriptors to the current message format(s) without changing existing descriptors. May result in duplicates." }, }; static constexpr inline EnumInfo value = { @@ -1074,7 +1074,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1083,7 +1083,7 @@ struct MetadataFor /* .docs = */ "Reserved. Set to 0x00.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1112,7 +1112,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1121,7 +1121,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1151,7 +1151,7 @@ struct MetadataFor /* .docs = */ "The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets.\nOn Generation 5 products, this must be one of the above legacy constants.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1160,7 +1160,7 @@ struct MetadataFor /* .docs = */ "True or false to enable or disable the stream.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1172,7 +1172,7 @@ struct MetadataFor /* .docs = */ "Enable/disable the selected data stream.\n\nEach data stream (descriptor set) can be enabled or disabled.\nThe default for the device is all streams enabled.\nFor all functions except 0x01 (use new setting),\nthe new enable flag value is ignored and can be omitted.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1184,12 +1184,12 @@ struct MetadataFor using type = commands_3dm::ConstellationSettings::ConstellationId; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "GPS", "GPS (G1-G32)" }, - { 1, "SBAS", "SBAS (S120-S158)" }, - { 2, "GALILEO", "GALILEO (E1-E36)" }, - { 3, "BeiDou", "BeiDou (B1-B37)" }, - { 5, "QZSS", "QZSS (Q1-Q5)" }, - { 6, "GLONASS", "GLONASS (R1-R32)" }, + { uint32_t(0), "GPS", "GPS (G1-G32)" }, + { uint32_t(1), "SBAS", "SBAS (S120-S158)" }, + { uint32_t(2), "GALILEO", "GALILEO (E1-E36)" }, + { uint32_t(3), "BeiDou", "BeiDou (B1-B37)" }, + { uint32_t(5), "QZSS", "QZSS (Q1-Q5)" }, + { uint32_t(6), "GLONASS", "GLONASS (R1-R32)" }, }; static constexpr inline EnumInfo value = { @@ -1207,7 +1207,7 @@ struct MetadataFor using type = commands_3dm::ConstellationSettings::OptionFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "L1SAIF", "Available only for QZSS" }, + { uint32_t(1), "L1SAIF", "Available only for QZSS" }, }; static constexpr inline BitfieldInfo value = { @@ -1230,7 +1230,7 @@ struct MetadataFor /* .docs = */ "Constellation ID", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -1239,7 +1239,7 @@ struct MetadataFor /* .docs = */ "Enable/Disable constellation", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -1248,7 +1248,7 @@ struct MetadataFor /* .docs = */ "Minimum number of channels reserved for this constellation", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -1257,16 +1257,16 @@ struct MetadataFor /* .docs = */ "Maximum number of channels to use for this constallation", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "option_flags", /* .docs = */ "Constellation option Flags", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -1291,7 +1291,7 @@ struct MetadataFor /* .docs = */ "Maximum channels available", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1300,7 +1300,7 @@ struct MetadataFor /* .docs = */ "Maximum channels to use", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1309,7 +1309,7 @@ struct MetadataFor /* .docs = */ "Number of constellation configurations", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1318,7 +1318,7 @@ struct MetadataFor /* .docs = */ "Constellation Settings", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(2) /* config_count */}, /* .condition = */ {}, }, @@ -1348,7 +1348,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1357,7 +1357,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1366,7 +1366,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(1) /* config_count */}, /* .condition = */ {}, }, @@ -1378,7 +1378,7 @@ struct MetadataFor /* .docs = */ "This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation.\n\nMaximum number of tracking channels to use (total for all constellations):\n0 to max_channels_available (from reply message)\n\nFor each constellation you wish to use, include a ConstellationSettings struct. Note the following:\n\nTotal number of tracking channels (sum of 'reserved_channels' for all constellations) must be <= 32:\n0 -> 32 Number of reserved channels\n0 -> 32 Max number of channels (>= reserved channels)\n\nThe factory default setting is: GPS and GLONASS enabled. Min/Max for GPS = 8/16, GLONASS = 8/14, SBAS = 1/3, QZSS = 0/3.\n\nWarning: SBAS functionality shall not be used in 'safety of life' applications!\nWarning: Any setting that causes the total reserved channels to exceed 32 will result in a NACK.\nWarning: You cannot enable GLONASS and BeiDou at the same time.\nNote: Enabling SBAS and QZSS augments GPS accuracy.\nNote: It is recommended to disable GLONASS and BeiDou if a GPS-only antenna or GPS-only SAW filter is used.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1390,9 +1390,9 @@ struct MetadataFor using type = commands_3dm::GnssSbasSettings::SBASOptions; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "enable_ranging", "Use SBAS pseudo-ranges in position solution" }, - { 2, "enable_corrections", "Use SBAS differential corrections" }, - { 4, "apply_integrity", "Use SBAS integrity information. If enabled, only GPS satellites for which integrity information is available will be used." }, + { uint32_t(1), "enable_ranging", "Use SBAS pseudo-ranges in position solution" }, + { uint32_t(2), "enable_corrections", "Use SBAS differential corrections" }, + { uint32_t(4), "apply_integrity", "Use SBAS integrity information. If enabled, only GPS satellites for which integrity information is available will be used." }, }; static constexpr inline BitfieldInfo value = { @@ -1415,16 +1415,16 @@ struct MetadataFor /* .docs = */ "0 - SBAS Disabled, 1 - SBAS enabled", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "sbas_options", /* .docs = */ "SBAS options, see definition", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1433,7 +1433,7 @@ struct MetadataFor /* .docs = */ "Number of SBAS PRNs to include in search (0 = include all)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1442,7 +1442,7 @@ struct MetadataFor /* .docs = */ "List of specific SBAS PRNs to search for", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {39, microstrain::Index(2) /* num_included_prns */}, /* .condition = */ {}, }, @@ -1472,16 +1472,16 @@ struct MetadataFor /* .docs = */ "0 - SBAS Disabled, 1 - SBAS enabled", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "sbas_options", /* .docs = */ "SBAS options, see definition", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1490,7 +1490,7 @@ struct MetadataFor /* .docs = */ "Number of SBAS PRNs to include in search (0 = include all)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1499,7 +1499,7 @@ struct MetadataFor /* .docs = */ "List of specific SBAS PRNs to search for", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {39, microstrain::Index(2) /* num_included_prns */}, /* .condition = */ {}, }, @@ -1511,7 +1511,7 @@ struct MetadataFor /* .docs = */ "Configure the SBAS subsystem\n\n\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1523,8 +1523,8 @@ struct MetadataFor using type = commands_3dm::GnssAssistedFix::AssistedFixOption; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "NONE", "No assisted fix (default)" }, - { 1, "ENABLED", "Enable assisted fix" }, + { uint32_t(0), "NONE", "No assisted fix (default)" }, + { uint32_t(1), "ENABLED", "Enable assisted fix" }, }; static constexpr inline EnumInfo value = { @@ -1547,7 +1547,7 @@ struct MetadataFor /* .docs = */ "Assisted fix options", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1556,7 +1556,7 @@ struct MetadataFor /* .docs = */ "Assisted fix flags (set to 0xFF)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1586,7 +1586,7 @@ struct MetadataFor /* .docs = */ "Assisted fix options", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1595,7 +1595,7 @@ struct MetadataFor /* .docs = */ "Assisted fix flags (set to 0xFF)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1607,7 +1607,7 @@ struct MetadataFor /* .docs = */ "Set the options for assisted GNSS fix.\n\nDevices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM.\nThese storage mechanisms are used to retain information about the last good GNSS fix. This can greatly reduces the TTFF (Time To First Fix) depending on the age of the stored information.\nThe TTFF can be as low as one second, or up to the equivalent of a cold start. There is a small increase in power used when enabling assisted fix.\n\nThe fastest fix will be obtained by supplying the device with a GNSS Assist Time Update message containing the current GPS time immediately after subsequent power up.\nThis allows the device to determine if the last GNSS information saved is still fresh enough to improve the TTFF.\n\nNOTE: Non-volatile GNSS memory is cleared when going from an enabled state to a disabled state.\nWARNING: The clearing operation results in an erase operation on the GNSS Flash. The flash has a limited durability of 100,000 write/erase cycles", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1624,7 +1624,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1633,7 +1633,7 @@ struct MetadataFor /* .docs = */ "GPS Weeks since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1642,7 +1642,7 @@ struct MetadataFor /* .docs = */ "Accuracy of time information [seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1672,7 +1672,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1681,7 +1681,7 @@ struct MetadataFor /* .docs = */ "GPS Weeks since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1690,7 +1690,7 @@ struct MetadataFor /* .docs = */ "Accuracy of time information [seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1702,7 +1702,7 @@ struct MetadataFor /* .docs = */ "Provide the GNSS subsystem with initial time information.\n\nThis message is required immediately after power up if GNSS Assist was enabled when the device was powered off.\nThis will initialize the subsystem clock to help reduce the time to first fix (TTFF).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, false, false, false, true}, + /* .functions = */ {true, true, false, false, false}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1719,7 +1719,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1728,7 +1728,7 @@ struct MetadataFor /* .docs = */ "True if the filter is currently enabled.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1737,7 +1737,7 @@ struct MetadataFor /* .docs = */ "True if the filter cutoff was manually configured.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1746,7 +1746,7 @@ struct MetadataFor /* .docs = */ "The cutoff frequency of the filter. If the filter is in\nauto mode, this value is unspecified.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1755,7 +1755,7 @@ struct MetadataFor /* .docs = */ "Reserved and must be ignored.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1785,7 +1785,7 @@ struct MetadataFor /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.\nSupported values are accel (0x04), gyro (0x05), mag (0x06), and\npressure (0x17), provided the data is supported by the device.\nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1794,7 +1794,7 @@ struct MetadataFor /* .docs = */ "The target data will be filtered if this is true.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1803,7 +1803,7 @@ struct MetadataFor /* .docs = */ "If false, the cutoff frequency is set to half of the\nstreaming rate as configured by the message format command.\nOtherwise, the cutoff frequency is set according to the\nfollowing 'frequency' parameter.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1812,7 +1812,7 @@ struct MetadataFor /* .docs = */ "-3dB cutoff frequency in Hz. Will not affect filtering if 'manual' is false.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1821,7 +1821,7 @@ struct MetadataFor /* .docs = */ "Reserved, set to 0x00.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1833,7 +1833,7 @@ struct MetadataFor /* .docs = */ "Advanced configuration for the IMU data quantity low-pass filters.\n\nDeprecated, use the lowpass filter (0x0C,0x54) command instead.\n\nThe scaled data quantities are by default filtered through a single-pole IIR low-pass filter\nwhich is configured with a -3dB cutoff frequency of half the reporting frequency (set by\ndecimation factor in the IMU Message Format command) to prevent aliasing on a per data\nquantity basis. This advanced configuration command allows for the cutoff frequency to\nbe configured independently of the data reporting frequency as well as allowing for a\ncomplete bypass of the digital low-pass filter.\n\nPossible data descriptors:\n0x04 - Scaled accelerometer data\n0x05 - Scaled gyro data\n0x06 - Scaled magnetometer data (if applicable)\n0x17 - Scaled pressure data (if applicable)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1845,11 +1845,11 @@ struct MetadataFor using type = commands_3dm::PpsSource::Source; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "DISABLED", "PPS output is disabled. Not valid for PPS source command." }, - { 1, "RECEIVER_1", "PPS is provided by GNSS receiver 1." }, - { 2, "RECEIVER_2", "PPS is provided by GNSS receiver 2." }, - { 3, "GPIO", "PPS is provided to an external GPIO pin. Use the GPIO Setup command to choose and configure the pin." }, - { 4, "GENERATED", "PPS is generated from the system oscillator." }, + { uint32_t(0), "DISABLED", "PPS output is disabled. Not valid for PPS source command." }, + { uint32_t(1), "RECEIVER_1", "PPS is provided by GNSS receiver 1." }, + { uint32_t(2), "RECEIVER_2", "PPS is provided by GNSS receiver 2." }, + { uint32_t(3), "GPIO", "PPS is provided to an external GPIO pin. Use the GPIO Setup command to choose and configure the pin." }, + { uint32_t(4), "GENERATED", "PPS is generated from the system oscillator." }, }; static constexpr inline EnumInfo value = { @@ -1872,7 +1872,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1902,7 +1902,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1914,7 +1914,7 @@ struct MetadataFor /* .docs = */ "Controls the Pulse Per Second (PPS) source.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1926,12 +1926,12 @@ struct MetadataFor using type = commands_3dm::GpioConfig::Feature; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "UNUSED", "The pin is not used. It may be technically possible to read the pin state in this mode, but this is not guaranteed to be true of all devices or pins." }, - { 1, "GPIO", "General purpose input or output. Use this for direct control of pin output state or to stream the state of the pin." }, - { 2, "PPS", "Pulse per second input or output." }, - { 3, "ENCODER", "Motor encoder/odometer input." }, - { 4, "TIMESTAMP", "Precision Timestamping. Use with Event Trigger Configuration (0x0C,0x2E)." }, - { 5, "UART", "UART data or control lines." }, + { uint32_t(0), "UNUSED", "The pin is not used. It may be technically possible to read the pin state in this mode, but this is not guaranteed to be true of all devices or pins." }, + { uint32_t(1), "GPIO", "General purpose input or output. Use this for direct control of pin output state or to stream the state of the pin." }, + { uint32_t(2), "PPS", "Pulse per second input or output." }, + { uint32_t(3), "ENCODER", "Motor encoder/odometer input." }, + { uint32_t(4), "TIMESTAMP", "Precision Timestamping. Use with Event Trigger Configuration (0x0C,0x2E)." }, + { uint32_t(5), "UART", "UART data or control lines." }, }; static constexpr inline EnumInfo value = { @@ -1949,21 +1949,21 @@ struct MetadataFor using type = commands_3dm::GpioConfig::Behavior; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "UNUSED", "Use 0 unless otherwise specified." }, - { 1, "GPIO_INPUT", "Pin will be an input. This can be used to stream or poll the value and is the default setting." }, - { 2, "GPIO_OUTPUT_LOW", "Pin is an output initially in the LOW state. This state will be restored during system startup if the configuration is saved." }, - { 3, "GPIO_OUTPUT_HIGH", "Pin is an output initially in the HIGH state. This state will be restored during system startup if the configuration is saved." }, - { 1, "PPS_INPUT", "Pin will receive the pulse-per-second signal. Only one pin can have this behavior. This will only work if the PPS Source command is configured to GPIO." }, - { 2, "PPS_OUTPUT", "Pin will transmit the pulse-per-second signal from the device." }, - { 1, "ENCODER_A", "Encoder 'A' quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence." }, - { 2, "ENCODER_B", "Encoder 'B' quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence." }, - { 1, "TIMESTAMP_RISING", "Rising edges will be timestamped." }, - { 2, "TIMESTAMP_FALLING", "Falling edges will be timestamped." }, - { 3, "TIMESTAMP_EITHER", "Both rising and falling edges will be timestamped." }, - { 33, "UART_PORT2_TX", "(0x21) UART port 2 transmit." }, - { 34, "UART_PORT2_RX", "(0x22) UART port 2 receive." }, - { 49, "UART_PORT3_TX", "(0x31) UART port 3 transmit." }, - { 50, "UART_PORT3_RX", "(0x32) UART port 3 receive." }, + { uint32_t(0), "UNUSED", "Use 0 unless otherwise specified." }, + { uint32_t(1), "GPIO_INPUT", "Pin will be an input. This can be used to stream or poll the value and is the default setting." }, + { uint32_t(2), "GPIO_OUTPUT_LOW", "Pin is an output initially in the LOW state. This state will be restored during system startup if the configuration is saved." }, + { uint32_t(3), "GPIO_OUTPUT_HIGH", "Pin is an output initially in the HIGH state. This state will be restored during system startup if the configuration is saved." }, + { uint32_t(1), "PPS_INPUT", "Pin will receive the pulse-per-second signal. Only one pin can have this behavior. This will only work if the PPS Source command is configured to GPIO." }, + { uint32_t(2), "PPS_OUTPUT", "Pin will transmit the pulse-per-second signal from the device." }, + { uint32_t(1), "ENCODER_A", "Encoder 'A' quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence." }, + { uint32_t(2), "ENCODER_B", "Encoder 'B' quadrature input. Only one pin can have this behavior. The last command to set this behavior will take precedence." }, + { uint32_t(1), "TIMESTAMP_RISING", "Rising edges will be timestamped." }, + { uint32_t(2), "TIMESTAMP_FALLING", "Falling edges will be timestamped." }, + { uint32_t(3), "TIMESTAMP_EITHER", "Both rising and falling edges will be timestamped." }, + { uint32_t(33), "UART_PORT2_TX", "(0x21) UART port 2 transmit." }, + { uint32_t(34), "UART_PORT2_RX", "(0x22) UART port 2 receive." }, + { uint32_t(49), "UART_PORT3_TX", "(0x31) UART port 3 transmit." }, + { uint32_t(50), "UART_PORT3_RX", "(0x32) UART port 3 receive." }, }; static constexpr inline EnumInfo value = { @@ -1981,9 +1981,9 @@ struct MetadataFor using type = commands_3dm::GpioConfig::PinMode; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "open_drain", "The pin will be an open-drain output. The state will be either LOW or FLOATING instead of LOW or HIGH, respectively. This is used to connect multiple open-drain outputs from several devices. An internal or external pull-up resistor is typically used in combination. The maximum voltage of an open drain output is subject to the device maximum input voltage range found in the specifications." }, - { 2, "pulldown", "The pin will have an internal pull-down resistor enabled. This is useful for connecting inputs to signals which can only be pulled high such as mechanical switches. Cannot be used in combination with pull-up. See the device specifications for the resistance value." }, - { 4, "pullup", "The pin will have an internal pull-up resistor enabled. Useful for connecting inputs to signals which can only be pulled low such as mechanical switches, or in combination with an open drain output. Cannot be used in combination with pull-down. See the device specifications for the resistance value. Use of this mode may restrict the maximum allowed input voltage. See the device datasheet for details." }, + { uint32_t(1), "open_drain", "The pin will be an open-drain output. The state will be either LOW or FLOATING instead of LOW or HIGH, respectively. This is used to connect multiple open-drain outputs from several devices. An internal or external pull-up resistor is typically used in combination. The maximum voltage of an open drain output is subject to the device maximum input voltage range found in the specifications." }, + { uint32_t(2), "pulldown", "The pin will have an internal pull-down resistor enabled. This is useful for connecting inputs to signals which can only be pulled high such as mechanical switches. Cannot be used in combination with pull-up. See the device specifications for the resistance value." }, + { uint32_t(4), "pullup", "The pin will have an internal pull-up resistor enabled. Useful for connecting inputs to signals which can only be pulled low such as mechanical switches, or in combination with an open drain output. Cannot be used in combination with pull-down. See the device specifications for the resistance value. Use of this mode may restrict the maximum allowed input voltage. See the device datasheet for details." }, }; static constexpr inline BitfieldInfo value = { @@ -2006,7 +2006,7 @@ struct MetadataFor /* .docs = */ "GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2015,7 +2015,7 @@ struct MetadataFor /* .docs = */ "Determines how the pin will be used.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2024,16 +2024,16 @@ struct MetadataFor /* .docs = */ "Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.)", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "pin_mode", /* .docs = */ "GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2063,7 +2063,7 @@ struct MetadataFor /* .docs = */ "GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2072,7 +2072,7 @@ struct MetadataFor /* .docs = */ "Determines how the pin will be used.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2081,16 +2081,16 @@ struct MetadataFor /* .docs = */ "Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.)", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "pin_mode", /* .docs = */ "GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2102,7 +2102,7 @@ struct MetadataFor /* .docs = */ "Configures the user GPIO pins on the connector for use with several built-in functions or for general input or output.\n\nGPIO pins are device-dependent. Some features are only available on\ncertain pins. Some behaviors require specific configurations.\nConsult the device user manual for restrictions and default settings.\n\nTo avoid glitches on GPIOs configured as an output in a mode other than\nGPIO, always configure the relevant function before setting up the pin\nwith this command. Otherwise, the pin state will be undefined between\nthis command and the one to set up the feature. For input pins, use\nthis command first so the state is well-defined when the feature is\ninitialized.\n\nSome configurations can only be active on one pin at a time. If such\nconfiguration is applied to a second pin, the second one will take\nprecedence and the original pin's configuration will be reset.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2119,7 +2119,7 @@ struct MetadataFor /* .docs = */ "GPIO pin number counting from 1. Cannot be 0.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, false, false, false, true}, + /* .attributes = */ {true, true, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2128,7 +2128,7 @@ struct MetadataFor /* .docs = */ "The pin state.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2158,7 +2158,7 @@ struct MetadataFor /* .docs = */ "GPIO pin number counting from 1. Cannot be 0.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, false, false, false, true}, + /* .attributes = */ {true, true, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2167,7 +2167,7 @@ struct MetadataFor /* .docs = */ "The pin state.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2179,7 +2179,7 @@ struct MetadataFor /* .docs = */ "Allows the state of the pin to be read or controlled.\n\nThis command serves two purposes: 1) To allow reading the state of a pin via command,\nrather than polling a data quantity, and 2) to provide a way to set the output state\nwithout also having to specify the operating mode.\n\nThe state read back from the pin is the physical state of the pin, rather than a\nconfiguration value. The state can be read regardless of its configuration as long as\nthe device supports GPIO input on that pin. If the pin is set to an output, the read\nvalue would match the output value.\n\nWhile the state of a pin can always be set, it will only have an observable effect if\nthe pin is set to output mode.\n\nThis command does not support saving, loading, or resetting the state. Instead, use the\nGPIO Configuration command, which allows the initial state to be configured.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, false, false, false, true}, + /* .functions = */ {true, true, false, false, false}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2191,8 +2191,8 @@ struct MetadataFor using type = commands_3dm::Odometer::Mode; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "DISABLED", "Encoder is disabled." }, - { 2, "QUADRATURE", "Quadrature encoder mode." }, + { uint32_t(0), "DISABLED", "Encoder is disabled." }, + { uint32_t(2), "QUADRATURE", "Quadrature encoder mode." }, }; static constexpr inline EnumInfo value = { @@ -2215,7 +2215,7 @@ struct MetadataFor /* .docs = */ "Mode setting.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2224,7 +2224,7 @@ struct MetadataFor /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2233,7 +2233,7 @@ struct MetadataFor /* .docs = */ "Uncertainty in encoder counts to distance translation (1-sigma value) [m/m].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2263,7 +2263,7 @@ struct MetadataFor /* .docs = */ "Mode setting.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2272,7 +2272,7 @@ struct MetadataFor /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2281,7 +2281,7 @@ struct MetadataFor /* .docs = */ "Uncertainty in encoder counts to distance translation (1-sigma value) [m/m].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2293,7 +2293,7 @@ struct MetadataFor /* .docs = */ "Configures the hardware odometer interface.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2305,8 +2305,8 @@ struct MetadataFor using type = commands_3dm::GetEventSupport::Query; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "TRIGGER_TYPES", "Query the supported trigger types and max count for each." }, - { 2, "ACTION_TYPES", "Query the supported action types and max count for each." }, + { uint32_t(1), "TRIGGER_TYPES", "Query the supported trigger types and max count for each." }, + { uint32_t(2), "ACTION_TYPES", "Query the supported action types and max count for each." }, }; static constexpr inline EnumInfo value = { @@ -2329,7 +2329,7 @@ struct MetadataFor /* .docs = */ "Trigger or action type, as defined in the respective setup command.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2338,7 +2338,7 @@ struct MetadataFor /* .docs = */ "This is the maximum number of instances supported for this type.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2363,7 +2363,7 @@ struct MetadataFor /* .docs = */ "Query type specified in the command.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2372,7 +2372,7 @@ struct MetadataFor /* .docs = */ "Number of slots available. The 'instance' number for\nthe configuration or control commands must be between 1 and this value.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2381,7 +2381,7 @@ struct MetadataFor /* .docs = */ "Number of supported types.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2390,7 +2390,7 @@ struct MetadataFor /* .docs = */ "List of supported types.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(2) /* num_entries */}, /* .condition = */ {}, }, @@ -2419,7 +2419,7 @@ struct MetadataFor /* .docs = */ "What type of information to retrieve.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2443,10 +2443,10 @@ struct MetadataFor using type = commands_3dm::EventControl::Mode; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "DISABLED", "Trigger is disabled." }, - { 1, "ENABLED", "Trigger is enabled and will work normally." }, - { 2, "TEST", "Forces the trigger to the active state for testing purposes." }, - { 3, "TEST_PULSE", "Trigger is forced to the active state for one event cycle only. After the test cycle, the mode reverts to the previous state (either enabled or disabled)." }, + { uint32_t(0), "DISABLED", "Trigger is disabled." }, + { uint32_t(1), "ENABLED", "Trigger is enabled and will work normally." }, + { uint32_t(2), "TEST", "Forces the trigger to the active state for testing purposes." }, + { uint32_t(3), "TEST_PULSE", "Trigger is forced to the active state for one event cycle only. After the test cycle, the mode reverts to the previous state (either enabled or disabled)." }, }; static constexpr inline EnumInfo value = { @@ -2469,7 +2469,7 @@ struct MetadataFor /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2478,7 +2478,7 @@ struct MetadataFor /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2508,7 +2508,7 @@ struct MetadataFor /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2517,7 +2517,7 @@ struct MetadataFor /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2529,7 +2529,7 @@ struct MetadataFor /* .docs = */ "Enables or disables event triggers.\n\nTriggers can be disabled, enabled, and tested. While disabled, a trigger will\nnot evaluate its logic and effective behave like no trigger is configured.\nA disabled trigger will not activate any actions. Triggers are disabled by default.\n\nUse this command to enable (or disable) a trigger, or to place it into a test mode.\nWhen in test mode, the trigger logic is disabled but the output is forced to\nthe active state, meaning that it will behave as if the trigger logic is satisfied\nand any associated actions will execute.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2541,9 +2541,9 @@ struct MetadataFor using type = commands_3dm::GetEventTriggerStatus::Status; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "active", "True if the trigger is currently active (either due to its logic or being in test mode)." }, - { 2, "enabled", "True if the trigger is enabled." }, - { 4, "test", "True if the trigger is in test mode." }, + { uint32_t(1), "active", "True if the trigger is currently active (either due to its logic or being in test mode)." }, + { uint32_t(2), "enabled", "True if the trigger is enabled." }, + { uint32_t(4), "test", "True if the trigger is in test mode." }, }; static constexpr inline BitfieldInfo value = { @@ -2566,16 +2566,16 @@ struct MetadataFor /* .docs = */ "Configured trigger type.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "status", /* .docs = */ "Trigger status.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2600,7 +2600,7 @@ struct MetadataFor /* .docs = */ "Number of entries requested. If requested_count was 0, this is the number of supported trigger slots.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2609,7 +2609,7 @@ struct MetadataFor /* .docs = */ "A list of the configured triggers. Entries are in the order requested, or in increasing order if count was 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {20, microstrain::Index(0) /* count */}, /* .condition = */ {}, }, @@ -2638,7 +2638,7 @@ struct MetadataFor /* .docs = */ "Number of entries requested. If 0, requests all trigger slots.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2647,7 +2647,7 @@ struct MetadataFor /* .docs = */ "List of trigger instances to query.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {20, microstrain::Index(0) /* requested_count */}, /* .condition = */ {}, }, @@ -2676,7 +2676,7 @@ struct MetadataFor /* .docs = */ "Configured action type.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2685,7 +2685,7 @@ struct MetadataFor /* .docs = */ "Associated trigger instance.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2710,7 +2710,7 @@ struct MetadataFor /* .docs = */ "Number of entries requested. If requested_count was 0, this is the number of supported action slots.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2719,7 +2719,7 @@ struct MetadataFor /* .docs = */ "A list of the configured actions. Entries are in the order requested, or in increasing order if count was 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {20, microstrain::Index(0) /* count */}, /* .condition = */ {}, }, @@ -2748,7 +2748,7 @@ struct MetadataFor /* .docs = */ "Number of entries requested. If 0, requests all action slots.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2757,7 +2757,7 @@ struct MetadataFor /* .docs = */ "List of action instances to query.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {20, microstrain::Index(0) /* requested_count */}, /* .condition = */ {}, }, @@ -2781,10 +2781,10 @@ struct MetadataFor using type = commands_3dm::EventTrigger::GpioParams::Mode; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "DISABLED", "The pin will have no effect and the trigger will never activate." }, - { 1, "WHILE_HIGH", "The trigger will be active while the pin is high." }, - { 2, "WHILE_LOW", "The trigger will be active while the pin is low." }, - { 4, "EDGE", "Use if the pin is configured for timestamping via the 3DM Gpio Configuration command (0x0C41)." }, + { uint32_t(0), "DISABLED", "The pin will have no effect and the trigger will never activate." }, + { uint32_t(1), "WHILE_HIGH", "The trigger will be active while the pin is high." }, + { uint32_t(2), "WHILE_LOW", "The trigger will be active while the pin is low." }, + { uint32_t(4), "EDGE", "Use if the pin is configured for timestamping via the 3DM Gpio Configuration command (0x0C41)." }, }; static constexpr inline EnumInfo value = { @@ -2807,7 +2807,7 @@ struct MetadataFor /* .docs = */ "GPIO pin number.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2816,7 +2816,7 @@ struct MetadataFor /* .docs = */ "How the pin state affects the trigger.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2836,8 +2836,8 @@ struct MetadataFor using type = commands_3dm::EventTrigger::ThresholdParams::Type; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "WINDOW", "Window comparison. Trigger is active if low_thres <= value <= high_thres. If the thresholds are reversed, the trigger is active when value < high_thres or value > low_thres." }, - { 2, "INTERVAL", "Trigger at evenly-spaced intervals. Normally used with time fields to trigger periodically. Trigger is active when (value % interval) <= int_thres. If the thresholds are reversed (high_thres < low_thres) then the trigger is active when (value % low_thres) > high_thres." }, + { uint32_t(1), "WINDOW", "Window comparison. Trigger is active if low_thres <= value <= high_thres. If the thresholds are reversed, the trigger is active when value < high_thres or value > low_thres." }, + { uint32_t(2), "INTERVAL", "Trigger at evenly-spaced intervals. Normally used with time fields to trigger periodically. Trigger is active when (value % interval) <= int_thres. If the thresholds are reversed (high_thres < low_thres) then the trigger is active when (value % low_thres) > high_thres." }, }; static constexpr inline EnumInfo value = { @@ -2860,7 +2860,7 @@ struct MetadataFor /* .docs = */ "Descriptor set of target data quantity.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2869,7 +2869,7 @@ struct MetadataFor /* .docs = */ "Field descriptor of target data quantity.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2878,7 +2878,7 @@ struct MetadataFor /* .docs = */ "1-based index of the target parameter within the MIP field. E.g. for Scaled Accel (0x80,0x04) a value of 2 would represent the Y axis.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2887,7 +2887,7 @@ struct MetadataFor /* .docs = */ "Determines the type of comparison.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2896,7 +2896,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::WINDOW)} /* type == WINDOW */, }, @@ -2905,7 +2905,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::INTERVAL)} /* type == INTERVAL */, }, @@ -2914,7 +2914,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::WINDOW)} /* type == WINDOW */, }, @@ -2923,7 +2923,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::INTERVAL)} /* type == INTERVAL */, }, @@ -2948,7 +2948,7 @@ struct MetadataFor /* .docs = */ "The last column of a truth table describing the output given the state of each input.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -2957,7 +2957,7 @@ struct MetadataFor /* .docs = */ "List of trigger IDs for inputs. Use 0 for unused inputs.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 4, /* .condition = */ {}, }, @@ -2977,10 +2977,10 @@ struct MetadataFor using type = commands_3dm::EventTrigger::Type; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "NONE", "No trigger selected. The state will always be inactive." }, - { 1, "GPIO", "Trigger based on the state of a GPIO pin. See GpioParams." }, - { 2, "THRESHOLD", "Compare a data quantity against a high and low threshold. See ThresholdParams." }, - { 3, "COMBINATION", "Logical combination of two or more triggers. See CombinationParams." }, + { uint32_t(0), "NONE", "No trigger selected. The state will always be inactive." }, + { uint32_t(1), "GPIO", "Trigger based on the state of a GPIO pin. See GpioParams." }, + { uint32_t(2), "THRESHOLD", "Compare a data quantity against a high and low threshold. See ThresholdParams." }, + { uint32_t(3), "COMBINATION", "Logical combination of two or more triggers. See CombinationParams." }, }; static constexpr inline EnumInfo value = { @@ -3003,7 +3003,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* type */, static_cast(commands_3dm::EventTrigger::Type::GPIO)} /* type == GPIO */, }, @@ -3012,7 +3012,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* type */, static_cast(commands_3dm::EventTrigger::Type::THRESHOLD)} /* type == THRESHOLD */, }, @@ -3021,7 +3021,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* type */, static_cast(commands_3dm::EventTrigger::Type::COMBINATION)} /* type == COMBINATION */, }, @@ -3046,7 +3046,7 @@ struct MetadataFor /* .docs = */ "Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3055,7 +3055,7 @@ struct MetadataFor /* .docs = */ "Type of trigger to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3064,7 +3064,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3094,7 +3094,7 @@ struct MetadataFor /* .docs = */ "Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3103,7 +3103,7 @@ struct MetadataFor /* .docs = */ "Type of trigger to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3112,7 +3112,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3124,7 +3124,7 @@ struct MetadataFor /* .docs = */ "Configures various types of event triggers.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3136,12 +3136,12 @@ struct MetadataFor using type = commands_3dm::EventAction::GpioParams::Mode; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "DISABLED", "Pin state will not be changed." }, - { 1, "ACTIVE_HIGH", "Pin will be set high when the trigger is active and low otherwise." }, - { 2, "ACTIVE_LOW", "Pin will be set low when the trigger is active and high otherwise." }, - { 5, "ONESHOT_HIGH", "Pin will be set high each time the trigger activates. It will not be set low." }, - { 6, "ONESHOT_LOW", "Pin will be set low each time the trigger activates. It will not be set high." }, - { 7, "TOGGLE", "Pin will change to the opposite state each time the trigger activates." }, + { uint32_t(0), "DISABLED", "Pin state will not be changed." }, + { uint32_t(1), "ACTIVE_HIGH", "Pin will be set high when the trigger is active and low otherwise." }, + { uint32_t(2), "ACTIVE_LOW", "Pin will be set low when the trigger is active and high otherwise." }, + { uint32_t(5), "ONESHOT_HIGH", "Pin will be set high each time the trigger activates. It will not be set low." }, + { uint32_t(6), "ONESHOT_LOW", "Pin will be set low each time the trigger activates. It will not be set high." }, + { uint32_t(7), "TOGGLE", "Pin will change to the opposite state each time the trigger activates." }, }; static constexpr inline EnumInfo value = { @@ -3164,7 +3164,7 @@ struct MetadataFor /* .docs = */ "GPIO pin number.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -3173,7 +3173,7 @@ struct MetadataFor /* .docs = */ "Behavior of the pin.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -3198,7 +3198,7 @@ struct MetadataFor /* .docs = */ "MIP data descriptor set.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -3207,7 +3207,7 @@ struct MetadataFor /* .docs = */ "Decimation from the base rate.\nIf 0, a packet is emitted each time the trigger activates.\nOtherwise, packets will be streamed while the trigger is active.\nThe internal decimation counter is reset if the trigger deactivates.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -3216,7 +3216,7 @@ struct MetadataFor /* .docs = */ "Number of mip fields in the packet. Limited to 12.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -3225,7 +3225,7 @@ struct MetadataFor /* .docs = */ "List of field descriptors.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ {20, microstrain::Index(2) /* num_fields */}, /* .condition = */ {}, }, @@ -3245,9 +3245,9 @@ struct MetadataFor using type = commands_3dm::EventAction::Type; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "NONE", "No action. Parameters should be empty." }, - { 1, "GPIO", "Control the state of a GPIO pin. See GpioParameters." }, - { 2, "MESSAGE", "Output a data packet. See MessageParameters." }, + { uint32_t(0), "NONE", "No action. Parameters should be empty." }, + { uint32_t(1), "GPIO", "Control the state of a GPIO pin. See GpioParameters." }, + { uint32_t(2), "MESSAGE", "Output a data packet. See MessageParameters." }, }; static constexpr inline EnumInfo value = { @@ -3270,7 +3270,7 @@ struct MetadataFor /* .docs = */ "Gpio parameters, if type == GPIO. Ignore otherwise.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(2) /* type */, static_cast(commands_3dm::EventAction::Type::GPIO)} /* type == GPIO */, }, @@ -3279,7 +3279,7 @@ struct MetadataFor /* .docs = */ "Message parameters, if type == MESSAGE. Ignore otherwise.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(2) /* type */, static_cast(commands_3dm::EventAction::Type::MESSAGE)} /* type == MESSAGE */, }, @@ -3304,7 +3304,7 @@ struct MetadataFor /* .docs = */ "Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3313,7 +3313,7 @@ struct MetadataFor /* .docs = */ "Trigger ID number.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3322,7 +3322,7 @@ struct MetadataFor /* .docs = */ "Type of action to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3331,7 +3331,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3361,7 +3361,7 @@ struct MetadataFor /* .docs = */ "Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3370,7 +3370,7 @@ struct MetadataFor /* .docs = */ "Trigger ID number.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3379,7 +3379,7 @@ struct MetadataFor /* .docs = */ "Type of action to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3388,7 +3388,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3400,7 +3400,7 @@ struct MetadataFor /* .docs = */ "Configures various types of event actions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3417,7 +3417,7 @@ struct MetadataFor /* .docs = */ "accelerometer bias in the sensor frame (x,y,z) [g]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3447,7 +3447,7 @@ struct MetadataFor /* .docs = */ "accelerometer bias in the sensor frame (x,y,z) [g]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3459,7 +3459,7 @@ struct MetadataFor /* .docs = */ "Configures the user specified accelerometer bias\n\nThe user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3476,7 +3476,7 @@ struct MetadataFor /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3506,7 +3506,7 @@ struct MetadataFor /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3518,7 +3518,7 @@ struct MetadataFor /* .docs = */ "Configures the user specified gyroscope bias\n\nThe user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3535,7 +3535,7 @@ struct MetadataFor /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3564,7 +3564,7 @@ struct MetadataFor /* .docs = */ "Averaging time [milliseconds]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3593,7 +3593,7 @@ struct MetadataFor /* .docs = */ "hard iron offset in the sensor frame (x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3623,7 +3623,7 @@ struct MetadataFor /* .docs = */ "hard iron offset in the sensor frame (x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3632,10 +3632,10 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagHardIronOffset", /* .title = */ "Magnetometer Hard Iron Offset", - /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", + /* .docs = */ "Configure the user specified magnetometer hard iron offset vector\n\nThe values for this offset are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using Microstrain software tools.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe offset is applied to the scaled magnetometer vector prior to output.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3652,7 +3652,7 @@ struct MetadataFor /* .docs = */ "soft iron matrix [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3682,7 +3682,7 @@ struct MetadataFor /* .docs = */ "soft iron matrix [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3691,10 +3691,10 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "commands_3dm::MagSoftIronMatrix", /* .title = */ "Magnetometer Soft Iron Matrix", - /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using the LORD 'MIP Iron Calibration' application.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \\begin{bmatrix} 0 & 1 & 2 \\\\ 3 & 4 & 5 \\\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n", + /* .docs = */ "Configure the user specified magnetometer soft iron offset matrix\n\nThe values for this matrix are determined empirically by external software algorithms\nbased on calibration data taken after the device is installed in its application. These values\ncan be obtained and set by using Microstrain software tools.\nAlternatively, on some systems, the auto-mag calibration feature may be used to capture these values in-run.\nThe matrix is applied to the scaled magnetometer vector prior to output.\n\nThe matrix is in row major order:\nEQSTART M = \\begin{bmatrix} 0 & 1 & 2 \\\\ 3 & 4 & 5 \\\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3711,7 +3711,7 @@ struct MetadataFor /* .docs = */ "If true, coning and sculling compensation is enabled.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3741,7 +3741,7 @@ struct MetadataFor /* .docs = */ "If true, coning and sculling compensation is enabled.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3753,7 +3753,7 @@ struct MetadataFor /* .docs = */ "Controls the Coning and Sculling Compenstation setting.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3770,7 +3770,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3779,7 +3779,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3788,7 +3788,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3818,7 +3818,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3827,7 +3827,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3836,7 +3836,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3848,7 +3848,7 @@ struct MetadataFor /* .docs = */ "Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, Roll Euler angles.\nThese are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference,\nand describe the transformation of vectors from the sensor body frame to the vehicle frame.
\nNote: This is the transformation, the inverse of the rotation defined in our legacy products.
\nThe transformation may be stored in the device as a matrix or quaternion. When Euler angles are read back from the device, they may not\nbe exactly equal to the Euler angles used to set the transformation, but they are functionally equivalent, such that they result in the same transformation.
\n

\nThis transformation to the vehicle frame will be applied to the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\nComplementary Filter Orientation
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3865,7 +3865,7 @@ struct MetadataFor /* .docs = */ "Unit length quaternion representing transform [w, i, j, k]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3895,7 +3895,7 @@ struct MetadataFor /* .docs = */ "Unit length quaternion representing transform [w, i, j, k]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3907,7 +3907,7 @@ struct MetadataFor /* .docs = */ "Set the sensor to vehicle frame transformation using unit length quaternion.\n\nNote: This is the transformation, the inverse of the rotation.\n\nThis quaternion describes the transformation of vectors from the sensor body frame to the vehicle frame of reference, and satisfies the following relationship:
\n\nEQSTART p^{veh} = q^{-1} p^{sen} q EQEND
\n\nWhere:
\nEQSTART q = (q_w, q_x, q_y, q_z) EQEND is the quaternion describing the transformation.
\nEQSTART p^{sen} = (0, v^{sen}_x, v^{sen}_y, v^{sen}_z) EQEND and EQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART p^{veh} = (0, v^{veh}_x, v^{veh}_y, v^{veh}_z) EQEND and EQSTART v^{veh} EQEND is a 3-element vector expressed in the vehicle frame.
\n\nThe transformation may be stored in the device as a matrix or a quaternion. When the quaternion is read back from the device, it may not\nbe exactly equal to the quaternion used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3924,7 +3924,7 @@ struct MetadataFor /* .docs = */ "3 x 3 direction cosine matrix, stored in row-major order", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3954,7 +3954,7 @@ struct MetadataFor /* .docs = */ "3 x 3 direction cosine matrix, stored in row-major order", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3966,7 +3966,7 @@ struct MetadataFor /* .docs = */ "Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array.\n\nThese angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
\nEQSTART v^{veh} = M_{sen}^{veh} v^{sen} EQEND
\n\nWhere:
\n\nEQSTART v^{sen} EQEND is a 3-element vector expressed in the sensor body frame.
\nEQSTART v^{veh} EQEND is the same 3-element vector expressed in the vehicle frame.
\n
\nThe matrix elements are stored is row-major order: EQSTART M_{sen}^{veh} = \\begin{bmatrix} M_{11}, M_{12}, M_{13}, M_{21}, M_{22}, M_{23}, M_{31}, M_{32}, M_{33} \\end{bmatrix} EQEND\nThe transformation may be stored in the device as a matrix or a quaternion. When EQSTART M_{sen}^{veh} EQEND is read back from the device, it may not\nbe exactly equal to array used to set the transformation, but it is functionally equivalent.
\n

\nThis transformation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
\n
\nChanging this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3983,7 +3983,7 @@ struct MetadataFor /* .docs = */ "Enable Pitch/Roll corrections", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3992,7 +3992,7 @@ struct MetadataFor /* .docs = */ "Enable Heading corrections (only available on devices with magnetometer)", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4001,7 +4001,7 @@ struct MetadataFor /* .docs = */ "Time constant associated with the pitch/roll corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4010,7 +4010,7 @@ struct MetadataFor /* .docs = */ "Time constant associated with the heading corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4040,7 +4040,7 @@ struct MetadataFor /* .docs = */ "Enable Pitch/Roll corrections", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4049,7 +4049,7 @@ struct MetadataFor /* .docs = */ "Enable Heading corrections (only available on devices with magnetometer)", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4058,7 +4058,7 @@ struct MetadataFor /* .docs = */ "Time constant associated with the pitch/roll corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4067,7 +4067,7 @@ struct MetadataFor /* .docs = */ "Time constant associated with the heading corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4079,7 +4079,7 @@ struct MetadataFor /* .docs = */ "Configure the settings for the complementary filter which produces the following (0x80) descriptor set values: attitude matrix (0x80,09), quaternion (0x80,0A), and Euler angle (0x80,0C) outputs.\n\nThe filter can be configured to correct for pitch and roll using the accelerometer (with the assumption that linear acceleration is minimal),\nand to correct for heading using the magnetometer (with the assumption that the local magnetic field is dominated by the Earth's own magnetic field).\nPitch/roll and heading corrections each have their own configurable time constants, with a valid range of 1-1000 seconds. The default time constant is 10 seconds.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -4091,11 +4091,11 @@ struct MetadataFor using type = commands_3dm::SensorRangeType; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "ALL", "Only allowed for SAVE, LOAD, and DEFAULT function selectors." }, - { 1, "ACCEL", "Accelerometer. Range is specified in g." }, - { 2, "GYRO", "Gyroscope. Range is specified in degrees/s." }, - { 3, "MAG", "Magnetometer. Range is specified in Gauss." }, - { 4, "PRESS", "Pressure sensor. Range is specified in hPa." }, + { uint32_t(0), "ALL", "Only allowed for SAVE, LOAD, and DEFAULT function selectors." }, + { uint32_t(1), "ACCEL", "Accelerometer. Range is specified in g." }, + { uint32_t(2), "GYRO", "Gyroscope. Range is specified in degrees/s." }, + { uint32_t(3), "MAG", "Magnetometer. Range is specified in Gauss." }, + { uint32_t(4), "PRESS", "Pressure sensor. Range is specified in hPa." }, }; static constexpr inline EnumInfo value = { @@ -4118,7 +4118,7 @@ struct MetadataFor /* .docs = */ "Which type of sensor will get the new range value.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4127,7 +4127,7 @@ struct MetadataFor /* .docs = */ "Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4157,7 +4157,7 @@ struct MetadataFor /* .docs = */ "Which type of sensor will get the new range value.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4166,7 +4166,7 @@ struct MetadataFor /* .docs = */ "Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4178,7 +4178,7 @@ struct MetadataFor /* .docs = */ "Changes the IMU sensor gain.\n\nThis allows you to optimize the range to get the best accuracy and performance\nwhile minimizing over-range events.\n\nUse the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine\nthe appropriate setting value for your application. Using values other than\nthose specified may result in a NACK or inaccurate measurement data.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -4195,7 +4195,7 @@ struct MetadataFor /* .docs = */ "The value used in the 3DM Sensor Range command and response.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -4204,7 +4204,7 @@ struct MetadataFor /* .docs = */ "The actual range value. Units depend on the sensor type.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -4229,7 +4229,7 @@ struct MetadataFor /* .docs = */ "The sensor type from the command.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4238,7 +4238,7 @@ struct MetadataFor /* .docs = */ "Number of supported ranges.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4247,7 +4247,7 @@ struct MetadataFor /* .docs = */ "List of possible range settings.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(1) /* num_ranges */}, /* .condition = */ {}, }, @@ -4276,7 +4276,7 @@ struct MetadataFor /* .docs = */ "The sensor to query. Cannot be ALL.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4305,7 +4305,7 @@ struct MetadataFor /* .docs = */ "Descriptor set of the quantity to be filtered.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4314,7 +4314,7 @@ struct MetadataFor /* .docs = */ "Field descriptor of the quantity to be filtered.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4323,7 +4323,7 @@ struct MetadataFor /* .docs = */ "The filter will be enabled if this is true.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4332,7 +4332,7 @@ struct MetadataFor /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4341,7 +4341,7 @@ struct MetadataFor /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4371,7 +4371,7 @@ struct MetadataFor /* .docs = */ "Descriptor set of the quantity to be filtered.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4380,7 +4380,7 @@ struct MetadataFor /* .docs = */ "Field descriptor of the quantity to be filtered.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4389,7 +4389,7 @@ struct MetadataFor /* .docs = */ "The filter will be enabled if this is true.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4398,7 +4398,7 @@ struct MetadataFor /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4407,7 +4407,7 @@ struct MetadataFor /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4419,14 +4419,14 @@ struct MetadataFor /* .docs = */ "This command controls the low-pass anti-aliasing filter supported data quantities.\n\nSee the device user manual for data quantities which support the anti-aliasing filter.\n\nIf set to automatic mode, the frequency will track half of the transmission rate\nof the target descriptor according to the configured message format (0x0C,0x0F).\nFor example, if scaled accel (0x80,0x04) is set to stream at 100 Hz, the filter would\nbe set to 50 Hz. Changing the message format to 200 Hz would automatically adjust the\nfilter to 100 Hz.\n\nFor WRITE, SAVE, LOAD, and DEFAULT function selectors, the descriptor set and/or field descriptor\nmay be 0x00 to set, save, load, or reset the setting for all supported descriptors. The\nfield descriptor must be 0x00 if the descriptor set is 0x00.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; }; -static constexpr inline std::initializer_list ALL_COMMANDS_3DM = { +static constexpr inline std::initializer_list COMMANDS_3DM = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/commands_aiding.hpp b/src/cpp/mip/metadata/definitions/commands_aiding.hpp index 22eaa35d2..5b15d17b5 100644 --- a/src/cpp/mip/metadata/definitions/commands_aiding.hpp +++ b/src/cpp/mip/metadata/definitions/commands_aiding.hpp @@ -16,8 +16,8 @@ struct MetadataFor using type = commands_aiding::FrameConfig::Format; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "EULER", "Translation vector followed by euler angles (roll, pitch, yaw)." }, - { 2, "QUATERNION", "Translation vector followed by quaternion (w, x, y, z)." }, + { uint32_t(1), "EULER", "Translation vector followed by euler angles (roll, pitch, yaw)." }, + { uint32_t(2), "QUATERNION", "Translation vector followed by quaternion (w, x, y, z)." }, }; static constexpr inline EnumInfo value = { @@ -40,7 +40,7 @@ struct MetadataFor /* .docs = */ "Rotation represented as euler angles in RPY format [rad]. Range +/- pi.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* format */, static_cast(commands_aiding::FrameConfig::Format::EULER)} /* format == EULER */, }, @@ -49,7 +49,7 @@ struct MetadataFor /* .docs = */ "Rotation represented as a quaternion in WXYZ format.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* format */, static_cast(commands_aiding::FrameConfig::Format::QUATERNION)} /* format == QUATERNION */, }, @@ -74,7 +74,7 @@ struct MetadataFor /* .docs = */ "Reference frame number. Limit 4.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -83,7 +83,7 @@ struct MetadataFor /* .docs = */ "Format of the transformation.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, false, false, false, true}, + /* .attributes = */ {true, true, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -92,7 +92,7 @@ struct MetadataFor /* .docs = */ "If enabled, the Kalman filter will track errors.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -101,7 +101,7 @@ struct MetadataFor /* .docs = */ "Translation X, Y, and Z.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -110,7 +110,7 @@ struct MetadataFor /* .docs = */ "Rotation as specified by format.", /* .type = */ {Type::UNION, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -140,7 +140,7 @@ struct MetadataFor /* .docs = */ "Reference frame number. Limit 4.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -149,7 +149,7 @@ struct MetadataFor /* .docs = */ "Format of the transformation.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, false, false, false, true}, + /* .attributes = */ {true, true, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -158,7 +158,7 @@ struct MetadataFor /* .docs = */ "If enabled, the Kalman filter will track errors.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -167,7 +167,7 @@ struct MetadataFor /* .docs = */ "Translation X, Y, and Z.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -176,7 +176,7 @@ struct MetadataFor /* .docs = */ "Rotation as specified by format.", /* .type = */ {Type::UNION, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -188,7 +188,7 @@ struct MetadataFor /* .docs = */ "Defines an aiding frame associated with a specific sensor frame ID.\nThe frame ID used in this command should mirror the frame ID used in the aiding command\n(if that aiding measurement is measured in this reference frame).\n\nThis transform satisfies the following relationship:\n\nEQSTART p^{veh} = R p^{sensor_frame} + t EQEND
\n\nWhere:
\nEQSTART R EQEND is rotation matrix defined by the rotation component and EQSTART t EQEND is the translation vector

\nEQSTART p^{sensor_frame} EQEND is a 3-element position vector expressed in the external sensor frame
\nEQSTART p^{veh} EQEND is a 3-element position vector expressed in the vehicle frame
\n\nRotation can be defined using Euler angles OR quaternions. If Format selector is set to Euler Angles, the fourth element\nin the rotation vector is ignored and should be set to 0.\n\nWhen the tracking_enabled flag is 1, the Kalman filter will track errors in the provided frame definition; when 0, no errors are tracked.\n\nExample: GNSS antenna lever arm\n\nFrame ID: 1\nFormat: 1 (Euler)\nTranslation: [0,1,] (GNSS with a 1 meter Y offset in the vehicle frame)\nRotation: [0,0,0,0] (Rotational component is not relevant for GNSS measurements, set to zero)\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -200,9 +200,9 @@ struct MetadataFor using type = commands_aiding::EchoControl::Mode; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "SUPPRESS_ACK", "Suppresses the usual command ack field for aiding messages." }, - { 1, "STANDARD", "Normal ack/nack behavior." }, - { 2, "RESPONSE", "Echo the data back as a response." }, + { uint32_t(0), "SUPPRESS_ACK", "Suppresses the usual command ack field for aiding messages." }, + { uint32_t(1), "STANDARD", "Normal ack/nack behavior." }, + { uint32_t(2), "RESPONSE", "Echo the data back as a response." }, }; static constexpr inline EnumInfo value = { @@ -225,7 +225,7 @@ struct MetadataFor /* .docs = */ "Controls data echoing.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -255,7 +255,7 @@ struct MetadataFor /* .docs = */ "Controls data echoing.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -267,7 +267,7 @@ struct MetadataFor /* .docs = */ "Controls command response behavior to external aiding commands", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -279,9 +279,9 @@ struct MetadataFor using type = commands_aiding::Time::Timebase; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "INTERNAL_REFERENCE", "Timestamp provided is with respect to internal clock." }, - { 2, "EXTERNAL_TIME", "Timestamp provided is with respect to external clock, synced by PPS source." }, - { 3, "TIME_OF_ARRIVAL", "Timestamp provided is a fixed latency relative to time of message arrival." }, + { uint32_t(1), "INTERNAL_REFERENCE", "Timestamp provided is with respect to internal clock." }, + { uint32_t(2), "EXTERNAL_TIME", "Timestamp provided is with respect to external clock, synced by PPS source." }, + { uint32_t(3), "TIME_OF_ARRIVAL", "Timestamp provided is a fixed latency relative to time of message arrival." }, }; static constexpr inline EnumInfo value = { @@ -304,7 +304,7 @@ struct MetadataFor /* .docs = */ "Timebase reference, e.g. internal, external, GPS, UTC, etc.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -313,7 +313,7 @@ struct MetadataFor /* .docs = */ "Reserved, set to 0x01.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -322,7 +322,7 @@ struct MetadataFor /* .docs = */ "Nanoseconds since the timebase epoch.", /* .type = */ {Type::U64, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -342,9 +342,9 @@ struct MetadataFor using type = commands_aiding::PosEcef::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "X", "" }, - { 2, "Y", "" }, - { 4, "Z", "" }, + { uint32_t(1), "X", "" }, + { uint32_t(2), "Y", "" }, + { uint32_t(4), "Z", "" }, }; static constexpr inline BitfieldInfo value = { @@ -367,7 +367,7 @@ struct MetadataFor /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -376,7 +376,7 @@ struct MetadataFor /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -385,7 +385,7 @@ struct MetadataFor /* .docs = */ "ECEF position [m].", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -394,16 +394,16 @@ struct MetadataFor /* .docs = */ "ECEF position uncertainty [m]. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -427,9 +427,9 @@ struct MetadataFor using type = commands_aiding::PosLlh::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "Latitude", "" }, - { 2, "Longitude", "" }, - { 4, "Height", "" }, + { uint32_t(1), "Latitude", "" }, + { uint32_t(2), "Longitude", "" }, + { uint32_t(4), "Height", "" }, }; static constexpr inline BitfieldInfo value = { @@ -452,7 +452,7 @@ struct MetadataFor /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -461,7 +461,7 @@ struct MetadataFor /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -470,7 +470,7 @@ struct MetadataFor /* .docs = */ "[deg]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -479,7 +479,7 @@ struct MetadataFor /* .docs = */ "[deg]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -488,7 +488,7 @@ struct MetadataFor /* .docs = */ "[m]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -497,16 +497,16 @@ struct MetadataFor /* .docs = */ "NED position uncertainty. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -535,7 +535,7 @@ struct MetadataFor /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -544,7 +544,7 @@ struct MetadataFor /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -553,7 +553,7 @@ struct MetadataFor /* .docs = */ "[m]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -562,7 +562,7 @@ struct MetadataFor /* .docs = */ "[m]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -571,7 +571,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -595,9 +595,9 @@ struct MetadataFor using type = commands_aiding::VelEcef::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "X", "" }, - { 2, "Y", "" }, - { 4, "Z", "" }, + { uint32_t(1), "X", "" }, + { uint32_t(2), "Y", "" }, + { uint32_t(4), "Z", "" }, }; static constexpr inline BitfieldInfo value = { @@ -620,7 +620,7 @@ struct MetadataFor /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -629,7 +629,7 @@ struct MetadataFor /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -638,7 +638,7 @@ struct MetadataFor /* .docs = */ "ECEF velocity [m/s].", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -647,16 +647,16 @@ struct MetadataFor /* .docs = */ "ECEF velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -680,9 +680,9 @@ struct MetadataFor using type = commands_aiding::VelNed::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "X", "" }, - { 2, "Y", "" }, - { 4, "Z", "" }, + { uint32_t(1), "X", "" }, + { uint32_t(2), "Y", "" }, + { uint32_t(4), "Z", "" }, }; static constexpr inline BitfieldInfo value = { @@ -705,7 +705,7 @@ struct MetadataFor /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -714,7 +714,7 @@ struct MetadataFor /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -723,7 +723,7 @@ struct MetadataFor /* .docs = */ "NED velocity [m/s].", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -732,16 +732,16 @@ struct MetadataFor /* .docs = */ "NED velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -765,9 +765,9 @@ struct MetadataFor using type = commands_aiding::VelBodyFrame::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "X", "" }, - { 2, "Y", "" }, - { 4, "Z", "" }, + { uint32_t(1), "X", "" }, + { uint32_t(2), "Y", "" }, + { uint32_t(4), "Z", "" }, }; static constexpr inline BitfieldInfo value = { @@ -790,7 +790,7 @@ struct MetadataFor /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -799,7 +799,7 @@ struct MetadataFor /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -808,7 +808,7 @@ struct MetadataFor /* .docs = */ "[m/s]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -817,16 +817,16 @@ struct MetadataFor /* .docs = */ "[m/s] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -855,7 +855,7 @@ struct MetadataFor /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -864,7 +864,7 @@ struct MetadataFor /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -873,7 +873,7 @@ struct MetadataFor /* .docs = */ "Heading [radians]. Range +/- Pi.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -882,7 +882,7 @@ struct MetadataFor /* .docs = */ "Cannot be 0 unless the valid flags are 0.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -891,7 +891,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -915,9 +915,9 @@ struct MetadataFor using type = commands_aiding::MagneticField::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "X", "" }, - { 2, "Y", "" }, - { 4, "Z", "" }, + { uint32_t(1), "X", "" }, + { uint32_t(2), "Y", "" }, + { uint32_t(4), "Z", "" }, }; static constexpr inline BitfieldInfo value = { @@ -940,7 +940,7 @@ struct MetadataFor /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -949,7 +949,7 @@ struct MetadataFor /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -958,7 +958,7 @@ struct MetadataFor /* .docs = */ "[G]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -967,16 +967,16 @@ struct MetadataFor /* .docs = */ "[G] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1005,7 +1005,7 @@ struct MetadataFor /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1014,7 +1014,7 @@ struct MetadataFor /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1023,7 +1023,7 @@ struct MetadataFor /* .docs = */ "[mbar]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1032,7 +1032,7 @@ struct MetadataFor /* .docs = */ "[mbar] 1-sigma uncertainty. Cannot be 0 unless the valid flags are 0.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1041,7 +1041,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1060,7 +1060,7 @@ struct MetadataFor }; -static constexpr inline std::initializer_list ALL_COMMANDS_AIDING = { +static constexpr inline std::initializer_list COMMANDS_AIDING = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index 50152136d..a88a99dd0 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -55,7 +55,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -64,7 +64,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, }, @@ -73,7 +73,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, }, @@ -82,7 +82,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, }, @@ -91,7 +91,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, }, @@ -100,7 +100,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, }, @@ -125,7 +125,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -171,8 +171,17 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, - /* .count = */ 0, + /* .attributes = */ {true, false, false, false, false}, + /* .count = */ {0, microstrain::Index(1) /* descriptors_count */}, + /* .condition = */ {}, + }, + { + /* .name = */ "descriptors_count", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .attributes = */ {false, false, false, false, false, /*echo*/false, /*virtual*/true}, + /* .count = */ 1, /* .condition = */ {}, }, }; @@ -217,7 +226,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -280,8 +289,17 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, - /* .count = */ 0, + /* .attributes = */ {true, false, false, false, false}, + /* .count = */ {0, microstrain::Index(1) /* descriptors_count */}, + /* .condition = */ {}, + }, + { + /* .name = */ "descriptors_count", + /* .docs = */ "", + /* .type = */ {Type::U8, nullptr}, + /* .accessor = */ utils::access, + /* .attributes = */ {false, false, false, false, false, /*echo*/false, /*virtual*/true}, + /* .count = */ 1, /* .condition = */ {}, }, }; @@ -326,7 +344,7 @@ struct MetadataFor /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 16, /* .condition = */ {}, }, @@ -372,7 +390,7 @@ struct MetadataFor /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -381,7 +399,7 @@ struct MetadataFor /* .docs = */ "Port baud rate. Must be a supported rate.", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -411,7 +429,7 @@ struct MetadataFor /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -420,7 +438,7 @@ struct MetadataFor /* .docs = */ "Port baud rate. Must be a supported rate.", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -432,7 +450,7 @@ struct MetadataFor /* .docs = */ "Controls the baud rate of a specific port on the device.\n\nPlease see the device user manual for supported baud rates on each port.\n\nThe device will wait until all incoming and outgoing data has been sent, up\nto a maximum of 250 ms, before applying any change.\n\nNo guarantee is provided as to what happens to commands issued during this\ndelay period; They may or may not be processed and any responses aren't\nguaranteed to be at one rate or the other. The same applies to data packets.\n\nIt is highly recommended that the device be idle before issuing this command\nand that it be issued in its own packet. Users should wait 250 ms after\nsending this command before further interaction.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -444,8 +462,8 @@ struct MetadataFor using type = commands_base::GpsTimeUpdate::FieldId; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "WEEK_NUMBER", "Week number." }, - { 2, "TIME_OF_WEEK", "Time of week in seconds." }, + { uint32_t(1), "WEEK_NUMBER", "Week number." }, + { uint32_t(2), "TIME_OF_WEEK", "Time of week in seconds." }, }; static constexpr inline EnumInfo value = { @@ -469,7 +487,7 @@ struct MetadataFor /* .docs = */ "Determines how to interpret value.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -478,7 +496,7 @@ struct MetadataFor /* .docs = */ "Week number or time of week, depending on the field_id.", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -490,7 +508,7 @@ struct MetadataFor /* .docs = */ "Set device internal GPS time\nWhen combined with a PPS input signal applied to the I/O connector, this command enables complete synchronization of data outputs\nwith an external time base, such as GPS system time. Since the hardware PPS synchronization can only detect the fractional number of seconds when pulses arrive,\ncomplete synchronization requires that the user provide the whole number of seconds via this command. After achieving PPS synchronization, this command should be sent twice: once to set the time-of-week and once to set the week number. PPS synchronization can be verified by monitoring the time sync status message (0xA0, 0x02) or the valid flags of any shared external timestamp (0x--, D7) data field.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, false, false, false, false, true}, + /* .functions = */ {true, false, false, false, false}, /* .proprietary = */ false, /* .response = */ nullptr, }; @@ -514,7 +532,7 @@ struct MetadataFor }; -static constexpr inline std::initializer_list ALL_COMMANDS_BASE = { +static constexpr inline std::initializer_list COMMANDS_BASE = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/commands_filter.hpp b/src/cpp/mip/metadata/definitions/commands_filter.hpp index 391ada0f3..3fa759901 100644 --- a/src/cpp/mip/metadata/definitions/commands_filter.hpp +++ b/src/cpp/mip/metadata/definitions/commands_filter.hpp @@ -38,7 +38,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -47,7 +47,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -56,7 +56,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -80,13 +80,13 @@ struct MetadataFor using type = commands_filter::EstimationControl::EnableFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "gyro_bias", "" }, - { 2, "accel_bias", "" }, - { 4, "gyro_scale_factor", "" }, - { 8, "accel_scale_factor", "" }, - { 16, "antenna_offset", "" }, - { 32, "auto_mag_hard_iron", "" }, - { 64, "auto_mag_soft_iron", "" }, + { uint32_t(1), "gyro_bias", "" }, + { uint32_t(2), "accel_bias", "" }, + { uint32_t(4), "gyro_scale_factor", "" }, + { uint32_t(8), "accel_scale_factor", "" }, + { uint32_t(16), "antenna_offset", "" }, + { uint32_t(32), "auto_mag_hard_iron", "" }, + { uint32_t(64), "auto_mag_soft_iron", "" }, }; static constexpr inline BitfieldInfo value = { @@ -107,9 +107,9 @@ struct MetadataFor { /* .name = */ "enable", /* .docs = */ "See above", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -137,9 +137,9 @@ struct MetadataFor { /* .name = */ "enable", /* .docs = */ "See above", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -151,7 +151,7 @@ struct MetadataFor /* .docs = */ "Estimation Control Flags\n\nControls which parameters are estimated by the Kalman Filter.\n\nDesired settings should be logically ORed together.\n\nExamples:\n\n0x0001 - Enable Gyro Bias Estimation Only\n0x0063 - Enable Gyro Bias, Accel Bias, and Mag Auto Hard and Soft Iron Cal States Only\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -168,7 +168,7 @@ struct MetadataFor /* .docs = */ "[seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -177,7 +177,7 @@ struct MetadataFor /* .docs = */ "[GPS week number, not modulus 1024]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -186,7 +186,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -195,7 +195,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -204,7 +204,7 @@ struct MetadataFor /* .docs = */ "Above WGS84 ellipsoid [meters]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -213,7 +213,7 @@ struct MetadataFor /* .docs = */ "NED Frame [meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -222,7 +222,7 @@ struct MetadataFor /* .docs = */ "NED Frame, 1-sigma [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -231,7 +231,7 @@ struct MetadataFor /* .docs = */ "NED Frame, 1-sigma [meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -260,7 +260,7 @@ struct MetadataFor /* .docs = */ "Bounded by +-PI [radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -269,7 +269,7 @@ struct MetadataFor /* .docs = */ "1-sigma [radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -278,7 +278,7 @@ struct MetadataFor /* .docs = */ "1 - True, 2 - Magnetic", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -307,7 +307,7 @@ struct MetadataFor /* .docs = */ "[seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -316,7 +316,7 @@ struct MetadataFor /* .docs = */ "[GPS week number, not modulus 1024]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -325,7 +325,7 @@ struct MetadataFor /* .docs = */ "Relative to true north, bounded by +-PI [radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -334,7 +334,7 @@ struct MetadataFor /* .docs = */ "1-sigma [radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -343,7 +343,7 @@ struct MetadataFor /* .docs = */ "1 - True, 2 - Magnetic", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -367,9 +367,9 @@ struct MetadataFor using type = commands_filter::TareOrientation::MipTareAxes; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "roll", "" }, - { 2, "pitch", "" }, - { 4, "yaw", "" }, + { uint32_t(1), "roll", "" }, + { uint32_t(2), "pitch", "" }, + { uint32_t(4), "yaw", "" }, }; static constexpr inline BitfieldInfo value = { @@ -390,9 +390,9 @@ struct MetadataFor { /* .name = */ "axes", /* .docs = */ "Axes to tare", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -420,9 +420,9 @@ struct MetadataFor { /* .name = */ "axes", /* .docs = */ "Axes to tare", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -434,7 +434,7 @@ struct MetadataFor /* .docs = */ "Tare the device orientation.\n\nThis function uses the current device orientation relative to the NED frame as the current sensor to vehicle transformation.\nThis command is provided as a convenient way to set the sensor to vehicle frame transformation.\nThe filter must be initialized and have a valid attitude output. If the attitude is not valid, an error will be returned.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -446,10 +446,10 @@ struct MetadataFor using type = commands_filter::VehicleDynamicsMode::DynamicsMode; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "PORTABLE", "" }, - { 2, "AUTOMOTIVE", "" }, - { 3, "AIRBORNE", "" }, - { 4, "AIRBORNE_HIGH_G", "" }, + { uint32_t(1), "PORTABLE", "" }, + { uint32_t(2), "AUTOMOTIVE", "" }, + { uint32_t(3), "AIRBORNE", "" }, + { uint32_t(4), "AIRBORNE_HIGH_G", "" }, }; static constexpr inline EnumInfo value = { @@ -472,7 +472,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -502,7 +502,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -514,7 +514,7 @@ struct MetadataFor /* .docs = */ "Controls the vehicle dynamics mode.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -531,7 +531,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -540,7 +540,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -549,7 +549,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -579,7 +579,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -588,7 +588,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -597,7 +597,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -609,7 +609,7 @@ struct MetadataFor /* .docs = */ "Set the sensor to vehicle frame rotation using Yaw, Pitch, Roll Euler angles.\n\nNote: This is the rotation, the inverse of the transformation.\nThese angles define the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe rotation is stored in the device as a quaternion. When Euler angles are read back from the device, they may not\nbe equivalent in value to the Euler angles used to set the rotation, but they are functionally equivalent.
\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -626,7 +626,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -656,7 +656,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -668,7 +668,7 @@ struct MetadataFor /* .docs = */ "Set the sensor to vehicle frame rotation using a row-major direction cosine matrix.\n\nNote: This is the rotation, the inverse of the transformation.\nThis matrix defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe matrix must be orthonormal (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a quaternion. When the DCM is read back from the device, the components may not\nbe exactly equivalent in value to the DCM used to set the rotation, but they are functionally equivalent.
\n
\nMatrix element order:

\n\nEQSTART T_{SEN}^{VEH} = \\begin{bmatrix} 0 & 1 & 2\\\\ 3 & 4 & 5\\\\ 6 & 7 & 8 \\end{bmatrix} EQEND\n\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -685,7 +685,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -715,7 +715,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -727,7 +727,7 @@ struct MetadataFor /* .docs = */ "Set the sensor to vehicle frame rotation using a quaternion.\n\nNote: This is the rotation, the inverse of the transformation.\nThis quaternion defines the rotation from the sensor body frame to the fixed vehicle frame.
\nPlease reference the device Theory of Operation for more information.
\nThe quaternion must be unit length (tolerance 1e-3) or the device will NACK the command.\nThe rotation is stored in the device as a unit quaternion. When the quaternion elements are read back from the device, they may not\nbe equivalent in value to the quaternion used to set the rotation, due to normalization.
\n
\nQuaternion element definition:

\n
\nEQSTART Q_{SEN}^{VEH} = \\begin{bmatrix} q_{0} & q_{1}*i & q_{2}*j & q_{3}*k \\end{bmatrix} EQEND\n

\nThis rotation affects the following output quantities:

\nIMU:
\nScaled Acceleration
\nScaled Gyro
\nScaled Magnetometer
\nDelta Theta
\nDelta Velocity
\n

\nEstimation Filter:
\nEstimated Orientation, Quaternion
\nEstimated Orientation, Matrix
\nEstimated Orientation, Euler Angles
\nEstimated Linear Acceleration
\nEstimated Angular Rate
\nEstimated Gravity Vector
", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -744,7 +744,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -774,7 +774,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -786,7 +786,7 @@ struct MetadataFor /* .docs = */ "Set the sensor to vehicle frame offset, expressed in the sensor frame.\n\nThis is a simple offset, not a lever arm. It does not compensate for inertial effects experienced from being offset from the center of gravity/rotation of the vehicle.\nIt simply adds the offset to the position output to express it in the origin of the user's vehicle frame.\n\nThis offset affects the following output quantities:\nEstimated LLH Position\n\nThe magnitude of the offset vector is limited to 10 meters", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -803,7 +803,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -833,7 +833,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -845,7 +845,7 @@ struct MetadataFor /* .docs = */ "Configure the GNSS antenna offset.\n\nFor 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center.\n\nFor 7-series products, this is expressed in the vehicle frame, from the sensor origin to the GNSS antenna RF center.\n\nThis command should also be used for CV7 / GV7-INS NMEA Input over GPIO.\n\nThe magnitude of the offset vector is limited to 10 meters\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -857,10 +857,10 @@ struct MetadataFor using type = commands_filter::GnssSource::Source; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "ALL_INT", "All internal receivers" }, - { 2, "EXT", "External GNSS messages provided by user" }, - { 3, "INT_1", "Internal GNSS Receiver 1 only" }, - { 4, "INT_2", "Internal GNSS Receiver 2 only" }, + { uint32_t(1), "ALL_INT", "All internal receivers" }, + { uint32_t(2), "EXT", "External GNSS messages provided by user" }, + { uint32_t(3), "INT_1", "Internal GNSS Receiver 1 only" }, + { uint32_t(4), "INT_2", "Internal GNSS Receiver 2 only" }, }; static constexpr inline EnumInfo value = { @@ -883,7 +883,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -913,7 +913,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -925,7 +925,7 @@ struct MetadataFor /* .docs = */ "Control the source of GNSS information used to update the Kalman Filter.\n\nChanging the GNSS source while the sensor is in the 'running' state may temporarily place\nit back in the 'init' state until the new source of GNSS data is received.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -937,14 +937,14 @@ struct MetadataFor using type = commands_filter::HeadingSource::Source; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "NONE", "See note 3" }, - { 1, "MAG", "" }, - { 2, "GNSS_VEL", "See notes 1,2" }, - { 3, "EXTERNAL", "" }, - { 4, "GNSS_VEL_AND_MAG", "" }, - { 5, "GNSS_VEL_AND_EXTERNAL", "" }, - { 6, "MAG_AND_EXTERNAL", "" }, - { 7, "GNSS_VEL_AND_MAG_AND_EXTERNAL", "" }, + { uint32_t(0), "NONE", "See note 3" }, + { uint32_t(1), "MAG", "" }, + { uint32_t(2), "GNSS_VEL", "See notes 1,2" }, + { uint32_t(3), "EXTERNAL", "" }, + { uint32_t(4), "GNSS_VEL_AND_MAG", "" }, + { uint32_t(5), "GNSS_VEL_AND_EXTERNAL", "" }, + { uint32_t(6), "MAG_AND_EXTERNAL", "" }, + { uint32_t(7), "GNSS_VEL_AND_MAG_AND_EXTERNAL", "" }, }; static constexpr inline EnumInfo value = { @@ -967,7 +967,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -997,7 +997,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1009,7 +1009,7 @@ struct MetadataFor /* .docs = */ "Control the source of heading information used to update the Kalman Filter.\n\n1. To use internal GNSS velocity vector for heading updates, the target application\nmust have minimal (preferably no) side-slip. This option is good for wheeled vehicles.\n\n2. On some devices, when using GNSS velocity vector for heading updates, the X-axis of the device\nmust align with the direction of travel. Please reference the user guide for your particular device to\ndetermine if this limitation is applicable.\n\n3. When none is selected, the heading estimate can still converge if GNSS is available and sufficient dynamic motion\n(change in direction of travel and acceleration) is experienced. The heading may drift when: stationary, traveling\nat a constant speed, or during a constant course over ground.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1026,7 +1026,7 @@ struct MetadataFor /* .docs = */ "See above", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1056,7 +1056,7 @@ struct MetadataFor /* .docs = */ "See above", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1068,7 +1068,7 @@ struct MetadataFor /* .docs = */ "Filter Auto-initialization Control\n\nEnable/Disable automatic initialization upon device startup.\n\nPossible enable values:\n\n0x00 - Disable auto-initialization\n0x01 - Enable auto-initialization\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1085,7 +1085,7 @@ struct MetadataFor /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1115,7 +1115,7 @@ struct MetadataFor /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1127,7 +1127,7 @@ struct MetadataFor /* .docs = */ "Accelerometer Noise Standard Deviation\n\nEach of the noise values must be greater than 0.0.\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.\nDefault values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1144,7 +1144,7 @@ struct MetadataFor /* .docs = */ "Gyro Noise 1-sigma [rad/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1174,7 +1174,7 @@ struct MetadataFor /* .docs = */ "Gyro Noise 1-sigma [rad/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1186,7 +1186,7 @@ struct MetadataFor /* .docs = */ "Gyroscope Noise Standard Deviation\n\nEach of the noise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter.\nDefault values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1203,7 +1203,7 @@ struct MetadataFor /* .docs = */ "Accel Bias Beta [1/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1212,7 +1212,7 @@ struct MetadataFor /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1242,7 +1242,7 @@ struct MetadataFor /* .docs = */ "Accel Bias Beta [1/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1251,7 +1251,7 @@ struct MetadataFor /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1263,7 +1263,7 @@ struct MetadataFor /* .docs = */ "Accelerometer Bias Model Parameters\n\nNoise values must be greater than 0.0\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1280,7 +1280,7 @@ struct MetadataFor /* .docs = */ "Gyro Bias Beta [1/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1289,7 +1289,7 @@ struct MetadataFor /* .docs = */ "Gyro Noise 1-sigma [rad/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1319,7 +1319,7 @@ struct MetadataFor /* .docs = */ "Gyro Bias Beta [1/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1328,7 +1328,7 @@ struct MetadataFor /* .docs = */ "Gyro Noise 1-sigma [rad/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1340,7 +1340,7 @@ struct MetadataFor /* .docs = */ "Gyroscope Bias Model Parameters\n\nNoise values must be greater than 0.0\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1352,8 +1352,8 @@ struct MetadataFor using type = commands_filter::AltitudeAiding::AidingSelector; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "NONE", "No altitude aiding" }, - { 1, "PRESURE", "Enable pressure sensor aiding" }, + { uint32_t(0), "NONE", "No altitude aiding" }, + { uint32_t(1), "PRESURE", "Enable pressure sensor aiding" }, }; static constexpr inline EnumInfo value = { @@ -1376,7 +1376,7 @@ struct MetadataFor /* .docs = */ "See above", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1406,7 +1406,7 @@ struct MetadataFor /* .docs = */ "See above", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1418,7 +1418,7 @@ struct MetadataFor /* .docs = */ "Select altitude input for absolute altitude and/or vertical velocity. The primary altitude reading is always GNSS.\nAiding inputs are used to improve GNSS altitude readings when GNSS is available and to backup GNSS during outages.\n\nPressure altitude is based on 'instant sea level pressure' which is dependent on location and weather conditions and can vary by more than 40 meters.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1430,8 +1430,8 @@ struct MetadataFor using type = commands_filter::PitchRollAiding::AidingSource; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "NONE", "No pitch/roll aiding" }, - { 1, "GRAVITY_VEC", "Enable gravity vector aiding" }, + { uint32_t(0), "NONE", "No pitch/roll aiding" }, + { uint32_t(1), "GRAVITY_VEC", "Enable gravity vector aiding" }, }; static constexpr inline EnumInfo value = { @@ -1454,7 +1454,7 @@ struct MetadataFor /* .docs = */ "Controls the aiding source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1484,7 +1484,7 @@ struct MetadataFor /* .docs = */ "Controls the aiding source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1496,7 +1496,7 @@ struct MetadataFor /* .docs = */ "Select pitch/roll aiding input. Pitch/roll reading is always derived from GNSS corrected inertial solution.\nAiding inputs are used to improve that solution during periods of low dynamics and GNSS outages.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1513,7 +1513,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1522,7 +1522,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1552,7 +1552,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1561,7 +1561,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1573,7 +1573,7 @@ struct MetadataFor /* .docs = */ "The ZUPT is triggered when the scalar magnitude of the GNSS reported velocity vector is equal-to or less than the threshold value.\nThe device will NACK threshold values that are less than zero (i.e.negative.)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1590,7 +1590,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1599,7 +1599,7 @@ struct MetadataFor /* .docs = */ "[radians/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1629,7 +1629,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1638,7 +1638,7 @@ struct MetadataFor /* .docs = */ "[radians/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1650,7 +1650,7 @@ struct MetadataFor /* .docs = */ "Zero Angular Rate Update\nThe ZUPT is triggered when the scalar magnitude of the angular rate vector is equal-to or less than the threshold value.\nThe device will NACK threshold values that are less than zero (i.e.negative.)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1706,7 +1706,7 @@ struct MetadataFor /* .docs = */ "This command captures the current value of the auto-calibration, applies it to the current fixed hard and soft iron calibration coefficients, and replaces the current fixed hard and soft iron calibration coefficients with the new values.\nThis may be used in place of (or in addition to) a manual hard and soft iron calibration utility. This command also resets the auto-calibration coefficients.\nFunction selector SAVE is the same as issuing the 0x0C, 0x3A and 0x0C, 0x3B commands with the SAVE function selector.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, false, true, false, false, true}, + /* .functions = */ {true, false, true, false, false}, /* .proprietary = */ false, /* .response = */ nullptr, }; @@ -1723,7 +1723,7 @@ struct MetadataFor /* .docs = */ "Gravity Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1753,7 +1753,7 @@ struct MetadataFor /* .docs = */ "Gravity Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1765,7 +1765,7 @@ struct MetadataFor /* .docs = */ "Set the expected gravity noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nNote: Noise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter. Changing this value modifies how the filter responds to dynamic input and can be used to tune filter performance.\nDefault values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1782,7 +1782,7 @@ struct MetadataFor /* .docs = */ "Pressure Altitude Noise 1-sigma [m]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1812,7 +1812,7 @@ struct MetadataFor /* .docs = */ "Pressure Altitude Noise 1-sigma [m]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1824,7 +1824,7 @@ struct MetadataFor /* .docs = */ "Set the expected pressure altitude noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nThe noise value must be greater than 0.0\n\nThis noise value represents pressure altitude model noise in the Estimation Filter.\nA lower value will increase responsiveness of the sensor to pressure changes, however height estimates will be more susceptible to error from air pressure fluctuations not due to changes in altitude. Default values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1841,7 +1841,7 @@ struct MetadataFor /* .docs = */ "Hard Iron Offset Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1871,7 +1871,7 @@ struct MetadataFor /* .docs = */ "Hard Iron Offset Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1883,7 +1883,7 @@ struct MetadataFor /* .docs = */ "Set the expected hard iron offset noise 1-sigma values. This function can be used to tune the filter performance in the target application.\n\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0\n\nThe noise values represent process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1900,7 +1900,7 @@ struct MetadataFor /* .docs = */ "Soft Iron Matrix Noise 1-sigma [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1930,7 +1930,7 @@ struct MetadataFor /* .docs = */ "Soft Iron Matrix Noise 1-sigma [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1942,7 +1942,7 @@ struct MetadataFor /* .docs = */ "Set the expected soft iron matrix noise 1-sigma values.\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -1959,7 +1959,7 @@ struct MetadataFor /* .docs = */ "Mag Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1989,7 +1989,7 @@ struct MetadataFor /* .docs = */ "Mag Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2001,7 +2001,7 @@ struct MetadataFor /* .docs = */ "Set the expected magnetometer noise 1-sigma values.\nThis function can be used to tune the filter performance in the target application.\n\nNoise values must be greater than 0.0 (gauss)\n\nThe noise value represents process noise in the Estimation Filter.\nChanging this value modifies how the filter responds to dynamic input and can be used to tune the performance of the filter. Default values provide good performance for most laboratory conditions", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2013,9 +2013,9 @@ struct MetadataFor using type = commands_filter::FilterMagParamSource; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "NONE", "No source. See command documentation for default behavior" }, - { 2, "WMM", "Magnetic field is assumed to conform to the World Magnetic Model, calculated using current location estimate as an input to the model." }, - { 3, "MANUAL", "Magnetic field is assumed to have the parameter specified by the user." }, + { uint32_t(1), "NONE", "No source. See command documentation for default behavior" }, + { uint32_t(2), "WMM", "Magnetic field is assumed to conform to the World Magnetic Model, calculated using current location estimate as an input to the model." }, + { uint32_t(3), "MANUAL", "Magnetic field is assumed to have the parameter specified by the user." }, }; static constexpr inline EnumInfo value = { @@ -2038,7 +2038,7 @@ struct MetadataFor /* .docs = */ "Inclination Source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2047,7 +2047,7 @@ struct MetadataFor /* .docs = */ "Inclination angle [radians] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2077,7 +2077,7 @@ struct MetadataFor /* .docs = */ "Inclination Source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2086,7 +2086,7 @@ struct MetadataFor /* .docs = */ "Inclination angle [radians] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2098,7 +2098,7 @@ struct MetadataFor /* .docs = */ "Set/Get the local magnetic field inclination angle source.\n\nThis can be used to correct for the local value of inclination (dip angle) of the earthmagnetic field.\nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2115,7 +2115,7 @@ struct MetadataFor /* .docs = */ "Magnetic field declination angle source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2124,7 +2124,7 @@ struct MetadataFor /* .docs = */ "Declination angle [radians] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2154,7 +2154,7 @@ struct MetadataFor /* .docs = */ "Magnetic field declination angle source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2163,7 +2163,7 @@ struct MetadataFor /* .docs = */ "Declination angle [radians] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2175,7 +2175,7 @@ struct MetadataFor /* .docs = */ "Set/Get the local magnetic field declination angle source.\n\nThis can be used to correct for the local value of declination of the earthmagnetic field.\nHaving a correct value is important for best performance of the auto-mag calibration feature. If you do not have an accurate inclination angle source, it is recommended that you leave the auto-mag calibration feature off.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2192,7 +2192,7 @@ struct MetadataFor /* .docs = */ "Magnetic Field Magnitude Source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2201,7 +2201,7 @@ struct MetadataFor /* .docs = */ "Magnitude [gauss] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2231,7 +2231,7 @@ struct MetadataFor /* .docs = */ "Magnetic Field Magnitude Source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2240,7 +2240,7 @@ struct MetadataFor /* .docs = */ "Magnitude [gauss] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2252,7 +2252,7 @@ struct MetadataFor /* .docs = */ "Set/Get the local magnetic field magnitude source.\n\nThis is used to specify the local magnitude of the earth's magnetic field.\nHaving a correct value for magnitude is important for best performance of the auto-mag calibration feature and for the magnetometer adaptive magnitude. If you do not have an accurate value for the local magnetic field magnitude, it is recommended that you leave the auto-mag calibration feature off.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2269,7 +2269,7 @@ struct MetadataFor /* .docs = */ "enable/disable", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2278,7 +2278,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2287,7 +2287,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2296,7 +2296,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2326,7 +2326,7 @@ struct MetadataFor /* .docs = */ "enable/disable", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2335,7 +2335,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2344,7 +2344,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2353,7 +2353,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2365,7 +2365,7 @@ struct MetadataFor /* .docs = */ "Set the Lat/Long/Alt reference position for the sensor.\n\nThis position is used by the sensor to calculate the WGS84 gravity and WMM2015 magnetic field parameters.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2377,9 +2377,9 @@ struct MetadataFor using type = commands_filter::FilterAdaptiveMeasurement; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "DISABLED", "No adaptive measurement" }, - { 1, "FIXED", "Enable fixed adaptive measurement (use specified limits)" }, - { 2, "AUTO", "Enable auto adaptive measurement" }, + { uint32_t(0), "DISABLED", "No adaptive measurement" }, + { uint32_t(1), "FIXED", "Enable fixed adaptive measurement (use specified limits)" }, + { uint32_t(2), "AUTO", "Enable auto adaptive measurement" }, }; static constexpr inline EnumInfo value = { @@ -2402,7 +2402,7 @@ struct MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2411,7 +2411,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2420,7 +2420,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2429,7 +2429,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2438,7 +2438,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2447,7 +2447,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2456,7 +2456,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2486,7 +2486,7 @@ struct MetadataFor /* .docs = */ "Adaptive measurement selector", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2495,7 +2495,7 @@ struct MetadataFor /* .docs = */ "Low-pass filter curoff frequency [hertz]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2504,7 +2504,7 @@ struct MetadataFor /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2513,7 +2513,7 @@ struct MetadataFor /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2522,7 +2522,7 @@ struct MetadataFor /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2531,7 +2531,7 @@ struct MetadataFor /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2540,7 +2540,7 @@ struct MetadataFor /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2552,7 +2552,7 @@ struct MetadataFor /* .docs = */ "Enable or disable the gravity magnitude error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nAdaptive measurements can be enabled/disabled without the need for providing the additional parameters.\nIn this case, only the function selector and enable value are required; all other parameters will remain at their previous values.\nWhen “auto-adaptive” is selected, the filter and limit parameters are ignored.\nInstead, aiding measurements which rely on the gravity vector will be automatically reweighted by the Kalman filter according to the perceived measurement quality.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2569,7 +2569,7 @@ struct MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2578,7 +2578,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2587,7 +2587,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2596,7 +2596,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2605,7 +2605,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2614,7 +2614,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2623,7 +2623,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2653,7 +2653,7 @@ struct MetadataFor /* .docs = */ "Adaptive measurement selector", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2662,7 +2662,7 @@ struct MetadataFor /* .docs = */ "Low-pass filter curoff frequency [hertz]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2671,7 +2671,7 @@ struct MetadataFor /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2680,7 +2680,7 @@ struct MetadataFor /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2689,7 +2689,7 @@ struct MetadataFor /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2698,7 +2698,7 @@ struct MetadataFor /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2707,7 +2707,7 @@ struct MetadataFor /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2719,7 +2719,7 @@ struct MetadataFor /* .docs = */ "Enable or disable the magnetometer magnitude error adaptive measurement.\nThis feature will reject magnetometer readings that are out of range of the thresholds specified (fixed adaptive) or calculated internally (auto-adaptive).\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2736,7 +2736,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2745,7 +2745,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2754,7 +2754,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2763,7 +2763,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2772,7 +2772,7 @@ struct MetadataFor, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2802,7 +2802,7 @@ struct MetadataFor /* .docs = */ "Enable/Disable", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2811,7 +2811,7 @@ struct MetadataFor /* .docs = */ "Low-pass filter curoff frequency [hertz]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2820,7 +2820,7 @@ struct MetadataFor /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2829,7 +2829,7 @@ struct MetadataFor /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2838,7 +2838,7 @@ struct MetadataFor /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2850,7 +2850,7 @@ struct MetadataFor /* .docs = */ "Enable or disable the magnetometer dip angle error adaptive measurement.\nThis function can be used to tune the filter performance in the target application\n\nPick values that give you the least occurrence of invalid EF attitude output.\nThe default values are good for standard low dynamics applications.\nIncrease values for higher dynamic conditions, lower values for lower dynamic.\nToo low a value will result in excessive heading errors.\nHigher values increase heading errors when undergoing magnetic field anomalies caused by DC currents, magnets, steel structures,etc.\n\nThe magnetometer dip angle adaptive measurement is ignored if the auto-adaptive magnetometer magnitude or auto-adaptive accel magnitude options are selected.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2862,16 +2862,16 @@ struct MetadataFor using type = commands_filter::AidingMeasurementEnable::AidingSource; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "GNSS_POS_VEL", "GNSS Position and Velocity" }, - { 1, "GNSS_HEADING", "GNSS Heading (dual antenna)" }, - { 2, "ALTIMETER", "Pressure altimeter (built-in sensor)" }, - { 3, "SPEED", "Speed sensor / Odometer" }, - { 4, "MAGNETOMETER", "Magnetometer (built-in sensor)" }, - { 5, "EXTERNAL_HEADING", "External heading input" }, - { 6, "EXTERNAL_ALTIMETER", "External pressure altimeter input" }, - { 7, "EXTERNAL_MAGNETOMETER", "External magnetomer input" }, - { 8, "BODY_FRAME_VEL", "External body frame velocity input" }, - { 65535, "ALL", "Save/load/reset all options" }, + { uint32_t(0), "GNSS_POS_VEL", "GNSS Position and Velocity" }, + { uint32_t(1), "GNSS_HEADING", "GNSS Heading (dual antenna)" }, + { uint32_t(2), "ALTIMETER", "Pressure altimeter (built-in sensor)" }, + { uint32_t(3), "SPEED", "Speed sensor / Odometer" }, + { uint32_t(4), "MAGNETOMETER", "Magnetometer (built-in sensor)" }, + { uint32_t(5), "EXTERNAL_HEADING", "External heading input" }, + { uint32_t(6), "EXTERNAL_ALTIMETER", "External pressure altimeter input" }, + { uint32_t(7), "EXTERNAL_MAGNETOMETER", "External magnetomer input" }, + { uint32_t(8), "BODY_FRAME_VEL", "External body frame velocity input" }, + { uint32_t(65535), "ALL", "Save/load/reset all options" }, }; static constexpr inline EnumInfo value = { @@ -2894,7 +2894,7 @@ struct MetadataFor /* .docs = */ "Aiding measurement source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2903,7 +2903,7 @@ struct MetadataFor /* .docs = */ "Controls the aiding source", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2933,7 +2933,7 @@ struct MetadataFor /* .docs = */ "Aiding measurement source", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2942,7 +2942,7 @@ struct MetadataFor /* .docs = */ "Controls the aiding source", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2954,7 +2954,7 @@ struct MetadataFor /* .docs = */ "Enables / disables the specified aiding measurement source.\n\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -2988,7 +2988,7 @@ struct MetadataFor /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2997,7 +2997,7 @@ struct MetadataFor /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3006,7 +3006,7 @@ struct MetadataFor /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3036,7 +3036,7 @@ struct MetadataFor /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3045,7 +3045,7 @@ struct MetadataFor /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3054,7 +3054,7 @@ struct MetadataFor /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3066,7 +3066,7 @@ struct MetadataFor /* .docs = */ "Controls kinematic constraint model selection for the navigation filter.\n\nSee manual for explanation of how the kinematic constraints are applied.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3078,8 +3078,8 @@ struct MetadataFor using type = commands_filter::FilterReferenceFrame; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "ECEF", "WGS84 Earth-fixed, earth centered coordinates" }, - { 2, "LLH", "WGS84 Latitude, longitude, and height above ellipsoid" }, + { uint32_t(1), "ECEF", "WGS84 Earth-fixed, earth centered coordinates" }, + { uint32_t(2), "LLH", "WGS84 Latitude, longitude, and height above ellipsoid" }, }; static constexpr inline EnumInfo value = { @@ -3097,10 +3097,10 @@ struct MetadataFor /* .docs = */ "Initialize filter only after receiving 'run' command", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3153,16 +3153,16 @@ struct MetadataFor /* .docs = */ "Initial condition source:", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "auto_heading_alignment_selector", /* .docs = */ "Bitfield specifying the allowed automatic heading alignment methods for automatic initial conditions. Bits are set to 1 to enable, and the correspond to the following:
", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3171,7 +3171,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform heading (degrees).", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3180,7 +3180,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform pitch (degrees)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3189,7 +3189,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform roll (degrees)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3198,7 +3198,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform position (units determined by reference frame selector, see note.)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3207,7 +3207,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform velocity (units determined by reference frame selector, see note.)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3216,7 +3216,7 @@ struct MetadataFor /* .docs = */ "User-specified initial position/velocity reference frames", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3246,7 +3246,7 @@ struct MetadataFor /* .docs = */ "Initialize filter only after receiving 'run' command", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3255,16 +3255,16 @@ struct MetadataFor /* .docs = */ "Initial condition source:", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "auto_heading_alignment_selector", /* .docs = */ "Bitfield specifying the allowed automatic heading alignment methods for automatic initial conditions. Bits are set to 1 to enable, and the correspond to the following:
", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3273,7 +3273,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform heading (degrees).", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3282,7 +3282,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform pitch (degrees)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3291,7 +3291,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform roll (degrees)", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3300,7 +3300,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform position (units determined by reference frame selector, see note.)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3309,7 +3309,7 @@ struct MetadataFor /* .docs = */ "User-specified initial platform velocity (units determined by reference frame selector, see note.)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3318,7 +3318,7 @@ struct MetadataFor /* .docs = */ "User-specified initial position/velocity reference frames", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3330,7 +3330,7 @@ struct MetadataFor /* .docs = */ "Controls the source and values used for initial conditions of the navigation solution.\n\nNotes: Initial conditions are the position, velocity, and attitude of the platform used when the filter starts running or is reset.\nFor the user specified position array, the units are meters if the ECEF frame is selected, and degrees latitude, degrees longitude, and meters above ellipsoid if the latitude/longitude/height frame is selected.\nFor the user specified velocity array, the units are meters per second, but the reference frame depends on the reference frame selector (ECEF or NED).", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3347,7 +3347,7 @@ struct MetadataFor /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3356,7 +3356,7 @@ struct MetadataFor /* .docs = */ "Maximum duration of measurement rejection before entering recovery mode (ms)", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3386,7 +3386,7 @@ struct MetadataFor /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3395,7 +3395,7 @@ struct MetadataFor /* .docs = */ "Maximum duration of measurement rejection before entering recovery mode (ms)", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3407,7 +3407,7 @@ struct MetadataFor /* .docs = */ "Configures the basic setup for auto-adaptive filtering. See product manual for a detailed description of this feature.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3424,7 +3424,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3433,7 +3433,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3463,7 +3463,7 @@ struct MetadataFor /* .docs = */ "Receiver: 1, 2, etc...", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3472,7 +3472,7 @@ struct MetadataFor /* .docs = */ "Antenna lever arm offset vector in the vehicle frame (m)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3484,7 +3484,7 @@ struct MetadataFor /* .docs = */ "Set the antenna lever arm.\n\nThis command works with devices that utilize multiple antennas.\n

Offset Limit: 10 m magnitude (default)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3501,7 +3501,7 @@ struct MetadataFor /* .docs = */ "0 - auto (RTK base station), 1 - manual", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3510,7 +3510,7 @@ struct MetadataFor /* .docs = */ "ECEF or LLH", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3519,7 +3519,7 @@ struct MetadataFor /* .docs = */ "reference coordinates, units determined by source selection", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3549,7 +3549,7 @@ struct MetadataFor /* .docs = */ "0 - auto (RTK base station), 1 - manual", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3558,7 +3558,7 @@ struct MetadataFor /* .docs = */ "ECEF or LLH", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3567,7 +3567,7 @@ struct MetadataFor /* .docs = */ "reference coordinates, units determined by source selection", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3579,7 +3579,7 @@ struct MetadataFor /* .docs = */ "Configure the reference location for filter relative positioning outputs", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3591,7 +3591,7 @@ struct MetadataFor using type = commands_filter::RefPointLeverArm::ReferencePointSelector; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "VEH", "Defines the origin of the vehicle" }, + { uint32_t(1), "VEH", "Defines the origin of the vehicle" }, }; static constexpr inline EnumInfo value = { @@ -3614,7 +3614,7 @@ struct MetadataFor /* .docs = */ "Reserved, must be 1", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3623,7 +3623,7 @@ struct MetadataFor /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3653,7 +3653,7 @@ struct MetadataFor /* .docs = */ "Reserved, must be 1", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3662,7 +3662,7 @@ struct MetadataFor /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3674,7 +3674,7 @@ struct MetadataFor /* .docs = */ "Lever arm offset with respect to the sensor for the indicated point of reference.\nThis is used to change the location of the indicated point of reference, and will affect filter position and velocity outputs.\nChanging this setting from default will result in a global position offset that depends on vehicle attitude,\nand a velocity offset that depends on vehicle attitude and angular rate.\n
The lever arm is defined by a 3-element vector that points from the sensor to the desired reference point, with (x,y,z) components given in the vehicle's reference frame.\n

Note, if the reference point selector is set to VEH (1), this setting will affect the following data fields: (0x82, 0x01), (0x82, 0x02), (0x82, 0x40), (0x82, 0x41), and (0x82, 42)\n

Offset Limits\n
Reference Point VEH (1): 10 m magnitude (default)", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3691,7 +3691,7 @@ struct MetadataFor /* .docs = */ "Reserved, must be 1.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3700,7 +3700,7 @@ struct MetadataFor /* .docs = */ "GPS time of week when speed was sampled", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3709,7 +3709,7 @@ struct MetadataFor /* .docs = */ "Estimated speed along vehicle's x-axis (may be positive or negative) [meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3718,7 +3718,7 @@ struct MetadataFor /* .docs = */ "Estimated uncertainty in the speed measurement (1-sigma value) [meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3747,7 +3747,7 @@ struct MetadataFor /* .docs = */ "Reserved, must be 1.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3756,7 +3756,7 @@ struct MetadataFor /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3786,7 +3786,7 @@ struct MetadataFor /* .docs = */ "Reserved, must be 1.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, true, true, true, true, true}, + /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3795,7 +3795,7 @@ struct MetadataFor /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3807,7 +3807,7 @@ struct MetadataFor /* .docs = */ "Lever arm offset for speed measurements.\nThis is used to compensate for an off-center measurement point\nhaving a different speed due to rotation of the vehicle.\nThe typical use case for this would be an odometer attached to a wheel\non a standard 4-wheeled vehicle. If the odometer is on the left wheel,\nit will report higher speed on right turns and lower speed on left turns.\nThis is because the outside edge of the curve is longer than the inside edge.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3824,7 +3824,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3854,7 +3854,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3866,7 +3866,7 @@ struct MetadataFor /* .docs = */ "Configure the wheeled vehicle kinematic constraint.\n\nWhen enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis.\nBy convention, the primary vehicle axis is the vehicle X-axis (note: the sensor may be physically installed in\nany orientation on the vehicle if the appropriate mounting transformation has been specified).\nThis constraint will typically improve heading estimates for vehicles where the assumption is valid, such\nas an automobile, particularly when GNSS coverage is intermittent.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3883,7 +3883,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3913,7 +3913,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3925,7 +3925,7 @@ struct MetadataFor /* .docs = */ "Configure the vertical gyro kinematic constraint.\n\nWhen enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track pitch\nand roll under the assumption that the sensor platform is not undergoing linear acceleration.\nThis constraint is useful to maintain accurate pitch and roll during GNSS signal outages.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -3942,7 +3942,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3951,7 +3951,7 @@ struct MetadataFor /* .docs = */ "Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3981,7 +3981,7 @@ struct MetadataFor /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3990,7 +3990,7 @@ struct MetadataFor /* .docs = */ "Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4002,7 +4002,7 @@ struct MetadataFor /* .docs = */ "Configure the GNSS antenna lever arm calibration.\n\nWhen enabled, the filter will enable lever arm error tracking, up to the maximum offset specified.", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -4019,7 +4019,7 @@ struct MetadataFor /* .docs = */ "Initial heading in radians [-pi, pi]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -4038,7 +4038,7 @@ struct MetadataFor }; -static constexpr inline std::initializer_list ALL_COMMANDS_FILTER = { +static constexpr inline std::initializer_list COMMANDS_FILTER = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/commands_gnss.hpp b/src/cpp/mip/metadata/definitions/commands_gnss.hpp index 1f53daf67..ecb421bb5 100644 --- a/src/cpp/mip/metadata/definitions/commands_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/commands_gnss.hpp @@ -21,7 +21,7 @@ struct MetadataFor /* .docs = */ "Receiver id: e.g. 1, 2, etc.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -30,7 +30,7 @@ struct MetadataFor /* .docs = */ "MIP descriptor set associated with this receiver", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, }, @@ -39,7 +39,7 @@ struct MetadataFor /* .docs = */ "Ascii description of receiver. Contains the following info (comma-delimited):
\nModule name/model
\nFirmware version info", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ NO_FUNCTIONS, + /* .attributes = */ NO_FUNCTIONS, /* .count = */ 32, /* .condition = */ {}, }, @@ -64,7 +64,7 @@ struct MetadataFor /* .docs = */ "Number of physical receivers in the device", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -73,7 +73,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ {5, microstrain::Index(0) /* num_receivers */}, /* .condition = */ {}, }, @@ -116,10 +116,10 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { /* .name = */ "gps_enable", - /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C", + /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -128,25 +128,25 @@ struct MetadataFor /* .docs = */ "Bitfield 0: Enable L1OF, 1: Enable L2OF", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "galileo_enable", - /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B", + /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "beidou_enable", - /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2", + /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -155,7 +155,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, }, @@ -182,10 +182,10 @@ struct MetadataFor FUNCTION_SELECTOR_PARAM, { /* .name = */ "gps_enable", - /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C", + /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -194,25 +194,25 @@ struct MetadataFor /* .docs = */ "Bitfield 0: Enable L1OF, 1: Enable L2OF", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "galileo_enable", - /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B", + /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "beidou_enable", - /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2", + /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -221,7 +221,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, }, @@ -233,7 +233,7 @@ struct MetadataFor /* .docs = */ "Configure the GNSS signals used by the device.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -250,7 +250,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -259,7 +259,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 3, /* .condition = */ {}, }, @@ -289,7 +289,7 @@ struct MetadataFor /* .docs = */ "0 - Disabled, 1- Enabled", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -298,7 +298,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 3, /* .condition = */ {}, }, @@ -310,14 +310,14 @@ struct MetadataFor /* .docs = */ "Configure the communications with the RTK Dongle connected to the device.\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; }; -static constexpr inline std::initializer_list ALL_COMMANDS_GNSS = { +static constexpr inline std::initializer_list COMMANDS_GNSS = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/commands_rtk.hpp b/src/cpp/mip/metadata/definitions/commands_rtk.hpp index 98a45ba30..45f67104a 100644 --- a/src/cpp/mip/metadata/definitions/commands_rtk.hpp +++ b/src/cpp/mip/metadata/definitions/commands_rtk.hpp @@ -16,17 +16,17 @@ struct MetadataFor using type = commands_rtk::GetStatusFlags::StatusFlagsLegacy; static constexpr inline BitfieldInfo::Entry entries[] = { - { 7, "controllerState", "" }, - { 248, "platformState", "" }, - { 1792, "controllerStatusCode", "" }, - { 14336, "platformStatusCode", "" }, - { 49152, "resetCode", "" }, - { 983040, "signalQuality", "" }, - { 4293918720, "reserved", "" }, - { 66060288, "rssi", "" }, - { 201326592, "rsrp", "" }, - { 805306368, "rsrq", "" }, - { 3221225472, "sinr", "" }, + { uint32_t(7), "controllerState", "" }, + { uint32_t(248), "platformState", "" }, + { uint32_t(1792), "controllerStatusCode", "" }, + { uint32_t(14336), "platformStatusCode", "" }, + { uint32_t(49152), "resetCode", "" }, + { uint32_t(983040), "signalQuality", "" }, + { uint32_t(4293918720), "reserved", "" }, + { uint32_t(66060288), "rssi", "" }, + { uint32_t(201326592), "rsrp", "" }, + { uint32_t(805306368), "rsrq", "" }, + { uint32_t(3221225472), "sinr", "" }, }; static constexpr inline BitfieldInfo value = { @@ -44,18 +44,18 @@ struct MetadataFor using type = commands_rtk::GetStatusFlags::StatusFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 15, "modem_state", "" }, - { 240, "connection_type", "" }, - { 65280, "rssi", "" }, - { 983040, "signal_quality", "" }, - { 15728640, "tower_change_indicator", "" }, - { 16777216, "nmea_timeout", "" }, - { 33554432, "server_timeout", "" }, - { 67108864, "corrections_timeout", "" }, - { 134217728, "device_out_of_range", "" }, - { 268435456, "corrections_unavailable", "" }, - { 536870912, "reserved", "" }, - { 3221225472, "version", "" }, + { uint32_t(15), "modem_state", "" }, + { uint32_t(240), "connection_type", "" }, + { uint32_t(65280), "rssi", "" }, + { uint32_t(983040), "signal_quality", "" }, + { uint32_t(15728640), "tower_change_indicator", "" }, + { uint32_t(16777216), "nmea_timeout", "" }, + { uint32_t(33554432), "server_timeout", "" }, + { uint32_t(67108864), "corrections_timeout", "" }, + { uint32_t(134217728), "device_out_of_range", "" }, + { uint32_t(268435456), "corrections_unavailable", "" }, + { uint32_t(536870912), "reserved", "" }, + { uint32_t(3221225472), "version", "" }, }; static constexpr inline BitfieldInfo value = { @@ -76,9 +76,9 @@ struct MetadataFor { /* .name = */ "flags", /* .docs = */ "Model number dependent. See above structures.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -124,7 +124,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, }, @@ -170,7 +170,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, }, @@ -216,7 +216,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, }, @@ -257,8 +257,8 @@ struct MetadataFor using type = commands_rtk::ConnectedDeviceType::Type; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "GENERIC", "" }, - { 1, "GQ7", "" }, + { uint32_t(0), "GENERIC", "" }, + { uint32_t(1), "GQ7", "" }, }; static constexpr inline EnumInfo value = { @@ -281,7 +281,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -311,7 +311,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -323,7 +323,7 @@ struct MetadataFor /* .docs = */ "", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, true, true, true, true}, + /* .functions = */ {true, true, true, true, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; @@ -340,7 +340,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, }, @@ -386,7 +386,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, }, @@ -432,7 +432,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -441,7 +441,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::S32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -450,7 +450,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::S32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -491,9 +491,9 @@ struct MetadataFor using type = commands_rtk::ServiceStatus::ServiceFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "throttle", "" }, - { 2, "corrections_unavailable", "" }, - { 252, "reserved", "" }, + { uint32_t(1), "throttle", "" }, + { uint32_t(2), "corrections_unavailable", "" }, + { uint32_t(252), "reserved", "" }, }; static constexpr inline BitfieldInfo value = { @@ -514,9 +514,9 @@ struct MetadataFor { /* .name = */ "flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -525,7 +525,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -534,7 +534,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -543,7 +543,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U64, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -572,7 +572,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -581,7 +581,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -605,8 +605,8 @@ struct MetadataFor using type = commands_rtk::MediaSelector; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "MEDIA_ExternalFlash", "" }, - { 1, "MEDIA_SD", "" }, + { uint32_t(0), "MEDIA_ExternalFlash", "" }, + { uint32_t(1), "MEDIA_SD", "" }, }; static constexpr inline EnumInfo value = { @@ -629,7 +629,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -653,9 +653,9 @@ struct MetadataFor using type = commands_rtk::LedAction; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "LED_NONE", "" }, - { 1, "LED_FLASH", "" }, - { 2, "LED_PULSATE", "" }, + { uint32_t(0), "LED_NONE", "" }, + { uint32_t(1), "LED_FLASH", "" }, + { uint32_t(2), "LED_PULSATE", "" }, }; static constexpr inline EnumInfo value = { @@ -678,7 +678,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 3, /* .condition = */ {}, }, @@ -687,7 +687,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 3, /* .condition = */ {}, }, @@ -696,7 +696,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -705,7 +705,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -741,7 +741,7 @@ struct MetadataFor }; -static constexpr inline std::initializer_list ALL_COMMANDS_RTK = { +static constexpr inline std::initializer_list COMMANDS_RTK = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/commands_system.hpp b/src/cpp/mip/metadata/definitions/commands_system.hpp index 6d7ef219f..559b30fd5 100644 --- a/src/cpp/mip/metadata/definitions/commands_system.hpp +++ b/src/cpp/mip/metadata/definitions/commands_system.hpp @@ -21,7 +21,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -51,7 +51,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -63,14 +63,14 @@ struct MetadataFor /* .docs = */ "Advanced specialized communication modes.\n\nThis command allows the user to communicate directly with various subsystems which may be present in MIP devices (i.e. IMU, GNSS, etc.)\nPlease see the specific device's user manual for possible modes.\n\nThis command responds with an ACK/NACK just prior to switching to the new protocol.\nFor all functions except 0x01 (use new settings), the new communications mode value is ignored.\n\n", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, - /* .functions = */ {true, true, false, false, true, true}, + /* .functions = */ {true, true, false, false, true}, /* .proprietary = */ false, /* .response = */ &MetadataFor::value, }; }; -static constexpr inline std::initializer_list ALL_COMMANDS_SYSTEM = { +static constexpr inline std::initializer_list COMMANDS_SYSTEM = { &MetadataFor::value, &MetadataFor::value, }; diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index fccaac0b7..c6cdc36f1 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -79,7 +79,7 @@ struct MetadataFor .docs = "The field descriptor of the command this field acknowledges.", .type = {Type::U8}, .accessor = utils::access, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 1, .condition = {}, }, @@ -88,7 +88,7 @@ struct MetadataFor .docs = "Result of the command.", .type = {Type::ENUM, &MetadataFor::value}, .accessor = utils::access, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 1, .condition = {}, }, @@ -117,7 +117,7 @@ struct MetadataFor .docs = "MIP data descriptor", .type = {Type::U8}, .accessor = utils::access, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 1, .condition = {}, }, @@ -126,7 +126,7 @@ struct MetadataFor .docs = "Decimation from the base rate", .type = {Type::U16}, .accessor = utils::access, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 1, .condition = {}, }, @@ -152,7 +152,7 @@ struct MetadataFor> .docs = "X axis", .type = {utils::ParamType::value}, .accessor = nullptr, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 1, .condition = {}, }, @@ -161,7 +161,7 @@ struct MetadataFor> .docs = "Y axis", .type = {utils::ParamType::value}, .accessor = nullptr, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 1, .condition = {}, }, @@ -170,7 +170,7 @@ struct MetadataFor> .docs = "Z axis", .type = {utils::ParamType::value}, .accessor = nullptr, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 1, .condition = {}, }, @@ -179,7 +179,7 @@ struct MetadataFor> .docs = "W axis", .type = {utils::ParamType::value}, .accessor = nullptr, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 1, .condition = {}, }, @@ -245,7 +245,7 @@ struct MetadataFor .docs = "Matrix data", .type = {Type::FLOAT}, .accessor = nullptr, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 3, .condition = {}, }, @@ -270,7 +270,7 @@ struct MetadataFor .docs = "Matrix data", .type = {Type::DOUBLE}, .accessor = nullptr, - .functions = NO_FUNCTIONS, + .attributes = NO_FUNCTIONS, .count = 3, .condition = {}, }, diff --git a/src/cpp/mip/metadata/definitions/data_filter.hpp b/src/cpp/mip/metadata/definitions/data_filter.hpp index f12adcbb1..09e7e8415 100644 --- a/src/cpp/mip/metadata/definitions/data_filter.hpp +++ b/src/cpp/mip/metadata/definitions/data_filter.hpp @@ -21,7 +21,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -30,7 +30,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -39,7 +39,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -48,7 +48,7 @@ struct MetadataFor /* .docs = */ "0 - Invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -77,7 +77,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -86,7 +86,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -95,7 +95,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -104,7 +104,7 @@ struct MetadataFor /* .docs = */ "0 - Invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -133,7 +133,7 @@ struct MetadataFor /* .docs = */ "Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -142,7 +142,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -171,7 +171,7 @@ struct MetadataFor /* .docs = */ "Matrix elements in row-major order.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -180,7 +180,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -209,7 +209,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -218,7 +218,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -227,7 +227,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -236,7 +236,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -265,7 +265,7 @@ struct MetadataFor /* .docs = */ "(x, y, z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -274,7 +274,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -303,7 +303,7 @@ struct MetadataFor /* .docs = */ "(x, y, z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -312,7 +312,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -341,7 +341,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -350,7 +350,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -359,7 +359,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -368,7 +368,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -397,7 +397,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -406,7 +406,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -415,7 +415,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -424,7 +424,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -453,7 +453,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -462,7 +462,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -471,7 +471,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -480,7 +480,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -509,7 +509,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [radians/sec]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -518,7 +518,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -547,7 +547,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -556,7 +556,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -585,7 +585,7 @@ struct MetadataFor /* .docs = */ "GPS Time of Week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -594,7 +594,7 @@ struct MetadataFor /* .docs = */ "GPS Week Number since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -603,7 +603,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -627,14 +627,14 @@ struct MetadataFor using type = data_filter::FilterMode; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "GX5_STARTUP", "" }, - { 1, "GX5_INIT", "" }, - { 2, "GX5_RUN_SOLUTION_VALID", "" }, - { 3, "GX5_RUN_SOLUTION_ERROR", "" }, - { 1, "INIT", "" }, - { 2, "VERT_GYRO", "" }, - { 3, "AHRS", "" }, - { 4, "FULL_NAV", "" }, + { uint32_t(0), "GX5_STARTUP", "" }, + { uint32_t(1), "GX5_INIT", "" }, + { uint32_t(2), "GX5_RUN_SOLUTION_VALID", "" }, + { uint32_t(3), "GX5_RUN_SOLUTION_ERROR", "" }, + { uint32_t(1), "INIT", "" }, + { uint32_t(2), "VERT_GYRO", "" }, + { uint32_t(3), "AHRS", "" }, + { uint32_t(4), "FULL_NAV", "" }, }; static constexpr inline EnumInfo value = { @@ -652,10 +652,10 @@ struct MetadataFor using type = data_filter::FilterDynamicsMode; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "GX5_PORTABLE", "" }, - { 2, "GX5_AUTOMOTIVE", "" }, - { 3, "GX5_AIRBORNE", "" }, - { 1, "GQ7_DEFAULT", "" }, + { uint32_t(1), "GX5_PORTABLE", "" }, + { uint32_t(2), "GX5_AUTOMOTIVE", "" }, + { uint32_t(3), "GX5_AIRBORNE", "" }, + { uint32_t(1), "GQ7_DEFAULT", "" }, }; static constexpr inline EnumInfo value = { @@ -673,34 +673,34 @@ struct MetadataFor using type = data_filter::FilterStatusFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 4096, "gx5_init_no_attitude", "" }, - { 8192, "gx5_init_no_position_velocity", "" }, - { 1, "gx5_run_imu_unavailable", "" }, - { 2, "gx5_run_gps_unavailable", "" }, - { 8, "gx5_run_matrix_singularity", "" }, - { 16, "gx5_run_position_covariance_warning", "" }, - { 32, "gx5_run_velocity_covariance_warning", "" }, - { 64, "gx5_run_attitude_covariance_warning", "" }, - { 128, "gx5_run_nan_in_solution_warning", "" }, - { 256, "gx5_run_gyro_bias_est_high_warning", "" }, - { 512, "gx5_run_accel_bias_est_high_warning", "" }, - { 1024, "gx5_run_gyro_scale_factor_est_high_warning", "" }, - { 2048, "gx5_run_accel_scale_factor_est_high_warning", "" }, - { 4096, "gx5_run_mag_bias_est_high_warning", "" }, - { 8192, "gx5_run_ant_offset_correction_est_high_warning", "" }, - { 16384, "gx5_run_mag_hard_iron_est_high_warning", "" }, - { 32768, "gx5_run_mag_soft_iron_est_high_warning", "" }, - { 3, "gq7_filter_condition", "" }, - { 4, "gq7_roll_pitch_warning", "" }, - { 8, "gq7_heading_warning", "" }, - { 16, "gq7_position_warning", "" }, - { 32, "gq7_velocity_warning", "" }, - { 64, "gq7_imu_bias_warning", "" }, - { 128, "gq7_gnss_clk_warning", "" }, - { 256, "gq7_antenna_lever_arm_warning", "" }, - { 512, "gq7_mounting_transform_warning", "" }, - { 1024, "gq7_time_sync_warning", "No time synchronization pulse detected" }, - { 61440, "gq7_solution_error", "Filter computation warning flags. If any bits 12-15 are set, and all filter outputs will be invalid." }, + { uint32_t(4096), "gx5_init_no_attitude", "" }, + { uint32_t(8192), "gx5_init_no_position_velocity", "" }, + { uint32_t(1), "gx5_run_imu_unavailable", "" }, + { uint32_t(2), "gx5_run_gps_unavailable", "" }, + { uint32_t(8), "gx5_run_matrix_singularity", "" }, + { uint32_t(16), "gx5_run_position_covariance_warning", "" }, + { uint32_t(32), "gx5_run_velocity_covariance_warning", "" }, + { uint32_t(64), "gx5_run_attitude_covariance_warning", "" }, + { uint32_t(128), "gx5_run_nan_in_solution_warning", "" }, + { uint32_t(256), "gx5_run_gyro_bias_est_high_warning", "" }, + { uint32_t(512), "gx5_run_accel_bias_est_high_warning", "" }, + { uint32_t(1024), "gx5_run_gyro_scale_factor_est_high_warning", "" }, + { uint32_t(2048), "gx5_run_accel_scale_factor_est_high_warning", "" }, + { uint32_t(4096), "gx5_run_mag_bias_est_high_warning", "" }, + { uint32_t(8192), "gx5_run_ant_offset_correction_est_high_warning", "" }, + { uint32_t(16384), "gx5_run_mag_hard_iron_est_high_warning", "" }, + { uint32_t(32768), "gx5_run_mag_soft_iron_est_high_warning", "" }, + { uint32_t(3), "gq7_filter_condition", "" }, + { uint32_t(4), "gq7_roll_pitch_warning", "" }, + { uint32_t(8), "gq7_heading_warning", "" }, + { uint32_t(16), "gq7_position_warning", "" }, + { uint32_t(32), "gq7_velocity_warning", "" }, + { uint32_t(64), "gq7_imu_bias_warning", "" }, + { uint32_t(128), "gq7_gnss_clk_warning", "" }, + { uint32_t(256), "gq7_antenna_lever_arm_warning", "" }, + { uint32_t(512), "gq7_mounting_transform_warning", "" }, + { uint32_t(1024), "gq7_time_sync_warning", "No time synchronization pulse detected" }, + { uint32_t(61440), "gq7_solution_error", "Filter computation warning flags. If any bits 12-15 are set, and all filter outputs will be invalid." }, }; static constexpr inline BitfieldInfo value = { @@ -723,7 +723,7 @@ struct MetadataFor /* .docs = */ "Device-specific filter state. Please consult the user manual for definition.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -732,16 +732,16 @@ struct MetadataFor /* .docs = */ "Device-specific dynamics mode. Please consult the user manual for definition.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "status_flags", /* .docs = */ "Device-specific status flags. Please consult the user manual for definition.", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -770,7 +770,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -779,7 +779,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -808,7 +808,7 @@ struct MetadataFor /* .docs = */ "(x, y, z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -817,7 +817,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -846,7 +846,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -855,7 +855,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -884,7 +884,7 @@ struct MetadataFor /* .docs = */ "(x, y, z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -893,7 +893,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -922,7 +922,7 @@ struct MetadataFor /* .docs = */ "[dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -931,7 +931,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -960,7 +960,7 @@ struct MetadataFor /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -969,7 +969,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -993,11 +993,11 @@ struct MetadataFor using type = data_filter::HeadingUpdateState::HeadingSource; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "NONE", "" }, - { 1, "MAGNETOMETER", "" }, - { 2, "GNSS_VELOCITY_VECTOR", "" }, - { 4, "EXTERNAL", "" }, - { 8, "DUAL_ANTENNA", "" }, + { uint32_t(0), "NONE", "" }, + { uint32_t(1), "MAGNETOMETER", "" }, + { uint32_t(2), "GNSS_VELOCITY_VECTOR", "" }, + { uint32_t(4), "EXTERNAL", "" }, + { uint32_t(8), "DUAL_ANTENNA", "" }, }; static constexpr inline EnumInfo value = { @@ -1020,7 +1020,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1029,7 +1029,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1038,7 +1038,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1047,7 +1047,7 @@ struct MetadataFor /* .docs = */ "1 if a valid heading update was received in 2 seconds, 0 otherwise.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1076,7 +1076,7 @@ struct MetadataFor /* .docs = */ "[Gauss]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1085,7 +1085,7 @@ struct MetadataFor /* .docs = */ "[Gauss]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1094,7 +1094,7 @@ struct MetadataFor /* .docs = */ "[Gauss]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1103,7 +1103,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1112,7 +1112,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1121,7 +1121,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1150,7 +1150,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1159,7 +1159,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1188,7 +1188,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1197,7 +1197,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1226,7 +1226,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1235,7 +1235,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1264,7 +1264,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1273,7 +1273,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1302,7 +1302,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1311,7 +1311,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1340,7 +1340,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1349,7 +1349,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1378,7 +1378,7 @@ struct MetadataFor /* .docs = */ "Input into calculation [meters]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1387,7 +1387,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1396,7 +1396,7 @@ struct MetadataFor /* .docs = */ "[degC]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1405,7 +1405,7 @@ struct MetadataFor /* .docs = */ "[milliBar]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1414,7 +1414,7 @@ struct MetadataFor /* .docs = */ "[kilogram/meter^3]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1423,7 +1423,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1452,7 +1452,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1461,7 +1461,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1490,7 +1490,7 @@ struct MetadataFor /* .docs = */ "m", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1499,7 +1499,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1528,7 +1528,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1537,7 +1537,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1566,7 +1566,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1575,7 +1575,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1604,7 +1604,7 @@ struct MetadataFor /* .docs = */ "Receiver ID for the receiver to which the antenna is attached", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1613,7 +1613,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1622,7 +1622,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1651,7 +1651,7 @@ struct MetadataFor /* .docs = */ "Receiver ID for the receiver to which the antenna is attached", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1660,7 +1660,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1669,7 +1669,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1698,7 +1698,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1707,7 +1707,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1736,7 +1736,7 @@ struct MetadataFor /* .docs = */ "Row-major [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1745,7 +1745,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1774,7 +1774,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1783,7 +1783,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1812,7 +1812,7 @@ struct MetadataFor /* .docs = */ "Row-major [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1821,7 +1821,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1850,7 +1850,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1859,7 +1859,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1888,7 +1888,7 @@ struct MetadataFor /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1897,7 +1897,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1926,7 +1926,7 @@ struct MetadataFor /* .docs = */ "1, 2, etc.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1935,7 +1935,7 @@ struct MetadataFor /* .docs = */ "[seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1944,7 +1944,7 @@ struct MetadataFor /* .docs = */ "[seconds/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1953,7 +1953,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1982,7 +1982,7 @@ struct MetadataFor /* .docs = */ "1, 2, etc.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1991,7 +1991,7 @@ struct MetadataFor /* .docs = */ "[seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2000,7 +2000,7 @@ struct MetadataFor /* .docs = */ "[seconds/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2009,7 +2009,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2033,22 +2033,22 @@ struct MetadataFor using type = data_filter::GnssAidStatusFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tight_coupling", "If 1, the Kalman filter is processing raw range information from this GNSS module" }, - { 2, "differential", "If 1, the Kalman filter is processing RTK corrections from this GNSS module" }, - { 4, "integer_fix", "If 1, the Kalman filter has an RTK integer fix from this GNSS module, indicating the best position performance possible" }, - { 8, "GPS_L1", "If 1, the Kalman filter is using GPS L1 measurements" }, - { 16, "GPS_L2", "If 1, the Kalman filter is using GPS L2 measurements" }, - { 32, "GPS_L5", "If 1, the Kalman filter is using GPS L5 measurements (not available on the GQ7)" }, - { 64, "GLO_L1", "If 1, the Kalman filter is using GLONASS L1 measurements" }, - { 128, "GLO_L2", "If 1, the Kalman filter is using GLONASS L2 measurements" }, - { 256, "GAL_E1", "If 1, the Kalman filter is using Galileo E1 measurements" }, - { 512, "GAL_E5", "If 1, the Kalman filter is using Galileo E5 measurements" }, - { 1024, "GAL_E6", "If 1, the Kalman filter is using Galileo E6 measurements" }, - { 2048, "BEI_B1", "If 1, the Kalman filter is using Beidou B1 measurements (not enabled on GQ7 currently)" }, - { 4096, "BEI_B2", "If 1, the Kalman filter is using Beidou B2 measurements (not enabled on GQ7 currently)" }, - { 8192, "BEI_B3", "If 1, the Kalman filter is using Beidou B3 measurements (not available on the GQ7)" }, - { 16384, "no_fix", "If 1, this GNSS module is reporting no position fix" }, - { 32768, "config_error", "If 1, there is likely an issue with the antenna offset for this GNSS module" }, + { uint32_t(1), "tight_coupling", "If 1, the Kalman filter is processing raw range information from this GNSS module" }, + { uint32_t(2), "differential", "If 1, the Kalman filter is processing RTK corrections from this GNSS module" }, + { uint32_t(4), "integer_fix", "If 1, the Kalman filter has an RTK integer fix from this GNSS module, indicating the best position performance possible" }, + { uint32_t(8), "GPS_L1", "If 1, the Kalman filter is using GPS L1 measurements" }, + { uint32_t(16), "GPS_L2", "If 1, the Kalman filter is using GPS L2 measurements" }, + { uint32_t(32), "GPS_L5", "If 1, the Kalman filter is using GPS L5 measurements (not available on the GQ7)" }, + { uint32_t(64), "GLO_L1", "If 1, the Kalman filter is using GLONASS L1 measurements" }, + { uint32_t(128), "GLO_L2", "If 1, the Kalman filter is using GLONASS L2 measurements" }, + { uint32_t(256), "GAL_E1", "If 1, the Kalman filter is using Galileo E1 measurements" }, + { uint32_t(512), "GAL_E5", "If 1, the Kalman filter is using Galileo E5 measurements" }, + { uint32_t(1024), "GAL_E6", "If 1, the Kalman filter is using Galileo E6 measurements" }, + { uint32_t(2048), "BEI_B1", "If 1, the Kalman filter is using Beidou B1 measurements (not enabled on GQ7 currently)" }, + { uint32_t(4096), "BEI_B2", "If 1, the Kalman filter is using Beidou B2 measurements (not enabled on GQ7 currently)" }, + { uint32_t(8192), "BEI_B3", "If 1, the Kalman filter is using Beidou B3 measurements (not available on the GQ7)" }, + { uint32_t(16384), "no_fix", "If 1, this GNSS module is reporting no position fix" }, + { uint32_t(32768), "config_error", "If 1, there is likely an issue with the antenna offset for this GNSS module" }, }; static constexpr inline BitfieldInfo value = { @@ -2071,7 +2071,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2080,16 +2080,16 @@ struct MetadataFor /* .docs = */ "Last GNSS aiding measurement time of week [seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "status", /* .docs = */ "Aiding measurement status bitfield", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2098,7 +2098,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 8, /* .condition = */ {}, }, @@ -2127,16 +2127,16 @@ struct MetadataFor /* .docs = */ "Last valid aiding measurement time of week [seconds] [processed instead of measured?]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "status", /* .docs = */ "Last valid aiding measurement status bitfield", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2145,7 +2145,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 8, /* .condition = */ {}, }, @@ -2169,8 +2169,8 @@ struct MetadataFor using type = data_filter::HeadAidStatus::HeadingAidType; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "DUAL_ANTENNA", "" }, - { 2, "EXTERNAL_MESSAGE", "" }, + { uint32_t(1), "DUAL_ANTENNA", "" }, + { uint32_t(2), "EXTERNAL_MESSAGE", "" }, }; static constexpr inline EnumInfo value = { @@ -2193,7 +2193,7 @@ struct MetadataFor /* .docs = */ "Last valid aiding measurement time of week [seconds] [processed instead of measured?]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2202,7 +2202,7 @@ struct MetadataFor /* .docs = */ "1 - Dual antenna, 2 - External heading message (user supplied)", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2211,7 +2211,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 2, /* .condition = */ {}, }, @@ -2240,7 +2240,7 @@ struct MetadataFor /* .docs = */ "[meters, NED]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2249,7 +2249,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2278,7 +2278,7 @@ struct MetadataFor /* .docs = */ "[meters, ECEF]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2287,7 +2287,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2316,7 +2316,7 @@ struct MetadataFor /* .docs = */ "[meters/second, ECEF]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2325,7 +2325,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2354,7 +2354,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2363,7 +2363,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2392,7 +2392,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2401,7 +2401,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2425,21 +2425,21 @@ struct MetadataFor using type = data_filter::FilterAidingMeasurementType; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "GNSS", "" }, - { 2, "DUAL_ANTENNA", "" }, - { 3, "HEADING", "" }, - { 4, "PRESSURE", "" }, - { 5, "MAGNETOMETER", "" }, - { 6, "SPEED", "" }, - { 33, "AIDING_POS_ECEF", "" }, - { 34, "AIDING_POS_LLH", "" }, - { 35, "AIDING_HEIGHT_ABOVE_ELLIPSOID", "" }, - { 40, "AIDING_VEL_ECEF", "" }, - { 41, "AIDING_VEL_NED", "" }, - { 42, "AIDING_VEL_BODY_FRAME", "" }, - { 49, "AIDING_HEADING_TRUE", "" }, - { 50, "AIDING_MAGNETIC_FIELD", "" }, - { 51, "AIDING_PRESSURE", "" }, + { uint32_t(1), "GNSS", "" }, + { uint32_t(2), "DUAL_ANTENNA", "" }, + { uint32_t(3), "HEADING", "" }, + { uint32_t(4), "PRESSURE", "" }, + { uint32_t(5), "MAGNETOMETER", "" }, + { uint32_t(6), "SPEED", "" }, + { uint32_t(33), "AIDING_POS_ECEF", "" }, + { uint32_t(34), "AIDING_POS_LLH", "" }, + { uint32_t(35), "AIDING_HEIGHT_ABOVE_ELLIPSOID", "" }, + { uint32_t(40), "AIDING_VEL_ECEF", "" }, + { uint32_t(41), "AIDING_VEL_NED", "" }, + { uint32_t(42), "AIDING_VEL_BODY_FRAME", "" }, + { uint32_t(49), "AIDING_HEADING_TRUE", "" }, + { uint32_t(50), "AIDING_MAGNETIC_FIELD", "" }, + { uint32_t(51), "AIDING_PRESSURE", "" }, }; static constexpr inline EnumInfo value = { @@ -2457,12 +2457,12 @@ struct MetadataFor using type = data_filter::FilterMeasurementIndicator; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "enabled", "" }, - { 2, "used", "" }, - { 4, "residual_high_warning", "" }, - { 8, "sample_time_warning", "" }, - { 16, "configuration_error", "" }, - { 32, "max_num_meas_exceeded", "" }, + { uint32_t(1), "enabled", "" }, + { uint32_t(2), "used", "" }, + { uint32_t(4), "residual_high_warning", "" }, + { uint32_t(8), "sample_time_warning", "" }, + { uint32_t(16), "configuration_error", "" }, + { uint32_t(32), "max_num_meas_exceeded", "" }, }; static constexpr inline BitfieldInfo value = { @@ -2485,7 +2485,7 @@ struct MetadataFor /* .docs = */ "[seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2494,7 +2494,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2503,16 +2503,16 @@ struct MetadataFor /* .docs = */ "(see product manual for supported types) Note: values 0x20 and above correspond to commanded aiding measurements in the 0x13 Aiding command set.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "indicator", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2541,7 +2541,7 @@ struct MetadataFor /* .docs = */ "[dimensionless]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2550,7 +2550,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2579,7 +2579,7 @@ struct MetadataFor /* .docs = */ "[dimensionless]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2588,7 +2588,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2612,9 +2612,9 @@ struct MetadataFor using type = data_filter::GnssDualAntennaStatus::FixType; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "FIX_NONE", "" }, - { 1, "FIX_DA_FLOAT", "" }, - { 2, "FIX_DA_FIXED", "" }, + { uint32_t(0), "FIX_NONE", "" }, + { uint32_t(1), "FIX_DA_FLOAT", "" }, + { uint32_t(2), "FIX_DA_FIXED", "" }, }; static constexpr inline EnumInfo value = { @@ -2632,9 +2632,9 @@ struct MetadataFor using type = data_filter::GnssDualAntennaStatus::DualAntennaStatusFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "rcv_1_data_valid", "" }, - { 2, "rcv_2_data_valid", "" }, - { 4, "antenna_offsets_valid", "" }, + { uint32_t(1), "rcv_1_data_valid", "" }, + { uint32_t(2), "rcv_2_data_valid", "" }, + { uint32_t(4), "antenna_offsets_valid", "" }, }; static constexpr inline BitfieldInfo value = { @@ -2657,7 +2657,7 @@ struct MetadataFor /* .docs = */ "Last dual-antenna GNSS aiding measurement time of week [seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2666,7 +2666,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2675,7 +2675,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2684,16 +2684,16 @@ struct MetadataFor /* .docs = */ "Fix type indicator", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "status_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2702,7 +2702,7 @@ struct MetadataFor /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2731,7 +2731,7 @@ struct MetadataFor /* .docs = */ "Frame ID for the receiver to which the antenna is attached", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2740,7 +2740,7 @@ struct MetadataFor /* .docs = */ "Translation config X, Y, and Z (m).", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2749,7 +2749,7 @@ struct MetadataFor /* .docs = */ "Attitude quaternion", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2778,7 +2778,7 @@ struct MetadataFor /* .docs = */ "Frame ID for the receiver to which the antenna is attached", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2787,7 +2787,7 @@ struct MetadataFor /* .docs = */ "Translation uncertaint X, Y, and Z (m).", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2796,7 +2796,7 @@ struct MetadataFor /* .docs = */ "Attitude uncertainty, X, Y, and Z (radians).", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2815,7 +2815,7 @@ struct MetadataFor }; -static constexpr inline std::initializer_list ALL_DATA_FILTER = { +static constexpr inline std::initializer_list DATA_FILTER = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/data_gnss.hpp b/src/cpp/mip/metadata/definitions/data_gnss.hpp index 87612e9e4..173087f18 100644 --- a/src/cpp/mip/metadata/definitions/data_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/data_gnss.hpp @@ -16,12 +16,12 @@ struct MetadataFor using type = data_gnss::PosLlh::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "lat_lon", "" }, - { 2, "ellipsoid_height", "" }, - { 4, "msl_height", "" }, - { 8, "horizontal_accuracy", "" }, - { 16, "vertical_accuracy", "" }, - { 31, "flags", "" }, + { uint32_t(1), "lat_lon", "" }, + { uint32_t(2), "ellipsoid_height", "" }, + { uint32_t(4), "msl_height", "" }, + { uint32_t(8), "horizontal_accuracy", "" }, + { uint32_t(16), "vertical_accuracy", "" }, + { uint32_t(31), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -44,7 +44,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -53,7 +53,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -62,7 +62,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -71,7 +71,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -80,7 +80,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -89,16 +89,16 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -122,9 +122,9 @@ struct MetadataFor using type = data_gnss::PosEcef::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "position", "" }, - { 2, "position_accuracy", "" }, - { 3, "flags", "" }, + { uint32_t(1), "position", "" }, + { uint32_t(2), "position_accuracy", "" }, + { uint32_t(3), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -147,7 +147,7 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -156,16 +156,16 @@ struct MetadataFor /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -189,13 +189,13 @@ struct MetadataFor using type = data_gnss::VelNed::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "velocity", "" }, - { 2, "speed_3d", "" }, - { 4, "ground_speed", "" }, - { 8, "heading", "" }, - { 16, "speed_accuracy", "" }, - { 32, "heading_accuracy", "" }, - { 63, "flags", "" }, + { uint32_t(1), "velocity", "" }, + { uint32_t(2), "speed_3d", "" }, + { uint32_t(4), "ground_speed", "" }, + { uint32_t(8), "heading", "" }, + { uint32_t(16), "speed_accuracy", "" }, + { uint32_t(32), "heading_accuracy", "" }, + { uint32_t(63), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -218,7 +218,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -227,7 +227,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -236,7 +236,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -245,7 +245,7 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -254,7 +254,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -263,16 +263,16 @@ struct MetadataFor /* .docs = */ "[degrees]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -296,9 +296,9 @@ struct MetadataFor using type = data_gnss::VelEcef::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "velocity", "" }, - { 2, "velocity_accuracy", "" }, - { 3, "flags", "" }, + { uint32_t(1), "velocity", "" }, + { uint32_t(2), "velocity_accuracy", "" }, + { uint32_t(3), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -321,7 +321,7 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -330,16 +330,16 @@ struct MetadataFor /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -363,14 +363,14 @@ struct MetadataFor using type = data_gnss::Dop::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "gdop", "" }, - { 2, "pdop", "" }, - { 4, "hdop", "" }, - { 8, "vdop", "" }, - { 16, "tdop", "" }, - { 32, "ndop", "" }, - { 64, "edop", "" }, - { 127, "flags", "" }, + { uint32_t(1), "gdop", "" }, + { uint32_t(2), "pdop", "" }, + { uint32_t(4), "hdop", "" }, + { uint32_t(8), "vdop", "" }, + { uint32_t(16), "tdop", "" }, + { uint32_t(32), "ndop", "" }, + { uint32_t(64), "edop", "" }, + { uint32_t(127), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -393,7 +393,7 @@ struct MetadataFor /* .docs = */ "Geometric DOP", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -402,7 +402,7 @@ struct MetadataFor /* .docs = */ "Position DOP", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -411,7 +411,7 @@ struct MetadataFor /* .docs = */ "Horizontal DOP", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -420,7 +420,7 @@ struct MetadataFor /* .docs = */ "Vertical DOP", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -429,7 +429,7 @@ struct MetadataFor /* .docs = */ "Time DOP", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -438,7 +438,7 @@ struct MetadataFor /* .docs = */ "Northing DOP", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -447,16 +447,16 @@ struct MetadataFor /* .docs = */ "Easting DOP", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -480,9 +480,9 @@ struct MetadataFor using type = data_gnss::UtcTime::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "gnss_date_time", "" }, - { 2, "leap_seconds_known", "" }, - { 3, "flags", "" }, + { uint32_t(1), "gnss_date_time", "" }, + { uint32_t(2), "leap_seconds_known", "" }, + { uint32_t(3), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -505,7 +505,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -514,7 +514,7 @@ struct MetadataFor /* .docs = */ "Month (1-12)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -523,7 +523,7 @@ struct MetadataFor /* .docs = */ "Day (1-31)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -532,7 +532,7 @@ struct MetadataFor /* .docs = */ "Hour (0-23)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -541,7 +541,7 @@ struct MetadataFor /* .docs = */ "Minute (0-59)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -550,7 +550,7 @@ struct MetadataFor /* .docs = */ "Second (0-59)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -559,16 +559,16 @@ struct MetadataFor /* .docs = */ "Millisecond(0-999)", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -592,9 +592,9 @@ struct MetadataFor using type = data_gnss::GpsTime::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tow", "" }, - { 2, "week_number", "" }, - { 3, "flags", "" }, + { uint32_t(1), "tow", "" }, + { uint32_t(2), "week_number", "" }, + { uint32_t(3), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -617,7 +617,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -626,16 +626,16 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -659,10 +659,10 @@ struct MetadataFor using type = data_gnss::ClockInfo::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "bias", "" }, - { 2, "drift", "" }, - { 4, "accuracy_estimate", "" }, - { 7, "flags", "" }, + { uint32_t(1), "bias", "" }, + { uint32_t(2), "drift", "" }, + { uint32_t(4), "accuracy_estimate", "" }, + { uint32_t(7), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -685,7 +685,7 @@ struct MetadataFor /* .docs = */ "[seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -694,7 +694,7 @@ struct MetadataFor /* .docs = */ "[seconds/second]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -703,16 +703,16 @@ struct MetadataFor /* .docs = */ "[seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -736,14 +736,14 @@ struct MetadataFor using type = data_gnss::FixInfo::FixType; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "FIX_3D", "" }, - { 1, "FIX_2D", "" }, - { 2, "FIX_TIME_ONLY", "" }, - { 3, "FIX_NONE", "" }, - { 4, "FIX_INVALID", "" }, - { 5, "FIX_RTK_FLOAT", "" }, - { 6, "FIX_RTK_FIXED", "" }, - { 7, "FIX_DIFFERENTIAL", "" }, + { uint32_t(0), "FIX_3D", "" }, + { uint32_t(1), "FIX_2D", "" }, + { uint32_t(2), "FIX_TIME_ONLY", "" }, + { uint32_t(3), "FIX_NONE", "" }, + { uint32_t(4), "FIX_INVALID", "" }, + { uint32_t(5), "FIX_RTK_FLOAT", "" }, + { uint32_t(6), "FIX_RTK_FIXED", "" }, + { uint32_t(7), "FIX_DIFFERENTIAL", "" }, }; static constexpr inline EnumInfo value = { @@ -761,8 +761,8 @@ struct MetadataFor using type = data_gnss::FixInfo::FixFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "sbas_used", "" }, - { 2, "dgnss_used", "" }, + { uint32_t(1), "sbas_used", "" }, + { uint32_t(2), "dgnss_used", "" }, }; static constexpr inline BitfieldInfo value = { @@ -780,10 +780,10 @@ struct MetadataFor using type = data_gnss::FixInfo::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "fix_type", "" }, - { 2, "num_sv", "" }, - { 4, "fix_flags", "" }, - { 7, "flags", "" }, + { uint32_t(1), "fix_type", "" }, + { uint32_t(2), "num_sv", "" }, + { uint32_t(4), "fix_flags", "" }, + { uint32_t(7), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -806,7 +806,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -815,25 +815,25 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "fix_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -857,8 +857,8 @@ struct MetadataFor using type = data_gnss::SvInfo::SVFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "used_for_navigation", "" }, - { 2, "healthy", "" }, + { uint32_t(1), "used_for_navigation", "" }, + { uint32_t(2), "healthy", "" }, }; static constexpr inline BitfieldInfo value = { @@ -876,13 +876,13 @@ struct MetadataFor using type = data_gnss::SvInfo::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "channel", "" }, - { 2, "sv_id", "" }, - { 4, "carrier_noise_ratio", "" }, - { 8, "azimuth", "" }, - { 16, "elevation", "" }, - { 32, "sv_flags", "" }, - { 63, "flags", "" }, + { uint32_t(1), "channel", "" }, + { uint32_t(2), "sv_id", "" }, + { uint32_t(4), "carrier_noise_ratio", "" }, + { uint32_t(8), "azimuth", "" }, + { uint32_t(16), "elevation", "" }, + { uint32_t(32), "sv_flags", "" }, + { uint32_t(63), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -905,7 +905,7 @@ struct MetadataFor /* .docs = */ "Receiver channel number", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -914,7 +914,7 @@ struct MetadataFor /* .docs = */ "GNSS Satellite ID", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -923,7 +923,7 @@ struct MetadataFor /* .docs = */ "[dBHz]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -932,7 +932,7 @@ struct MetadataFor /* .docs = */ "[deg]", /* .type = */ {Type::S16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -941,25 +941,25 @@ struct MetadataFor /* .docs = */ "[deg]", /* .type = */ {Type::S16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "sv_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -983,9 +983,9 @@ struct MetadataFor using type = data_gnss::HwStatus::ReceiverState; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "OFF", "" }, - { 1, "ON", "" }, - { 2, "UNKNOWN", "" }, + { uint32_t(0), "OFF", "" }, + { uint32_t(1), "ON", "" }, + { uint32_t(2), "UNKNOWN", "" }, }; static constexpr inline EnumInfo value = { @@ -1003,11 +1003,11 @@ struct MetadataFor using type = data_gnss::HwStatus::AntennaState; static constexpr inline EnumInfo::Entry entries[] = { - { 1, "INIT", "" }, - { 2, "SHORT", "" }, - { 3, "OPEN", "" }, - { 4, "GOOD", "" }, - { 5, "UNKNOWN", "" }, + { uint32_t(1), "INIT", "" }, + { uint32_t(2), "SHORT", "" }, + { uint32_t(3), "OPEN", "" }, + { uint32_t(4), "GOOD", "" }, + { uint32_t(5), "UNKNOWN", "" }, }; static constexpr inline EnumInfo value = { @@ -1025,9 +1025,9 @@ struct MetadataFor using type = data_gnss::HwStatus::AntennaPower; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "OFF", "" }, - { 1, "ON", "" }, - { 2, "UNKNOWN", "" }, + { uint32_t(0), "OFF", "" }, + { uint32_t(1), "ON", "" }, + { uint32_t(2), "UNKNOWN", "" }, }; static constexpr inline EnumInfo value = { @@ -1045,10 +1045,10 @@ struct MetadataFor using type = data_gnss::HwStatus::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "sensor_state", "" }, - { 2, "antenna_state", "" }, - { 4, "antenna_power", "" }, - { 7, "flags", "" }, + { uint32_t(1), "sensor_state", "" }, + { uint32_t(2), "antenna_state", "" }, + { uint32_t(4), "antenna_power", "" }, + { uint32_t(7), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1071,7 +1071,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1080,7 +1080,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1089,16 +1089,16 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1122,11 +1122,11 @@ struct MetadataFor using type = data_gnss::DgpsInfo::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "age", "" }, - { 2, "base_station_id", "" }, - { 4, "base_station_status", "" }, - { 8, "num_channels", "" }, - { 15, "flags", "" }, + { uint32_t(1), "age", "" }, + { uint32_t(2), "base_station_id", "" }, + { uint32_t(4), "base_station_status", "" }, + { uint32_t(8), "num_channels", "" }, + { uint32_t(15), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1149,7 +1149,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1158,7 +1158,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1167,7 +1167,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1176,16 +1176,16 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1209,11 +1209,11 @@ struct MetadataFor using type = data_gnss::DgpsChannel::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "id", "" }, - { 2, "age", "" }, - { 4, "range_correction", "" }, - { 8, "range_rate_correction", "" }, - { 15, "flags", "" }, + { uint32_t(1), "id", "" }, + { uint32_t(2), "age", "" }, + { uint32_t(4), "range_correction", "" }, + { uint32_t(8), "range_rate_correction", "" }, + { uint32_t(15), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1236,7 +1236,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1245,7 +1245,7 @@ struct MetadataFor /* .docs = */ "[s]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1254,7 +1254,7 @@ struct MetadataFor /* .docs = */ "[m]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1263,16 +1263,16 @@ struct MetadataFor /* .docs = */ "[m/s]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1296,11 +1296,11 @@ struct MetadataFor using type = data_gnss::ClockInfo2::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "bias", "" }, - { 2, "drift", "" }, - { 4, "bias_accuracy", "" }, - { 8, "drift_accuracy", "" }, - { 15, "flags", "" }, + { uint32_t(1), "bias", "" }, + { uint32_t(2), "drift", "" }, + { uint32_t(4), "bias_accuracy", "" }, + { uint32_t(8), "drift_accuracy", "" }, + { uint32_t(15), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1323,7 +1323,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1332,7 +1332,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1341,7 +1341,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1350,16 +1350,16 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1383,7 +1383,7 @@ struct MetadataFor using type = data_gnss::GpsLeapSeconds::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 2, "leap_seconds", "" }, + { uint32_t(2), "leap_seconds", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1406,16 +1406,16 @@ struct MetadataFor /* .docs = */ "[s]", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1439,11 +1439,11 @@ struct MetadataFor using type = data_gnss::SbasSystem; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "UNKNOWN", "" }, - { 1, "WAAS", "" }, - { 2, "EGNOS", "" }, - { 3, "MSAS", "" }, - { 4, "GAGAN", "" }, + { uint32_t(0), "UNKNOWN", "" }, + { uint32_t(1), "WAAS", "" }, + { uint32_t(2), "EGNOS", "" }, + { uint32_t(3), "MSAS", "" }, + { uint32_t(4), "GAGAN", "" }, }; static constexpr inline EnumInfo value = { @@ -1461,10 +1461,10 @@ struct MetadataFor using type = data_gnss::SbasInfo::SbasStatus; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "range_available", "" }, - { 2, "corrections_available", "" }, - { 4, "integrity_available", "" }, - { 8, "test_mode", "" }, + { uint32_t(1), "range_available", "" }, + { uint32_t(2), "corrections_available", "" }, + { uint32_t(4), "integrity_available", "" }, + { uint32_t(8), "test_mode", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1482,13 +1482,13 @@ struct MetadataFor using type = data_gnss::SbasInfo::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tow", "" }, - { 2, "week_number", "" }, - { 4, "sbas_system", "" }, - { 8, "sbas_id", "" }, - { 16, "count", "" }, - { 32, "sbas_status", "" }, - { 63, "flags", "" }, + { uint32_t(1), "tow", "" }, + { uint32_t(2), "week_number", "" }, + { uint32_t(4), "sbas_system", "" }, + { uint32_t(8), "sbas_id", "" }, + { uint32_t(16), "count", "" }, + { uint32_t(32), "sbas_status", "" }, + { uint32_t(63), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1511,7 +1511,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1520,7 +1520,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1529,7 +1529,7 @@ struct MetadataFor /* .docs = */ "SBAS system id", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1538,7 +1538,7 @@ struct MetadataFor /* .docs = */ "SBAS satellite id.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1547,25 +1547,25 @@ struct MetadataFor /* .docs = */ "Number of SBAS corrections", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "sbas_status", /* .docs = */ "Status of the SBAS service", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1589,12 +1589,12 @@ struct MetadataFor using type = data_gnss::GnssConstellationId; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "UNKNOWN", "" }, - { 1, "GPS", "" }, - { 2, "GLONASS", "" }, - { 3, "GALILEO", "" }, - { 4, "BEIDOU", "" }, - { 5, "SBAS", "" }, + { uint32_t(0), "UNKNOWN", "" }, + { uint32_t(1), "GPS", "" }, + { uint32_t(2), "GLONASS", "" }, + { uint32_t(3), "GALILEO", "" }, + { uint32_t(4), "BEIDOU", "" }, + { uint32_t(5), "SBAS", "" }, }; static constexpr inline EnumInfo value = { @@ -1612,10 +1612,10 @@ struct MetadataFor using type = data_gnss::SbasCorrection::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "udrei", "" }, - { 2, "pseudorange_correction", "" }, - { 4, "iono_correction", "" }, - { 7, "flags", "" }, + { uint32_t(1), "udrei", "" }, + { uint32_t(2), "pseudorange_correction", "" }, + { uint32_t(4), "iono_correction", "" }, + { uint32_t(7), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1638,7 +1638,7 @@ struct MetadataFor /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1647,7 +1647,7 @@ struct MetadataFor /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1656,7 +1656,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week the message was received [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1665,7 +1665,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1674,7 +1674,7 @@ struct MetadataFor /* .docs = */ "GNSS constellation id", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1683,7 +1683,7 @@ struct MetadataFor /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1692,7 +1692,7 @@ struct MetadataFor /* .docs = */ "[See above 0-13 usable, 14 not monitored, 15 - do not use]", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1701,7 +1701,7 @@ struct MetadataFor /* .docs = */ "Pseudo-range correction [meters].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1710,16 +1710,16 @@ struct MetadataFor /* .docs = */ "Ionospheric correction [meters].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1743,10 +1743,10 @@ struct MetadataFor using type = data_gnss::RfErrorDetection::RFBand; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "UNKNOWN", "" }, - { 1, "L1", "" }, - { 2, "L2", "" }, - { 5, "L5", "" }, + { uint32_t(0), "UNKNOWN", "" }, + { uint32_t(1), "L1", "" }, + { uint32_t(2), "L2", "" }, + { uint32_t(5), "L5", "" }, }; static constexpr inline EnumInfo value = { @@ -1764,10 +1764,10 @@ struct MetadataFor using type = data_gnss::RfErrorDetection::JammingState; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "UNKNOWN", "" }, - { 1, "NONE", "" }, - { 2, "PARTIAL", "" }, - { 3, "SIGNIFICANT", "" }, + { uint32_t(0), "UNKNOWN", "" }, + { uint32_t(1), "NONE", "" }, + { uint32_t(2), "PARTIAL", "" }, + { uint32_t(3), "SIGNIFICANT", "" }, }; static constexpr inline EnumInfo value = { @@ -1785,10 +1785,10 @@ struct MetadataFor using type = data_gnss::RfErrorDetection::SpoofingState; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "UNKNOWN", "" }, - { 1, "NONE", "" }, - { 2, "PARTIAL", "" }, - { 3, "SIGNIFICANT", "" }, + { uint32_t(0), "UNKNOWN", "" }, + { uint32_t(1), "NONE", "" }, + { uint32_t(2), "PARTIAL", "" }, + { uint32_t(3), "SIGNIFICANT", "" }, }; static constexpr inline EnumInfo value = { @@ -1806,10 +1806,10 @@ struct MetadataFor using type = data_gnss::RfErrorDetection::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "rf_band", "" }, - { 2, "jamming_state", "" }, - { 4, "spoofing_state", "" }, - { 7, "flags", "" }, + { uint32_t(1), "rf_band", "" }, + { uint32_t(2), "jamming_state", "" }, + { uint32_t(4), "spoofing_state", "" }, + { uint32_t(7), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1832,7 +1832,7 @@ struct MetadataFor /* .docs = */ "RF Band of the reported information", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1841,7 +1841,7 @@ struct MetadataFor /* .docs = */ "GNSS Jamming State (as reported by the GNSS module)", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1850,7 +1850,7 @@ struct MetadataFor /* .docs = */ "GNSS Spoofing State (as reported by the GNSS module)", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1859,16 +1859,16 @@ struct MetadataFor /* .docs = */ "Reserved for future use", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1892,15 +1892,15 @@ struct MetadataFor using type = data_gnss::BaseStationInfo::IndicatorFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "gps", "" }, - { 2, "glonass", "" }, - { 4, "galileo", "" }, - { 8, "beidou", "" }, - { 16, "ref_station", "" }, - { 32, "single_receiver", "" }, - { 64, "quarter_cycle_bit1", "" }, - { 128, "quarter_cycle_bit2", "" }, - { 192, "quarter_cycle_bits", "" }, + { uint32_t(1), "gps", "" }, + { uint32_t(2), "glonass", "" }, + { uint32_t(4), "galileo", "" }, + { uint32_t(8), "beidou", "" }, + { uint32_t(16), "ref_station", "" }, + { uint32_t(32), "single_receiver", "" }, + { uint32_t(64), "quarter_cycle_bit1", "" }, + { uint32_t(128), "quarter_cycle_bit2", "" }, + { uint32_t(192), "quarter_cycle_bits", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1918,13 +1918,13 @@ struct MetadataFor using type = data_gnss::BaseStationInfo::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tow", "" }, - { 2, "week_number", "" }, - { 4, "ecef_position", "" }, - { 8, "height", "" }, - { 16, "station_id", "" }, - { 32, "indicators", "" }, - { 63, "flags", "" }, + { uint32_t(1), "tow", "" }, + { uint32_t(2), "week_number", "" }, + { uint32_t(4), "ecef_position", "" }, + { uint32_t(8), "height", "" }, + { uint32_t(16), "station_id", "" }, + { uint32_t(32), "indicators", "" }, + { uint32_t(63), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -1947,7 +1947,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week the message was received [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1956,7 +1956,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1965,7 +1965,7 @@ struct MetadataFor /* .docs = */ "Earth-centered, Earth-fixed [m]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1974,7 +1974,7 @@ struct MetadataFor /* .docs = */ "Antenna Height above the marker used in the survey [m]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -1983,25 +1983,25 @@ struct MetadataFor /* .docs = */ "Range: 0-4095", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "indicators", /* .docs = */ "Bitfield", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2025,15 +2025,15 @@ struct MetadataFor using type = data_gnss::RtkCorrectionsStatus::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tow", "" }, - { 2, "week_number", "" }, - { 4, "epoch_status", "" }, - { 8, "dongle_status", "" }, - { 16, "gps_latency", "" }, - { 32, "glonass_latency", "" }, - { 64, "galileo_latency", "" }, - { 128, "beidou_latency", "" }, - { 255, "flags", "" }, + { uint32_t(1), "tow", "" }, + { uint32_t(2), "week_number", "" }, + { uint32_t(4), "epoch_status", "" }, + { uint32_t(8), "dongle_status", "" }, + { uint32_t(16), "gps_latency", "" }, + { uint32_t(32), "glonass_latency", "" }, + { uint32_t(64), "galileo_latency", "" }, + { uint32_t(128), "beidou_latency", "" }, + { uint32_t(255), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -2051,15 +2051,15 @@ struct MetadataFor using type = data_gnss::RtkCorrectionsStatus::EpochStatus; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "antenna_location_received", "" }, - { 2, "antenna_description_received", "" }, - { 4, "gps_received", "" }, - { 8, "glonass_received", "" }, - { 16, "galileo_received", "" }, - { 32, "beidou_received", "" }, - { 64, "using_gps_msm_messages", "Using MSM messages for GPS corrections instead of RTCM messages 1001-1004" }, - { 128, "using_glonass_msm_messages", "Using MSM messages for GLONASS corrections instead of RTCM messages 1009-1012" }, - { 256, "dongle_status_read_failed", "A read of the dongle status was attempted, but failed" }, + { uint32_t(1), "antenna_location_received", "" }, + { uint32_t(2), "antenna_description_received", "" }, + { uint32_t(4), "gps_received", "" }, + { uint32_t(8), "glonass_received", "" }, + { uint32_t(16), "galileo_received", "" }, + { uint32_t(32), "beidou_received", "" }, + { uint32_t(64), "using_gps_msm_messages", "Using MSM messages for GPS corrections instead of RTCM messages 1001-1004" }, + { uint32_t(128), "using_glonass_msm_messages", "Using MSM messages for GLONASS corrections instead of RTCM messages 1009-1012" }, + { uint32_t(256), "dongle_status_read_failed", "A read of the dongle status was attempted, but failed" }, }; static constexpr inline BitfieldInfo value = { @@ -2082,7 +2082,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2091,16 +2091,16 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "epoch_status", /* .docs = */ "Status of the corrections received during this epoch", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2109,7 +2109,7 @@ struct MetadataFor /* .docs = */ "RTK Dongle Status Flags (valid only when using RTK dongle, see Get RTK Device Status Flags (0x0F,0x01) for details)", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2118,7 +2118,7 @@ struct MetadataFor /* .docs = */ "Latency of last GPS correction [seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2127,7 +2127,7 @@ struct MetadataFor /* .docs = */ "Latency of last GLONASS correction [seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2136,7 +2136,7 @@ struct MetadataFor /* .docs = */ "Latency of last Galileo correction [seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2145,7 +2145,7 @@ struct MetadataFor /* .docs = */ "Latency of last Beidou correction [seconds]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2154,16 +2154,16 @@ struct MetadataFor /* .docs = */ "Reserved for future use", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2187,14 +2187,14 @@ struct MetadataFor using type = data_gnss::SatelliteStatus::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tow", "" }, - { 2, "week_number", "" }, - { 4, "gnss_id", "" }, - { 8, "satellite_id", "" }, - { 16, "elevation", "" }, - { 32, "azimuth", "" }, - { 64, "health", "" }, - { 127, "flags", "" }, + { uint32_t(1), "tow", "" }, + { uint32_t(2), "week_number", "" }, + { uint32_t(4), "gnss_id", "" }, + { uint32_t(8), "satellite_id", "" }, + { uint32_t(16), "elevation", "" }, + { uint32_t(32), "azimuth", "" }, + { uint32_t(64), "health", "" }, + { uint32_t(127), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -2217,7 +2217,7 @@ struct MetadataFor /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2226,7 +2226,7 @@ struct MetadataFor /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2235,7 +2235,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2244,7 +2244,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2253,7 +2253,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2262,7 +2262,7 @@ struct MetadataFor /* .docs = */ "GNSS satellite id within the constellation", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2271,7 +2271,7 @@ struct MetadataFor /* .docs = */ "Elevation of the satellite relative to the rover [degrees]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2280,7 +2280,7 @@ struct MetadataFor /* .docs = */ "Azimuth of the satellite relative to the rover [degrees]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2289,16 +2289,16 @@ struct MetadataFor /* .docs = */ "True if the satellite is healthy.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2322,71 +2322,72 @@ struct MetadataFor using type = data_gnss::GnssSignalId; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "UNKNOWN", "" }, - { 1, "GPS_L1CA", "" }, - { 2, "GPS_L1P", "" }, - { 3, "GPS_L1Z", "" }, - { 4, "GPS_L2CA", "" }, - { 5, "GPS_L2P", "" }, - { 6, "GPS_L2Z", "" }, - { 7, "GPS_L2CL", "" }, - { 8, "GPS_L2CM", "" }, - { 9, "GPS_L2CML", "" }, - { 10, "GPS_L5I", "" }, - { 11, "GPS_L5Q", "" }, - { 12, "GPS_L5IQ", "" }, - { 13, "GPS_L1CD", "" }, - { 14, "GPS_L1CP", "" }, - { 15, "GPS_L1CDP", "" }, - { 32, "GLONASS_G1CA", "" }, - { 33, "GLONASS_G1P", "" }, - { 34, "GLONASS_G2C", "" }, - { 35, "GLONASS_G2P", "" }, - { 64, "GALILEO_E1C", "" }, - { 65, "GALILEO_E1A", "" }, - { 66, "GALILEO_E1B", "" }, - { 67, "GALILEO_E1BC", "" }, - { 68, "GALILEO_E1ABC", "" }, - { 69, "GALILEO_E6C", "" }, - { 70, "GALILEO_E6A", "" }, - { 71, "GALILEO_E6B", "" }, - { 72, "GALILEO_E6BC", "" }, - { 73, "GALILEO_E6ABC", "" }, - { 74, "GALILEO_E5BI", "" }, - { 75, "GALILEO_E5BQ", "" }, - { 76, "GALILEO_E5BIQ", "" }, - { 77, "GALILEO_E5ABI", "" }, - { 78, "GALILEO_E5ABQ", "" }, - { 79, "GALILEO_E5ABIQ", "" }, - { 80, "GALILEO_E5AI", "" }, - { 81, "GALILEO_E5AQ", "" }, - { 82, "GALILEO_E5AIQ", "" }, - { 96, "SBAS_L1CA", "" }, - { 97, "SBAS_L5I", "" }, - { 98, "SBAS_L5Q", "" }, - { 99, "SBAS_L5IQ", "" }, - { 128, "QZSS_L1CA", "" }, - { 129, "QZSS_LEXS", "" }, - { 130, "QZSS_LEXL", "" }, - { 131, "QZSS_LEXSL", "" }, - { 132, "QZSS_L2CM", "" }, - { 133, "QZSS_L2CL", "" }, - { 134, "QZSS_L2CML", "" }, - { 135, "QZSS_L5I", "" }, - { 136, "QZSS_L5Q", "" }, - { 137, "QZSS_L5IQ", "" }, - { 138, "QZSS_L1CD", "" }, - { 139, "QZSS_L1CP", "" }, - { 140, "QZSS_L1CDP", "" }, - { 160, "BEIDOU_B1I", "" }, - { 161, "BEIDOU_B1Q", "" }, - { 162, "BEIDOU_B1IQ", "" }, - { 163, "BEIDOU_B3I", "" }, - { 164, "BEIDOU_B3Q", "" }, - { 165, "BEIDOU_B3IQ", "" }, - { 166, "BEIDOU_B2I", "" }, - { 167, "BEIDOU_B2Q", "" }, - { 168, "BEIDOU_B2IQ", "" }, + { uint32_t(0), "UNKNOWN", "" }, + { uint32_t(1), "GPS_L1CA", "" }, + { uint32_t(2), "GPS_L1P", "" }, + { uint32_t(3), "GPS_L1Z", "" }, + { uint32_t(4), "GPS_L2CA", "" }, + { uint32_t(5), "GPS_L2P", "" }, + { uint32_t(6), "GPS_L2Z", "" }, + { uint32_t(7), "GPS_L2CL", "" }, + { uint32_t(8), "GPS_L2CM", "" }, + { uint32_t(9), "GPS_L2CML", "" }, + { uint32_t(10), "GPS_L5I", "" }, + { uint32_t(11), "GPS_L5Q", "" }, + { uint32_t(12), "GPS_L5IQ", "" }, + { uint32_t(13), "GPS_L1CD", "" }, + { uint32_t(14), "GPS_L1CP", "" }, + { uint32_t(15), "GPS_L1CDP", "" }, + { uint32_t(32), "GLONASS_G1CA", "" }, + { uint32_t(33), "GLONASS_G1P", "" }, + { uint32_t(34), "GLONASS_G2C", "" }, + { uint32_t(35), "GLONASS_G2P", "" }, + { uint32_t(64), "GALILEO_E1C", "" }, + { uint32_t(65), "GALILEO_E1A", "" }, + { uint32_t(66), "GALILEO_E1B", "" }, + { uint32_t(67), "GALILEO_E1BC", "" }, + { uint32_t(68), "GALILEO_E1ABC", "" }, + { uint32_t(69), "GALILEO_E6C", "" }, + { uint32_t(70), "GALILEO_E6A", "" }, + { uint32_t(71), "GALILEO_E6B", "" }, + { uint32_t(72), "GALILEO_E6BC", "" }, + { uint32_t(73), "GALILEO_E6ABC", "" }, + { uint32_t(74), "GALILEO_E5BI", "" }, + { uint32_t(75), "GALILEO_E5BQ", "" }, + { uint32_t(76), "GALILEO_E5BIQ", "" }, + { uint32_t(77), "GALILEO_E5ABI", "" }, + { uint32_t(78), "GALILEO_E5ABQ", "" }, + { uint32_t(79), "GALILEO_E5ABIQ", "" }, + { uint32_t(80), "GALILEO_E5AI", "" }, + { uint32_t(81), "GALILEO_E5AQ", "" }, + { uint32_t(82), "GALILEO_E5AIQ", "" }, + { uint32_t(96), "SBAS_L1CA", "" }, + { uint32_t(97), "SBAS_L5I", "" }, + { uint32_t(98), "SBAS_L5Q", "" }, + { uint32_t(99), "SBAS_L5IQ", "" }, + { uint32_t(128), "QZSS_L1CA", "" }, + { uint32_t(129), "QZSS_LEXS", "" }, + { uint32_t(130), "QZSS_LEXL", "" }, + { uint32_t(131), "QZSS_LEXSL", "" }, + { uint32_t(132), "QZSS_L2CM", "" }, + { uint32_t(133), "QZSS_L2CL", "" }, + { uint32_t(134), "QZSS_L2CML", "" }, + { uint32_t(135), "QZSS_L5I", "" }, + { uint32_t(136), "QZSS_L5Q", "" }, + { uint32_t(137), "QZSS_L5IQ", "" }, + { uint32_t(138), "QZSS_L1CD", "" }, + { uint32_t(139), "QZSS_L1CP", "" }, + { uint32_t(140), "QZSS_L1CDP", "" }, + { uint32_t(160), "BEIDOU_B1I", "" }, + { uint32_t(161), "BEIDOU_B1Q", "" }, + { uint32_t(162), "BEIDOU_B1IQ", "" }, + { uint32_t(163), "BEIDOU_B3I", "" }, + { uint32_t(164), "BEIDOU_B3Q", "" }, + { uint32_t(165), "BEIDOU_B3IQ", "" }, + { uint32_t(166), "BEIDOU_B2I", "" }, + { uint32_t(167), "BEIDOU_B2Q", "" }, + { uint32_t(168), "BEIDOU_B2IQ", "" }, + { uint32_t(169), "BEIDOU_B2A", "" }, }; static constexpr inline EnumInfo value = { @@ -2404,12 +2405,12 @@ struct MetadataFor using type = data_gnss::Raw::GnssSignalQuality; static constexpr inline EnumInfo::Entry entries[] = { - { 0, "NONE", "" }, - { 1, "SEARCHING", "" }, - { 2, "ACQUIRED", "" }, - { 3, "UNUSABLE", "" }, - { 4, "TIME_LOCKED", "" }, - { 5, "FULLY_LOCKED", "" }, + { uint32_t(0), "NONE", "" }, + { uint32_t(1), "SEARCHING", "" }, + { uint32_t(2), "ACQUIRED", "" }, + { uint32_t(3), "UNUSABLE", "" }, + { uint32_t(4), "TIME_LOCKED", "" }, + { uint32_t(5), "FULLY_LOCKED", "" }, }; static constexpr inline EnumInfo value = { @@ -2427,23 +2428,23 @@ struct MetadataFor using type = data_gnss::Raw::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tow", "" }, - { 2, "week_number", "" }, - { 4, "receiver_id", "" }, - { 8, "tracking_channel", "" }, - { 16, "gnss_id", "" }, - { 32, "satellite_id", "" }, - { 64, "signal_id", "" }, - { 128, "signal_strength", "" }, - { 256, "quality", "" }, - { 512, "pseudorange", "" }, - { 1024, "carrier_phase", "" }, - { 2048, "doppler", "" }, - { 4096, "range_uncertainty", "" }, - { 8192, "carrier_phase_uncertainty", "" }, - { 16384, "doppler_uncertainty", "" }, - { 32768, "lock_time", "" }, - { 65535, "flags", "" }, + { uint32_t(1), "tow", "" }, + { uint32_t(2), "week_number", "" }, + { uint32_t(4), "receiver_id", "" }, + { uint32_t(8), "tracking_channel", "" }, + { uint32_t(16), "gnss_id", "" }, + { uint32_t(32), "satellite_id", "" }, + { uint32_t(64), "signal_id", "" }, + { uint32_t(128), "signal_strength", "" }, + { uint32_t(256), "quality", "" }, + { uint32_t(512), "pseudorange", "" }, + { uint32_t(1024), "carrier_phase", "" }, + { uint32_t(2048), "doppler", "" }, + { uint32_t(4096), "range_uncertainty", "" }, + { uint32_t(8192), "carrier_phase_uncertainty", "" }, + { uint32_t(16384), "doppler_uncertainty", "" }, + { uint32_t(32768), "lock_time", "" }, + { uint32_t(65535), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -2466,7 +2467,7 @@ struct MetadataFor /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2475,7 +2476,7 @@ struct MetadataFor /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2484,7 +2485,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2493,7 +2494,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2502,7 +2503,7 @@ struct MetadataFor /* .docs = */ "When the measurement comes from RTCM, this will be the reference station ID; otherwise, it's the receiver number (1,2,...)", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2511,7 +2512,7 @@ struct MetadataFor /* .docs = */ "Channel the receiver is using to track this satellite.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2520,7 +2521,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2529,7 +2530,7 @@ struct MetadataFor /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2538,7 +2539,7 @@ struct MetadataFor /* .docs = */ "Signal identifier for the satellite.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2547,7 +2548,7 @@ struct MetadataFor /* .docs = */ "Carrier to noise ratio [dBHz].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2556,7 +2557,7 @@ struct MetadataFor /* .docs = */ "Indicator of signal quality.", /* .type = */ {Type::ENUM, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2565,7 +2566,7 @@ struct MetadataFor /* .docs = */ "Pseudo-range measurement [meters].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2574,7 +2575,7 @@ struct MetadataFor /* .docs = */ "Carrier phase measurement [Carrier periods].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2583,7 +2584,7 @@ struct MetadataFor /* .docs = */ "Measured doppler shift [Hz].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2592,7 +2593,7 @@ struct MetadataFor /* .docs = */ "Uncertainty of the pseudo-range measurement [m].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2601,7 +2602,7 @@ struct MetadataFor /* .docs = */ "Uncertainty of the phase measurement [Carrier periods].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2610,7 +2611,7 @@ struct MetadataFor /* .docs = */ "Uncertainty of the measured doppler shift [Hz].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2619,16 +2620,16 @@ struct MetadataFor /* .docs = */ "DOC\nMinimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2652,9 +2653,10 @@ struct MetadataFor using type = data_gnss::GpsEphemeris::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "ephemeris", "" }, - { 2, "modern_data", "" }, - { 3, "flags", "" }, + { uint32_t(1), "ephemeris", "" }, + { uint32_t(2), "modern_data", "" }, + { uint32_t(4), "isc_l5", "" }, + { uint32_t(7), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -2677,7 +2679,7 @@ struct MetadataFor /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2686,7 +2688,7 @@ struct MetadataFor /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2695,7 +2697,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2704,7 +2706,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2713,7 +2715,7 @@ struct MetadataFor /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2722,7 +2724,7 @@ struct MetadataFor /* .docs = */ "Satellite and signal health", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2731,7 +2733,7 @@ struct MetadataFor /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2740,7 +2742,7 @@ struct MetadataFor /* .docs = */ "Issue of Data Ephemeris.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2749,7 +2751,7 @@ struct MetadataFor /* .docs = */ "Reference time for clock data.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2758,7 +2760,7 @@ struct MetadataFor /* .docs = */ "Clock bias in [s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2767,7 +2769,7 @@ struct MetadataFor /* .docs = */ "Clock drift in [s/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2776,7 +2778,7 @@ struct MetadataFor /* .docs = */ "Clock drift rate in [s/s^2].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2785,25 +2787,25 @@ struct MetadataFor /* .docs = */ "T Group Delay [s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "ISC_L1CA", - /* .docs = */ "", + /* .docs = */ "Inter-signal correction (L1).", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "ISC_L2C", - /* .docs = */ "", + /* .docs = */ "Inter-signal correction (L2, or L5 if isc_l5 flag is set).", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2812,7 +2814,7 @@ struct MetadataFor /* .docs = */ "Reference time for ephemeris in [s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2821,7 +2823,7 @@ struct MetadataFor /* .docs = */ "Semi-major axis [m].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2830,7 +2832,7 @@ struct MetadataFor /* .docs = */ "Semi-major axis rate [m/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2839,7 +2841,7 @@ struct MetadataFor /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2848,7 +2850,7 @@ struct MetadataFor /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2857,7 +2859,7 @@ struct MetadataFor /* .docs = */ "[rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2866,7 +2868,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2875,7 +2877,7 @@ struct MetadataFor /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2884,7 +2886,7 @@ struct MetadataFor /* .docs = */ "Longitude of Ascending Node [rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2893,7 +2895,7 @@ struct MetadataFor /* .docs = */ "Rate of Right Ascension [rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2902,7 +2904,7 @@ struct MetadataFor /* .docs = */ "Inclination angle [rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2911,7 +2913,7 @@ struct MetadataFor /* .docs = */ "Inclination angle rate of change [rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2920,7 +2922,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2929,7 +2931,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2938,7 +2940,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2947,7 +2949,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2956,7 +2958,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2965,16 +2967,16 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -2982,7 +2984,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::GpsEphemeris", - /* .title = */ "gps_ephemeris", + /* .title = */ "GPS Ephemeris", /* .docs = */ "GPS Ephemeris Data", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -2998,9 +3000,10 @@ struct MetadataFor using type = data_gnss::GalileoEphemeris::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "ephemeris", "" }, - { 2, "modern_data", "" }, - { 3, "flags", "" }, + { uint32_t(1), "ephemeris", "" }, + { uint32_t(2), "modern_data", "" }, + { uint32_t(4), "isc_l5", "" }, + { uint32_t(7), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -3023,7 +3026,7 @@ struct MetadataFor /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3032,7 +3035,7 @@ struct MetadataFor /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3041,7 +3044,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3050,7 +3053,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3059,7 +3062,7 @@ struct MetadataFor /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3068,7 +3071,7 @@ struct MetadataFor /* .docs = */ "Satellite and signal health", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3077,7 +3080,7 @@ struct MetadataFor /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3086,7 +3089,7 @@ struct MetadataFor /* .docs = */ "Issue of Data Ephemeris.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3095,7 +3098,7 @@ struct MetadataFor /* .docs = */ "Reference time for clock data.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3104,7 +3107,7 @@ struct MetadataFor /* .docs = */ "Clock bias in [s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3113,7 +3116,7 @@ struct MetadataFor /* .docs = */ "Clock drift in [s/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3122,7 +3125,7 @@ struct MetadataFor /* .docs = */ "Clock drift rate in [s/s^2].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3131,25 +3134,25 @@ struct MetadataFor /* .docs = */ "T Group Delay [s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "ISC_L1CA", - /* .docs = */ "", + /* .docs = */ "Inter-signal correction (L1).", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "ISC_L2C", - /* .docs = */ "", + /* .docs = */ "Inter-signal correction (L2, or L5 if isc_l5 flag is set).", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3158,7 +3161,7 @@ struct MetadataFor /* .docs = */ "Reference time for ephemeris in [s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3167,7 +3170,7 @@ struct MetadataFor /* .docs = */ "Semi-major axis [m].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3176,7 +3179,7 @@ struct MetadataFor /* .docs = */ "Semi-major axis rate [m/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3185,7 +3188,7 @@ struct MetadataFor /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3194,7 +3197,7 @@ struct MetadataFor /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3203,7 +3206,7 @@ struct MetadataFor /* .docs = */ "[rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3212,7 +3215,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3221,7 +3224,7 @@ struct MetadataFor /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3230,7 +3233,7 @@ struct MetadataFor /* .docs = */ "Longitude of Ascending Node [rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3239,7 +3242,7 @@ struct MetadataFor /* .docs = */ "Rate of Right Ascension [rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3248,7 +3251,7 @@ struct MetadataFor /* .docs = */ "Inclination angle [rad].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3257,7 +3260,7 @@ struct MetadataFor /* .docs = */ "Inclination angle rate of change [rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3266,7 +3269,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3275,7 +3278,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3284,7 +3287,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3293,7 +3296,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3302,7 +3305,7 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3311,16 +3314,16 @@ struct MetadataFor /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3328,7 +3331,7 @@ struct MetadataFor static constexpr inline FieldInfo value = { /* .name = */ "data_gnss::GalileoEphemeris", - /* .title = */ "galileo_ephemeris", + /* .title = */ "Galileo Ephemeris", /* .docs = */ "Galileo Ephemeris Data", /* .parameters = */ parameters, /* .descriptor = */ type::DESCRIPTOR, @@ -3344,8 +3347,8 @@ struct MetadataFor using type = data_gnss::GloEphemeris::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "ephemeris", "" }, - { 1, "flags", "" }, + { uint32_t(1), "ephemeris", "" }, + { uint32_t(1), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -3368,7 +3371,7 @@ struct MetadataFor /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3377,7 +3380,7 @@ struct MetadataFor /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3386,7 +3389,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3395,7 +3398,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3404,7 +3407,7 @@ struct MetadataFor /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3413,7 +3416,7 @@ struct MetadataFor /* .docs = */ "GLONASS frequency number (-7 to 24)", /* .type = */ {Type::S8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3422,7 +3425,7 @@ struct MetadataFor /* .docs = */ "Frame start time within current day [seconds]", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3431,7 +3434,7 @@ struct MetadataFor /* .docs = */ "Ephemeris reference time [seconds]", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3440,7 +3443,7 @@ struct MetadataFor /* .docs = */ "Type of satellite (M) GLONASS = 0, GLONASS-M = 1", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3449,7 +3452,7 @@ struct MetadataFor /* .docs = */ "Relative deviation of carrier frequency from nominal [dimensionless]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3458,7 +3461,7 @@ struct MetadataFor /* .docs = */ "Time correction relative to GLONASS Time [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3467,7 +3470,7 @@ struct MetadataFor /* .docs = */ "Satellite PE-90 position [m]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3476,7 +3479,7 @@ struct MetadataFor /* .docs = */ "Satellite PE-90 velocity [m/s]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3485,7 +3488,7 @@ struct MetadataFor /* .docs = */ "Satellite PE-90 acceleration due to perturbations [m/s^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3494,7 +3497,7 @@ struct MetadataFor /* .docs = */ "Satellite Health (Bn), Non-zero indicates satellite malfunction", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3503,7 +3506,7 @@ struct MetadataFor /* .docs = */ "Satellite operation mode (See GLONASS ICD)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3512,7 +3515,7 @@ struct MetadataFor /* .docs = */ "Day number within a 4 year period.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3521,7 +3524,7 @@ struct MetadataFor /* .docs = */ "Time difference between L1 and L2[m/s]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3530,7 +3533,7 @@ struct MetadataFor /* .docs = */ "User Range Accuracy (See GLONASS ICD)", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3539,7 +3542,7 @@ struct MetadataFor /* .docs = */ "Age of current information [days]", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3548,7 +3551,7 @@ struct MetadataFor /* .docs = */ "Time interval between adjacent values of tb [minutes]", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3557,7 +3560,7 @@ struct MetadataFor /* .docs = */ "Oddness '1' or evenness '0' of the value of tb.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3566,7 +3569,7 @@ struct MetadataFor /* .docs = */ "Number of satellites in almanac for this frame", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3575,16 +3578,16 @@ struct MetadataFor /* .docs = */ "Flag indicating ephemeris parameters are present", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3608,11 +3611,11 @@ struct MetadataFor using type = data_gnss::GpsIonoCorr::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tow", "" }, - { 2, "week_number", "" }, - { 4, "alpha", "" }, - { 8, "beta", "" }, - { 15, "flags", "" }, + { uint32_t(1), "tow", "" }, + { uint32_t(2), "week_number", "" }, + { uint32_t(4), "alpha", "" }, + { uint32_t(8), "beta", "" }, + { uint32_t(15), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -3635,7 +3638,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3644,7 +3647,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3653,7 +3656,7 @@ struct MetadataFor /* .docs = */ "Ionospheric Correction Terms.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, }, @@ -3662,16 +3665,16 @@ struct MetadataFor /* .docs = */ "Ionospheric Correction Terms.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3695,11 +3698,11 @@ struct MetadataFor using type = data_gnss::GalileoIonoCorr::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tow", "" }, - { 2, "week_number", "" }, - { 4, "alpha", "" }, - { 8, "disturbance_flags", "" }, - { 15, "flags", "" }, + { uint32_t(1), "tow", "" }, + { uint32_t(2), "week_number", "" }, + { uint32_t(4), "alpha", "" }, + { uint32_t(8), "disturbance_flags", "" }, + { uint32_t(15), "flags", "" }, }; static constexpr inline BitfieldInfo value = { @@ -3722,7 +3725,7 @@ struct MetadataFor /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3731,7 +3734,7 @@ struct MetadataFor /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3740,7 +3743,7 @@ struct MetadataFor /* .docs = */ "Coefficients for the model.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3749,16 +3752,16 @@ struct MetadataFor /* .docs = */ "Region disturbance flags (bits 1-5).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -3777,7 +3780,7 @@ struct MetadataFor }; -static constexpr inline std::initializer_list ALL_DATA_GNSS = { +static constexpr inline std::initializer_list DATA_GNSS = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index 0249b7517..84d0b6b0a 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -21,7 +21,7 @@ struct MetadataFor /* .docs = */ "Native sensor counts", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -50,7 +50,7 @@ struct MetadataFor /* .docs = */ "Native sensor counts", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -79,7 +79,7 @@ struct MetadataFor /* .docs = */ "Native sensor counts", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -108,7 +108,7 @@ struct MetadataFor /* .docs = */ "Native sensor counts", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -137,7 +137,7 @@ struct MetadataFor /* .docs = */ "(x, y, z)[g]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -166,7 +166,7 @@ struct MetadataFor /* .docs = */ "(x, y, z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -195,7 +195,7 @@ struct MetadataFor /* .docs = */ "(x, y, z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -224,7 +224,7 @@ struct MetadataFor /* .docs = */ "[mBar]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -253,7 +253,7 @@ struct MetadataFor /* .docs = */ "(x, y, z) [radians]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -282,7 +282,7 @@ struct MetadataFor /* .docs = */ "(x, y, z) [g*sec]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -311,7 +311,7 @@ struct MetadataFor /* .docs = */ "Matrix elements in row-major order.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -340,7 +340,7 @@ struct MetadataFor /* .docs = */ "Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -369,7 +369,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -378,7 +378,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -387,7 +387,7 @@ struct MetadataFor /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -416,7 +416,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -445,7 +445,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, }, @@ -474,7 +474,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -503,7 +503,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -512,7 +512,7 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -536,11 +536,11 @@ struct MetadataFor using type = data_sensor::GpsTimestamp::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "pps_valid", "True when the PPS signal is present." }, - { 2, "time_refresh", "Toggles each time the time is updated via internal GPS or the GPS Time Update command (0x01, 0x72)." }, - { 4, "time_initialized", "True if the time has ever been set." }, - { 8, "tow_valid", "True if the time of week is valid." }, - { 16, "week_number_valid", "True if the week number is valid." }, + { uint32_t(1), "pps_valid", "True when the PPS signal is present." }, + { uint32_t(2), "time_refresh", "Toggles each time the time is updated via internal GPS or the GPS Time Update command (0x01, 0x72)." }, + { uint32_t(4), "time_initialized", "True if the time has ever been set." }, + { uint32_t(8), "tow_valid", "True if the time of week is valid." }, + { uint32_t(16), "week_number_valid", "True if the week number is valid." }, }; static constexpr inline BitfieldInfo value = { @@ -563,7 +563,7 @@ struct MetadataFor /* .docs = */ "GPS Time of Week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -572,16 +572,16 @@ struct MetadataFor /* .docs = */ "GPS Week Number since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -610,7 +610,7 @@ struct MetadataFor /* .docs = */ "[degC]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -619,7 +619,7 @@ struct MetadataFor /* .docs = */ "[degC]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -628,7 +628,7 @@ struct MetadataFor /* .docs = */ "[degC]", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -657,7 +657,7 @@ struct MetadataFor /* .docs = */ "[Gs]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -686,7 +686,7 @@ struct MetadataFor /* .docs = */ "[Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -710,16 +710,16 @@ struct MetadataFor using type = data_sensor::OverrangeStatus::Status; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "accel_x", "" }, - { 2, "accel_y", "" }, - { 4, "accel_z", "" }, - { 16, "gyro_x", "" }, - { 32, "gyro_y", "" }, - { 64, "gyro_z", "" }, - { 256, "mag_x", "" }, - { 512, "mag_y", "" }, - { 1024, "mag_z", "" }, - { 4096, "press", "" }, + { uint32_t(1), "accel_x", "" }, + { uint32_t(2), "accel_y", "" }, + { uint32_t(4), "accel_z", "" }, + { uint32_t(16), "gyro_x", "" }, + { uint32_t(32), "gyro_y", "" }, + { uint32_t(64), "gyro_z", "" }, + { uint32_t(256), "mag_x", "" }, + { uint32_t(512), "mag_y", "" }, + { uint32_t(1024), "mag_z", "" }, + { uint32_t(4096), "press", "" }, }; static constexpr inline BitfieldInfo value = { @@ -740,9 +740,9 @@ struct MetadataFor { /* .name = */ "status", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -771,7 +771,7 @@ struct MetadataFor /* .docs = */ "Average speed over the time interval [m/s]. Can be negative for quadrature encoders.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -780,7 +780,7 @@ struct MetadataFor /* .docs = */ "Uncertainty of velocity [m/s].", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -789,7 +789,7 @@ struct MetadataFor /* .docs = */ "If odometer is configured, bit 0 will be set to 1.", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -808,7 +808,7 @@ struct MetadataFor }; -static constexpr inline std::initializer_list ALL_DATA_SENSOR = { +static constexpr inline std::initializer_list DATA_SENSOR = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/data_shared.hpp b/src/cpp/mip/metadata/definitions/data_shared.hpp index f3a2f2889..d50165899 100644 --- a/src/cpp/mip/metadata/definitions/data_shared.hpp +++ b/src/cpp/mip/metadata/definitions/data_shared.hpp @@ -21,7 +21,7 @@ struct MetadataFor /* .docs = */ "Trigger ID number. If 0, this message was emitted due to being\nscheduled in the 3DM Message Format Command (0x0C,0x0F).", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -50,7 +50,7 @@ struct MetadataFor /* .docs = */ "Ticks since powerup.", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -79,7 +79,7 @@ struct MetadataFor /* .docs = */ "Ticks since last output.", /* .type = */ {Type::U32, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -103,9 +103,9 @@ struct MetadataFor using type = data_shared::GpsTimestamp::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "tow", "Whole number seconds TOW has been set" }, - { 2, "week_number", "Week number has been set" }, - { 3, "time_valid", "Both TOW and Week Number have been set" }, + { uint32_t(1), "tow", "Whole number seconds TOW has been set" }, + { uint32_t(2), "week_number", "Week number has been set" }, + { uint32_t(3), "time_valid", "Both TOW and Week Number have been set" }, }; static constexpr inline BitfieldInfo value = { @@ -128,7 +128,7 @@ struct MetadataFor /* .docs = */ "GPS Time of Week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -137,16 +137,16 @@ struct MetadataFor /* .docs = */ "GPS Week Number since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -175,7 +175,7 @@ struct MetadataFor /* .docs = */ "Seconds since last output.", /* .type = */ {Type::DOUBLE, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -204,7 +204,7 @@ struct MetadataFor /* .docs = */ "Nanoseconds since initialization.", /* .type = */ {Type::U64, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -233,7 +233,7 @@ struct MetadataFor /* .docs = */ "Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source.", /* .type = */ {Type::U64, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -257,7 +257,7 @@ struct MetadataFor using type = data_shared::ExternalTimestamp::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "nanoseconds", "" }, + { uint32_t(1), "nanoseconds", "" }, }; static constexpr inline BitfieldInfo value = { @@ -280,16 +280,16 @@ struct MetadataFor /* .docs = */ "", /* .type = */ {Type::U64, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -313,7 +313,7 @@ struct MetadataFor using type = data_shared::ExternalTimeDelta::ValidFlags; static constexpr inline BitfieldInfo::Entry entries[] = { - { 1, "dt_nanos", "" }, + { uint32_t(1), "dt_nanos", "" }, }; static constexpr inline BitfieldInfo value = { @@ -336,16 +336,16 @@ struct MetadataFor /* .docs = */ "Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source.", /* .type = */ {Type::U64, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, { /* .name = */ "valid_flags", /* .docs = */ "", - /* .type = */ {Type::BITFIELD, &MetadataFor::value}, + /* .type = */ {Type::BITS, &MetadataFor::value}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -364,7 +364,7 @@ struct MetadataFor }; -static constexpr inline std::initializer_list ALL_DATA_SHARED = { +static constexpr inline std::initializer_list DATA_SHARED = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/definitions/data_system.hpp b/src/cpp/mip/metadata/definitions/data_system.hpp index 2c976c2ab..dd382fc1a 100644 --- a/src/cpp/mip/metadata/definitions/data_system.hpp +++ b/src/cpp/mip/metadata/definitions/data_system.hpp @@ -21,7 +21,7 @@ struct MetadataFor /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 16, /* .condition = */ {}, }, @@ -50,7 +50,7 @@ struct MetadataFor /* .docs = */ "True if sync with the PPS signal is currently valid. False if PPS\nfeature is disabled or a PPS signal is not detected.", /* .type = */ {Type::BOOL, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -59,7 +59,7 @@ struct MetadataFor /* .docs = */ "Elapsed time in seconds since last PPS was received, with a maximum\nvalue of 255.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -88,7 +88,7 @@ struct MetadataFor /* .docs = */ "Bitfield containing the states for each GPIO pin.
\nBit 0 (0x01): pin 1
\nBit 1 (0x02): pin 2
\nBit 2 (0x04): pin 3
\nBit 3 (0x08): pin 4
\nBits for pins that don't exist will read as 0.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -117,7 +117,7 @@ struct MetadataFor /* .docs = */ "GPIO pin number starting with 1.", /* .type = */ {Type::U8, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -126,7 +126,7 @@ struct MetadataFor /* .docs = */ "Value of the GPIO line in scaled volts.", /* .type = */ {Type::FLOAT, nullptr}, /* .accessor = */ utils::access, - /* .functions = */ {true, false, false, false, false, true}, + /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, }, @@ -145,7 +145,7 @@ struct MetadataFor }; -static constexpr inline std::initializer_list ALL_DATA_SYSTEM = { +static constexpr inline std::initializer_list DATA_SYSTEM = { &MetadataFor::value, &MetadataFor::value, &MetadataFor::value, diff --git a/src/cpp/mip/metadata/mip_meta_utils.hpp b/src/cpp/mip/metadata/mip_meta_utils.hpp index 4d1b78ef2..ae0f80121 100644 --- a/src/cpp/mip/metadata/mip_meta_utils.hpp +++ b/src/cpp/mip/metadata/mip_meta_utils.hpp @@ -23,7 +23,7 @@ template<> struct ParamType { static constexpr inline auto value template<> struct ParamType< int64_t, void> { static constexpr inline auto value = Type::S64; }; template<> struct ParamType { static constexpr inline auto value = Type::FLOAT; }; template<> struct ParamType { static constexpr inline auto value = Type::DOUBLE; }; -template struct ParamType, void> { static constexpr inline auto value = Type::BITFIELD; }; +template struct ParamType, void> { static constexpr inline auto value = Type::BITS; }; template struct ParamType::value, T>::type> { static constexpr inline auto value = Type::ENUM; }; template struct ParamType::type> { static constexpr inline auto value = Type::STRUCT; }; template struct ParamType::value, T>::type> { static constexpr inline auto value = Type::UNION; }; diff --git a/src/cpp/mip/metadata/mip_structures.hpp b/src/cpp/mip/metadata/mip_structures.hpp index 6db3628c9..f47460797 100644 --- a/src/cpp/mip/metadata/mip_structures.hpp +++ b/src/cpp/mip/metadata/mip_structures.hpp @@ -36,7 +36,7 @@ enum class Type DOUBLE, ENUM, - BITFIELD, + BITS, STRUCT, UNION, }; @@ -80,78 +80,90 @@ struct BitfieldInfo : public EnumInfo {}; //struct ParameterInfo; // Defined below -struct FuncBits +struct Attributes { - constexpr FuncBits() = default; - constexpr FuncBits(bool w, bool r, bool s, bool l, bool d, bool e=false) : bits(0x00) { write(w); read(r); save(s); load(l); reset(d); echo(e); } + constexpr Attributes() = default; + constexpr Attributes(bool w, bool r, bool s, bool l, bool d, bool e=false, bool x=false) : bits(0x00) + { + setCanWrite(w); + setCanRead(r); + setCanSave(s); + setCanLoad(l); + setCanReset(d); + setNotSerialized(x); + setIsEchoed(e); + } constexpr bool any() const { return bits > 0; } - constexpr bool write() const { return bits & 0b00000001; } - constexpr bool read() const { return bits & 0b00000010; } - constexpr bool save() const { return bits & 0b00000100; } - constexpr bool load() const { return bits & 0b00001000; } - constexpr bool reset() const { return bits & 0b00010000; } - constexpr bool echo() const { return bits & 0b10000000; } - - constexpr FuncBits& write(bool w) { bits = (bits & 0b11111110) | (uint8_t(w)<<0); return *this; } - constexpr FuncBits& read (bool r) { bits = (bits & 0b11111101) | (uint8_t(r)<<1); return *this; } - constexpr FuncBits& save (bool s) { bits = (bits & 0b11111011) | (uint8_t(s)<<2); return *this; } - constexpr FuncBits& load (bool l) { bits = (bits & 0b11110111) | (uint8_t(l)<<3); return *this; } - constexpr FuncBits& reset(bool d) { bits = (bits & 0b11101111) | (uint8_t(d)<<4); return *this; } - constexpr FuncBits& echo (bool e) { bits = (bits & 0b01111111) | (uint8_t(e)<<7); return *this; } + constexpr bool canWrite() const { return bits & 0b00000001; } + constexpr bool canRead() const { return bits & 0b00000010; } + constexpr bool canSave() const { return bits & 0b00000100; } + constexpr bool canLoad() const { return bits & 0b00001000; } + constexpr bool canReset() const { return bits & 0b00010000; } + constexpr bool isNotSerialized() const { return bits & 0b01000000; } + constexpr bool isEchoed() const { return bits & 0b10000000; } + constexpr bool isSerialized() const { return !isNotSerialized(); } + + constexpr Attributes& setCanWrite (bool w) { bits = (bits & 0b11111110) | (uint8_t(w)<<0); return *this; } + constexpr Attributes& setCanRead (bool r) { bits = (bits & 0b11111101) | (uint8_t(r)<<1); return *this; } + constexpr Attributes& setCanSave (bool s) { bits = (bits & 0b11111011) | (uint8_t(s)<<2); return *this; } + constexpr Attributes& setCanLoad (bool l) { bits = (bits & 0b11110111) | (uint8_t(l)<<3); return *this; } + constexpr Attributes& setCanReset (bool d) { bits = (bits & 0b11101111) | (uint8_t(d)<<4); return *this; } + constexpr Attributes& setNotSerialized (bool x) { bits = (bits & 0b10111111) | (uint8_t(x)<<6); return *this; } + constexpr Attributes& setIsEchoed (bool e) { bits = (bits & 0b01111111) | (uint8_t(e)<<7); return *this; } constexpr bool has(mip::FunctionSelector function) const { return (bits >> (static_cast(function) - static_cast(mip::FunctionSelector::WRITE))) & 1; } uint8_t bits = 0x00; }; -static constexpr inline FuncBits ALL_FUNCTIONS = {true,true,true,true,true}; -static constexpr inline FuncBits NO_FUNCTIONS = {false, false, false, false, false}; +static constexpr inline Attributes ALL_FUNCTIONS = {true, true, true, true, true}; +static constexpr inline Attributes NO_FUNCTIONS = {false, false, false, false, false}; - struct ParameterInfo +struct ParameterInfo +{ + struct Count { - struct Count - { - constexpr Count() = default; - constexpr Count(uint8_t n) : count(n) {} - constexpr Count(uint8_t n, microstrain::Id id) : count(n), paramIdx(id) {} + constexpr Count() = default; + constexpr Count(uint8_t n) : count(n) {} + constexpr Count(uint8_t n, microstrain::Id id) : count(n), paramIdx(id) {} - uint8_t count = 1; ///< Fixed size if paramIdx unassigned. - microstrain::Id paramIdx = {}; ///< If assigned, specifies parameter that holds the actual runtime count. + uint8_t count = 1; ///< Fixed size if paramIdx unassigned. + microstrain::Id paramIdx = {}; ///< If assigned, specifies parameter that holds the actual runtime count. - constexpr bool isFixed() const { return count > 0 && !paramIdx.isAssigned(); } - constexpr bool hasCounter() const { return paramIdx.isAssigned(); } - }; + constexpr bool isFixed() const { return count > 0 && !paramIdx.isAssigned(); } + constexpr bool hasCounter() const { return paramIdx.isAssigned(); } + }; - struct Condition + struct Condition + { + enum class Type : uint8_t { - enum class Type : uint8_t - { - NONE = 0, ///< No condition, member always valid - ENUM = 1, ///< Enum value selector (e.g. for parameters in unions) - //PRODUCT = 2, ///< Depends on product variant (TBD) - //OPTIONAL = 2, ///< Parameter can be omitted (TBD) - }; - - Type type = Type::NONE; ///< Type of condition. - microstrain::Id paramIdx = {}; ///< Index of enum parameter identifying whether this parameter is enabled. - uint16_t value = 0; ///< Value of the enum parameter which activates this parameter. - - constexpr bool hasCondition() const { return type != Type::NONE; } + NONE = 0, ///< No condition, member always valid + ENUM = 1, ///< Enum value selector (e.g. for parameters in unions) + //PRODUCT = 2, ///< Depends on product variant (TBD) + //OPTIONAL = 2, ///< Parameter can be omitted (TBD) }; - using Accessor = void* (*)(void*); + Type type = Type::NONE; ///< Type of condition. + microstrain::Id paramIdx = {}; ///< Index of enum parameter identifying whether this parameter is enabled. + uint16_t value = 0; ///< Value of the enum parameter which activates this parameter. - const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). - const char* docs = nullptr; ///< Human-readable documentation. - TypeInfo type; ///< Data type. - Accessor accessor = nullptr; ///< Obtains a reference to the member variable. - FuncBits functions; ///< This parameter is required for the specified function selectors. - Count count; ///< Number of instances for arrays. - Condition condition; ///< For conditionally-enabled parameters like those in unions. + constexpr bool hasCondition() const { return type != Type::NONE; } }; + using Accessor = void* (*)(void*); + + const char* name = nullptr; ///< Programmatic name (e.g. for printing or language bindings). + const char* docs = nullptr; ///< Human-readable documentation. + TypeInfo type; ///< Data type. + Accessor accessor = nullptr; ///< Obtains a reference to the member variable. + Attributes attributes; ///< This parameter is required for the specified function selectors. + Count count; ///< Number of instances for arrays. + Condition condition; ///< For conditionally-enabled parameters like those in unions. +}; + struct StructInfo { @@ -166,7 +178,7 @@ struct UnionInfo : public StructInfo {}; struct FieldInfo : public StructInfo { CompositeDescriptor descriptor = {0x00, 0x00}; - FuncBits functions = {false, false, false, false, false}; + Attributes functions = {false, false, false, false, false}; bool proprietary = false; const FieldInfo* response = nullptr; }; @@ -200,7 +212,7 @@ constexpr size_t sizeForBasicType(Type type, const void* info=nullptr) return 0; return sizeForBasicType(static_cast(info)->type); - case Type::BITFIELD: + case Type::BITS: if(!info) return 0; return sizeForBasicType(static_cast(info)->type); From b4ed593176b01378c3f8c14e54ecfee47cf606d5 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 20 Sep 2024 11:57:43 -0400 Subject: [PATCH 116/147] Add custom span implementation and CMake macro to enable std::span. --- CMakeLists.txt | 10 +- cmake/check_cxx_support.cmake | 30 ++++++ cmake/check_metadata.cmake | 25 ----- src/cpp/microstrain/common/CMakeLists.txt | 9 ++ src/cpp/microstrain/common/platform.hpp | 3 - .../common/serialization/readwrite.hpp | 28 +++++- .../common/serialization/serializer.hpp | 15 +-- src/cpp/microstrain/common/span.hpp | 97 +++++++++++++++++++ 8 files changed, 174 insertions(+), 43 deletions(-) create mode 100644 cmake/check_cxx_support.cmake delete mode 100644 cmake/check_metadata.cmake create mode 100644 src/cpp/microstrain/common/span.hpp diff --git a/CMakeLists.txt b/CMakeLists.txt index cc9eb99eb..e0dca0772 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -27,8 +27,17 @@ option(MICROSTRAIN_ENABLE_LOGGING "Build with logging functions enabled" ON) set(MICROSTRAIN_LOGGING_MAX_LEVEL "MICROSTRAIN_LOG_LEVEL_INFO" CACHE STRING "Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration.") set(MICROSTRAIN_TIMESTAMP_TYPE "uint64_t" CACHE STRING "Override the type used for received data timestamps and timeouts (must be unsigned or at least 64 bits).") +include(check_cxx_support) + option(MICROSTRAIN_ENABLE_CPP "Enables the C++ API. Turn off to avoid compiling the C++ API." ON) #option(MICROSTRAIN_ENABLE_CPP_C_NAMESPACE "Wraps the C api in a C++ namespace to avoid global namespace pollution (e.g. microstrain::C::microstrain_serial_port)" ${MICROSTRAIN_ENABLE_CPP}) +message(DEBUG "MICROSTRAIN_ENABLE_CPP=${MICROSTRAIN_ENABLE_CPP}") +if(MICROSTRAIN_ENABLE_CPP) + option(MICROSTRAIN_USE_STD_SPAN "Use std::span from C++20 for microstrain::Span." ${MICROSTRAIN_COMPILER_SUPPORTS_SPAN}) + option(MICROSTRAIN_USE_STD_ENDIAN "Use std::endian from C++20 for microstrain::Endian." ${MICROSTRAIN_COMPILER_SUPPORTS_BIT}) + message(DEBUG "MICROSTRAIN_USE_STD_SPAN=${MICROSTRAIN_USE_STD_SPAN}") + message(DEBUG "MICROSTRAIN_USE_STD_ENDIAN=${MICROSTRAIN_USE_STD_ENDIAN}") +endif() option(MICROSTRAIN_ENABLE_EXTRAS "Build extra support into the library including some things that might work at a higher level and use dynamically allocated memory" ON) option(MICROSTRAIN_ENABLE_SERIAL "Build serial connection support into the library and examples" ON) @@ -51,7 +60,6 @@ mark_as_advanced(MICROSTRAIN_CMAKE_DEBUG) option(MIP_ENABLE_DIAGNOSTICS "Enable various diagnostic counters in the mip library for debugging." OFF) if(NOT DEFINED MIP_ENABLE_METADATA) - include(check_metadata) message(STATUS "MIP_ENABLE_METADATA not set - compiler support: ${MIP_COMPILER_SUPPORTS_METADATA}") endif() option(MIP_ENABLE_METADATA "Build support for MIP protocol metadata in C++ (requires c++20)" ${MIP_COMPILER_SUPPORTS_METADATA}) diff --git a/cmake/check_cxx_support.cmake b/cmake/check_cxx_support.cmake new file mode 100644 index 000000000..abeb77296 --- /dev/null +++ b/cmake/check_cxx_support.cmake @@ -0,0 +1,30 @@ + +include(CheckIncludeFileCXX) + +CHECK_INCLUDE_FILE_CXX("span" MICROSTRAIN_COMPILER_SUPPORTS_SPAN) +CHECK_INCLUDE_FILE_CXX("bit" MICROSTRAIN_COMPILER_SUPPORTS_BIT) + + +include(CheckCXXSourceCompiles) + +check_cxx_source_compiles(" + +#if __cpp_constexpr < 201907L +#error \"Metadata not supported\" +#endif + +struct Foo +{ + int i = 0; + const char* s = nullptr; +}; + +static inline constexpr Foo foo = {5, \"12345\"}; + +int main() +{ + static_assert(foo.i == 5 && foo.s != nullptr, \"foo has wrong value\"); + return 0; +} + +" MIP_COMPILER_SUPPORTS_METADATA) diff --git a/cmake/check_metadata.cmake b/cmake/check_metadata.cmake deleted file mode 100644 index 9ed17af9c..000000000 --- a/cmake/check_metadata.cmake +++ /dev/null @@ -1,25 +0,0 @@ - -#include(CheckCXXSourceCompiles) - -#check_cxx_source_compiles(" -##include -# -#struct Foo -#{ -# int i = 0; -# const char* s = nullptr; -#}; -# -#static inline constexpr Foo foo = {5, \"12345\"}; -# -#int main() -#{ -# static_assert(foo.i == 5 && foo.s != nullptr, \"foo has wrong value\"); -# return 0; -#} -# -#" MIP_COMPILER_SUPPORTS_METADATA) - -include(CheckIncludeFileCXX) - -CHECK_INCLUDE_FILE_CXX("span" MIP_COMPILER_SUPPORTS_METADATA) diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index a66e00624..7caf0ed9d 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -12,6 +12,15 @@ target_sources(${MICROSTRAIN_COMMON_LIBRARY} PRIVATE target_compile_features(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC cxx_std_11) target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${MICROSTRAIN_SRC_CPP_DIR}) + +if(MICROSTRAIN_USE_STD_SPAN) + target_compile_options(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_USE_STD_SPAN=1") +endif() + +if(MICROSTRAIN_USE_STD_ENDIAN) + target_compile_options(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_USE_STD_ENDIAN=1") +endif() + # # Installation # diff --git a/src/cpp/microstrain/common/platform.hpp b/src/cpp/microstrain/common/platform.hpp index c3830d902..52a2a60f6 100644 --- a/src/cpp/microstrain/common/platform.hpp +++ b/src/cpp/microstrain/common/platform.hpp @@ -24,6 +24,3 @@ #if __cpp_lib_optional >= 201606L #define MICROSTRAIN_HAS_OPTIONAL #endif -#if __cpp_lib_span >= 202002L -#define MICROSTRAIN_HAS_SPAN -#endif diff --git a/src/cpp/microstrain/common/serialization/readwrite.hpp b/src/cpp/microstrain/common/serialization/readwrite.hpp index fd16e5128..0c2d35dc1 100644 --- a/src/cpp/microstrain/common/serialization/readwrite.hpp +++ b/src/cpp/microstrain/common/serialization/readwrite.hpp @@ -16,21 +16,41 @@ //#include //#endif +#if MICROSTRAIN_USE_STD_ENDIAN + +#include + +namespace microstrain +{ +namespace serialization +{ + using Endian = std::endian; +} +} + +#else + namespace microstrain { namespace serialization { -//#if __cpp_lib_endian >= 201907L -//using Endian = std::endian; -//#else enum class Endian { little, big, //native = little, }; -//#endif + +} +} + +#endif + +namespace microstrain +{ +namespace serialization +{ // // Write to buffer diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index bd62b0961..3468503e6 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -2,6 +2,8 @@ #include "readwrite.hpp" +#include "../span.hpp" + #include #include @@ -10,9 +12,6 @@ #ifdef MICROSTRAIN_HAS_OPTIONAL #include #endif -#ifdef HAS_SPAN -#include -#endif #if __cpp_lib_apply >= 201603L #include @@ -27,9 +26,7 @@ class SerializerBase SerializerBase() = default; SerializerBase(uint8_t* ptr, size_t capacity, size_t offset=0) : m_ptr(ptr), m_size(capacity), m_offset(offset) {} SerializerBase(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} -#ifdef HAS_SPAN - SerializerBase(std::span buffer, size_t offset=0) : m_ptr(const_cast(buffer.data())), m_size(buffer.size()), m_offset(offset) {} -#endif + SerializerBase(microstrain::Span buffer, size_t offset=0) : m_ptr(const_cast(buffer.data())), m_size(buffer.size()), m_offset(offset) {} size_t capacity() const { return m_size; } size_t offset() const { return m_offset; } @@ -249,18 +246,16 @@ size_t extract(Serializer& serializer, T* values, size_t count) } } -#ifdef HAS_SPAN template -size_t insert(Serializer& serializer, std::span values) +size_t insert(Serializer& serializer, microstrain::Span values) { return insert(serializer, values.data(), values.size()); } template -size_t extract(Serializer& serializer, std::span values) +size_t extract(Serializer& serializer, microstrain::Span values) { return extract(serializer, values.data(), values.size()); } -#endif // diff --git a/src/cpp/microstrain/common/span.hpp b/src/cpp/microstrain/common/span.hpp new file mode 100644 index 000000000..d90294aaa --- /dev/null +++ b/src/cpp/microstrain/common/span.hpp @@ -0,0 +1,97 @@ +#pragma once + +#if MICROSTRAIN_USE_STD_SPAN + +#include + +namespace microstrain +{ + + static inline constexpr size_t DYNAMIC_EXTENT = std::dynamic_extent; + + template + using Span = std::span; + +} + +#else // MICROSTRAIN_USE_STD_SPAN + +#include +#include + +namespace microstrain +{ + + +static constexpr size_t DYNAMIC_EXTENT = -1; + +template +struct Span +{ + static constexpr size_t extent = Extent; + + using element_type = T; + using value_type = typename std::remove_cv::type; + using difference_type = ptrdiff_t; + using pointer = T*; + using reference = T&; + using const_pointer = const T*; + using const_reference = const T&; + + Span(pointer ptr) : m_ptr(ptr) {} + + constexpr pointer begin() const noexcept { return m_ptr; } + constexpr pointer end() const noexcept { return m_ptr+extent; } + + constexpr element_type front() const noexcept { return *m_ptr; } + constexpr element_type back() const noexcept { return *m_ptr[extent-1]; } + + constexpr reference operator[](size_t idx) noexcept { return m_ptr[idx]; } + constexpr const_reference operator[](size_t idx) const noexcept { return m_ptr[idx]; } + + constexpr pointer data() const noexcept { return m_ptr; } + + [[nodiscard]] constexpr size_t size() const noexcept { return extent; } + [[nodiscard]] constexpr bool empty() const noexcept { return extent == 0; } + +private: + const pointer m_ptr = nullptr; +}; + + +template +struct Span +{ + using element_type = T; + using value_type = typename std::remove_cv::type; + using difference_type = ptrdiff_t; + using pointer = T*; + using reference = T&; + using const_pointer = const T*; + using const_reference = const T&; + + Span(pointer ptr, size_t cnt) : m_ptr(ptr), m_cnt(cnt) {} + + constexpr pointer begin() const noexcept { return m_ptr; } + constexpr pointer end() const noexcept { return m_ptr+m_cnt; } + + constexpr element_type front() const noexcept { return *m_ptr; } + constexpr element_type back() const noexcept { return *m_ptr[m_cnt-1]; } + + constexpr reference operator[](size_t idx) noexcept { return m_ptr[idx]; } + constexpr const_reference operator[](size_t idx) const noexcept { return m_ptr[idx]; } + + constexpr pointer data() const noexcept { return m_ptr; } + + [[nodiscard]] constexpr size_t size() const noexcept { return m_cnt; } + [[nodiscard]] constexpr bool empty() const noexcept { return m_cnt == 0; } + +private: + pointer const m_ptr = nullptr; + size_t const m_cnt = 0; +}; + + +} // namespace microstrain + +#endif // MICROSTRAIN_USE_STD_SPAN From ba03237a627f93fc720a790a7be5a5f777b24de4 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 20 Sep 2024 12:23:36 -0400 Subject: [PATCH 117/147] Fixed Windows compiler warnings Fixed metadata all commands/data descriptor lists Fixed metadata Type::BITFIELD --> Type::BITS Updated builds to pre-build all targets before packaging (prevents possible issues with parallelism on package) Added multi-process compilation for MSVC Fixed adding Span/Endian preprocessor definitions (was options) Fixed preprocessor check for Span/Endian definitions --- .devcontainer/docker_build.sh | 4 +- CMakeLists.txt | 3 +- Jenkinsfile | 12 +++-- examples/CSV/stringify.cpp | 2 +- examples/CV7_INS/CV7_INS_simple_example.cpp | 5 +- .../CV7_INS/CV7_INS_simple_ublox_example.cpp | 6 ++- examples/device_info.cpp | 4 ++ src/cpp/microstrain/common/CMakeLists.txt | 4 +- src/cpp/microstrain/common/index.hpp | 3 +- .../common/serialization/readwrite.hpp | 27 ++++------- src/cpp/microstrain/common/span.hpp | 6 +-- src/cpp/mip/metadata/mip_all_definitions.hpp | 48 +++++++++---------- 12 files changed, 65 insertions(+), 59 deletions(-) diff --git a/.devcontainer/docker_build.sh b/.devcontainer/docker_build.sh index 7566ef20d..424afa992 100755 --- a/.devcontainer/docker_build.sh +++ b/.devcontainer/docker_build.sh @@ -62,9 +62,9 @@ docker run \ mkdir ${docker_project_dir}/${build_dir_name}; \ cd ${docker_project_dir}/${build_dir_name}; \ cmake ${docker_project_dir} \ + -DMICROSTRAIN_BUILD_EXAMPLES=ON \ -DMICROSTRAIN_BUILD_PACKAGE=ON \ -DCMAKE_BUILD_TYPE=RELEASE; \ - -DMICROSTRAIN_BUILD_EXAMPLES=ON \ - cmake --build . -j; \ + cmake --build . -j$(nproc); \ cmake --build . --target package; \ " diff --git a/CMakeLists.txt b/CMakeLists.txt index e0dca0772..253f6b509 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.12) -set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD 11) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_C_STANDARD 11) set(CMAKE_C_STANDARD_REQUIRED ON) @@ -79,6 +79,7 @@ if(WIN32) "/external:W0" # No warnings from system includes "/W4" # Enable warnings "/Zc:__cplusplus" # Enable updated __cplusplus value + "/MP" # Multi-process compilation ) endif() diff --git a/Jenkinsfile b/Jenkinsfile index c0c643d98..11e97bb50 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -39,7 +39,7 @@ pipeline { // Run all the builds in parallel parallel { stage('Documentation') { - agent { label 'windows10' } + agent { label 'linux-amd64' } options { skipDefaultCheckout() timeout(time: 5, activity: true, unit: 'MINUTES') @@ -71,7 +71,8 @@ pipeline { powershell """ mkdir build_Win32 cd build_Win32 - cmake .. -A "Win32" -DMICROSTRAIN_BUILD_PACKAGE=ON -DMICROSTRAIN_BUILD_EXAMPLES=ON + cmake .. -A "Win32" -DMICROSTRAIN_BUILD_EXAMPLES=ON -DMICROSTRAIN_BUILD_PACKAGE=ON + cmake --build . --config Release cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_Win32/mipsdk_*' @@ -91,7 +92,8 @@ pipeline { powershell """ mkdir build_x64 cd build_x64 - cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DMICROSTRAIN_BUILD_EXAMPLES=ON + cmake .. -DMICROSTRAIN_BUILD_EXAMPLES=ON -DMICROSTRAIN_BUILD_PACKAGE=ON + cmake --build . --config Release cmake --build . --config Release --target package """ archiveArtifacts artifacts: 'build_x64/mipsdk_*' @@ -171,7 +173,7 @@ pipeline { sh ''' mkdir build_mac_arm64 cd build_mac_arm64 - cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE -DMICROSTRAIN_BUILD_EXAMPLES=ON + cmake .. -DMICROSTRAIN_BUILD_EXAMPLES=ON -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' @@ -192,7 +194,7 @@ pipeline { sh ''' mkdir build_mac_intel cd build_mac_intel - cmake .. -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE -DMICROSTRAIN_BUILD_EXAMPLES=ON + cmake .. -DMICROSTRAIN_BUILD_EXAMPLES=ON -DMICROSTRAIN_BUILD_PACKAGE=ON -DCMAKE_BUILD_TYPE=RELEASE cmake --build . -j $(sysctl -n hw.ncpu) cmake --build . --target package ''' diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp index 707cd1f94..3156e2005 100644 --- a/examples/CSV/stringify.cpp +++ b/examples/CSV/stringify.cpp @@ -187,7 +187,7 @@ void Formatter::formatParameter(const mip::metadata::ParameterInfo ¶m, const formatEnum(static_cast(param.type.infoPtr)); break; - case Type::BITFIELD: + case Type::BITS: formatBitfield(static_cast(param.type.infoPtr)); break; diff --git a/examples/CV7_INS/CV7_INS_simple_example.cpp b/examples/CV7_INS/CV7_INS_simple_example.cpp index 257885615..c07754dd4 100644 --- a/examples/CV7_INS/CV7_INS_simple_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_example.cpp @@ -308,7 +308,11 @@ void print_device_information(const commands_base::BaseDeviceInfo& device_info) auto print_info = [](const char* name, const char info[16]) { char msg[17] = {0}; +#ifdef _WIN32 + strncpy_s(msg, info, 16); +#else std::strncpy(msg, info, 16); +#endif printf(" %s%s\n", name, msg); }; @@ -363,4 +367,3 @@ bool should_exit() { return false; } - diff --git a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp index 4bfc8a186..e222ffe60 100644 --- a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp @@ -403,7 +403,12 @@ void print_device_information(const commands_base::BaseDeviceInfo& device_info) auto print_info = [](const char* name, const char info[16]) { char msg[17] = {0}; +#ifdef _WIN32 + strncpy_s(msg, info, 16); +#else std::strncpy(msg, info, 16); +#endif + printf(" %s%s\n", name, msg); }; @@ -514,4 +519,3 @@ bool should_exit() { return false; } - diff --git a/examples/device_info.cpp b/examples/device_info.cpp index 209cab11a..ec0bb623c 100644 --- a/examples/device_info.cpp +++ b/examples/device_info.cpp @@ -44,7 +44,11 @@ int main(int argc, const char* argv[]) auto print_info = [](const char* name, const char info[16]) { char msg[17] = {0}; +#ifdef _WIN32 + strncpy_s(msg, info, 16); +#else std::strncpy(msg, info, 16); +#endif printf(" %s%s\n", name, msg); }; diff --git a/src/cpp/microstrain/common/CMakeLists.txt b/src/cpp/microstrain/common/CMakeLists.txt index 7caf0ed9d..8ff7dd37f 100644 --- a/src/cpp/microstrain/common/CMakeLists.txt +++ b/src/cpp/microstrain/common/CMakeLists.txt @@ -14,11 +14,11 @@ target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${MICROSTRAIN if(MICROSTRAIN_USE_STD_SPAN) - target_compile_options(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_USE_STD_SPAN=1") + target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_USE_STD_SPAN=1") endif() if(MICROSTRAIN_USE_STD_ENDIAN) - target_compile_options(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_USE_STD_ENDIAN=1") + target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_USE_STD_ENDIAN=1") endif() # diff --git a/src/cpp/microstrain/common/index.hpp b/src/cpp/microstrain/common/index.hpp index 888ecd3ed..22c97e2eb 100644 --- a/src/cpp/microstrain/common/index.hpp +++ b/src/cpp/microstrain/common/index.hpp @@ -2,6 +2,7 @@ #include #include +#include namespace microstrain { @@ -27,7 +28,7 @@ namespace microstrain class Index { private: - unsigned int INVALID = -1U; + unsigned int INVALID = UINT_MAX; public: constexpr explicit Index(unsigned int index) : m_index(index) {} diff --git a/src/cpp/microstrain/common/serialization/readwrite.hpp b/src/cpp/microstrain/common/serialization/readwrite.hpp index 0c2d35dc1..66697534e 100644 --- a/src/cpp/microstrain/common/serialization/readwrite.hpp +++ b/src/cpp/microstrain/common/serialization/readwrite.hpp @@ -16,23 +16,18 @@ //#include //#endif -#if MICROSTRAIN_USE_STD_ENDIAN +#ifdef MICROSTRAIN_USE_STD_ENDIAN #include -namespace microstrain -{ -namespace serialization +namespace microstrain::serialization { using Endian = std::endian; -} -} +} // namespace microstrain::serialization -#else +#else // MICROSTRAIN_USE_STD_ENDIAN -namespace microstrain -{ -namespace serialization +namespace microstrain::serialization { enum class Endian @@ -42,14 +37,11 @@ enum class Endian //native = little, }; -} -} +} // namespace microstrain::serialization -#endif +#endif // MICROSTRAIN_USE_STD_ENDIAN -namespace microstrain -{ -namespace serialization +namespace microstrain::serialization { // @@ -202,5 +194,4 @@ T read(const uint8_t* buffer) return value; } -} // namespace serialization -} // namespace microstrain +} // namespace microstrain::serialization diff --git a/src/cpp/microstrain/common/span.hpp b/src/cpp/microstrain/common/span.hpp index d90294aaa..4976162ab 100644 --- a/src/cpp/microstrain/common/span.hpp +++ b/src/cpp/microstrain/common/span.hpp @@ -1,6 +1,6 @@ #pragma once -#if MICROSTRAIN_USE_STD_SPAN +#ifdef MICROSTRAIN_USE_STD_SPAN #include @@ -12,7 +12,7 @@ namespace microstrain template using Span = std::span; -} +} // namespace microstrain #else // MICROSTRAIN_USE_STD_SPAN @@ -92,6 +92,6 @@ struct Span }; -} // namespace microstrain +} // namespace microstrain #endif // MICROSTRAIN_USE_STD_SPAN diff --git a/src/cpp/mip/metadata/mip_all_definitions.hpp b/src/cpp/mip/metadata/mip_all_definitions.hpp index ce3a6185f..1c6ff9dc9 100644 --- a/src/cpp/mip/metadata/mip_all_definitions.hpp +++ b/src/cpp/mip/metadata/mip_all_definitions.hpp @@ -17,37 +17,37 @@ namespace mip::metadata { static constexpr inline std::initializer_list< const std::initializer_list* > ALL_COMMANDS = { - &ALL_COMMANDS_3DM, - &ALL_COMMANDS_AIDING, - &ALL_COMMANDS_BASE, - &ALL_COMMANDS_FILTER, - &ALL_COMMANDS_GNSS, - &ALL_COMMANDS_RTK, - &ALL_COMMANDS_SYSTEM, + &COMMANDS_3DM, + &COMMANDS_AIDING, + &COMMANDS_BASE, + &COMMANDS_FILTER, + &COMMANDS_GNSS, + &COMMANDS_RTK, + &COMMANDS_SYSTEM, }; static constexpr inline std::initializer_list< const std::initializer_list* > ALL_DATA = { - &ALL_DATA_FILTER, - &ALL_DATA_GNSS, - &ALL_DATA_SENSOR, - &ALL_DATA_SHARED, - &ALL_DATA_SYSTEM, + &DATA_FILTER, + &DATA_GNSS, + &DATA_SENSOR, + &DATA_SHARED, + &DATA_SYSTEM, }; static constexpr inline std::initializer_list< const std::initializer_list< const FieldInfo* >* > ALL_FIELDS = { // Commands - &ALL_COMMANDS_3DM, - &ALL_COMMANDS_AIDING, - &ALL_COMMANDS_BASE, - &ALL_COMMANDS_FILTER, - &ALL_COMMANDS_GNSS, - &ALL_COMMANDS_RTK, - &ALL_COMMANDS_SYSTEM, + &COMMANDS_3DM, + &COMMANDS_AIDING, + &COMMANDS_BASE, + &COMMANDS_FILTER, + &COMMANDS_GNSS, + &COMMANDS_RTK, + &COMMANDS_SYSTEM, // Data - &ALL_DATA_FILTER, - &ALL_DATA_GNSS, - &ALL_DATA_SENSOR, - &ALL_DATA_SHARED, - &ALL_DATA_SYSTEM, + &DATA_FILTER, + &DATA_GNSS, + &DATA_SENSOR, + &DATA_SHARED, + &DATA_SYSTEM, }; } // namespace mip::metadata From 3ca5681b5667ad3aef62c6d95422a442d9ae578f Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 20 Sep 2024 13:07:54 -0400 Subject: [PATCH 118/147] Fixed C++ standard issues Setting the C++ standard to a desired value (20), CMake will decay to latest supported if 20 isn't supported by the compiler --- CMakeLists.txt | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 253f6b509..ccf4d73b2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,9 +1,7 @@ cmake_minimum_required(VERSION 3.12) -set(CMAKE_CXX_STANDARD 11) -set(CMAKE_CXX_STANDARD_REQUIRED ON) +set(CMAKE_CXX_STANDARD 20) # CMake decays this to the highest supported by the compiler set(CMAKE_C_STANDARD 11) -set(CMAKE_C_STANDARD_REQUIRED ON) project( "MIP_SDK" From 4f0137d7f7e9dd340b95c323a89c1dbd4b9bb294 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 20 Sep 2024 13:14:21 -0400 Subject: [PATCH 119/147] Fixes for compiling metadata with c++17 and switch std::span to microstrain::Span --- src/cpp/microstrain/common/span.hpp | 15 +- src/cpp/mip/metadata/definitions/common.hpp | 260 ++++++++++---------- src/cpp/mip/metadata/mip_meta_utils.hpp | 13 +- src/cpp/mip/metadata/mip_metadata.hpp | 8 +- src/cpp/mip/metadata/mip_structures.hpp | 10 +- src/cpp/mip/mip_field.hpp | 10 +- 6 files changed, 167 insertions(+), 149 deletions(-) diff --git a/src/cpp/microstrain/common/span.hpp b/src/cpp/microstrain/common/span.hpp index d90294aaa..4d6ac1bab 100644 --- a/src/cpp/microstrain/common/span.hpp +++ b/src/cpp/microstrain/common/span.hpp @@ -54,6 +54,11 @@ struct Span [[nodiscard]] constexpr size_t size() const noexcept { return extent; } [[nodiscard]] constexpr bool empty() const noexcept { return extent == 0; } + [[nodiscard]] constexpr Span subspan(size_t index, size_t length) const { return {m_ptr+index, length}; } + [[nodiscard]] constexpr Span subspan(size_t index) const { return {m_ptr+index, extent-index}; } + template + [[nodiscard]] constexpr Span subspan() const { return {m_ptr+Offset}; } + private: const pointer m_ptr = nullptr; }; @@ -70,7 +75,10 @@ struct Span using const_pointer = const T*; using const_reference = const T&; - Span(pointer ptr, size_t cnt) : m_ptr(ptr), m_cnt(cnt) {} + constexpr Span() = default; + constexpr Span(pointer ptr, size_t cnt) : m_ptr(ptr), m_cnt(cnt) {} + template + constexpr Span(const T (&arr)[N]) : m_ptr(arr), m_cnt(N) {} constexpr pointer begin() const noexcept { return m_ptr; } constexpr pointer end() const noexcept { return m_ptr+m_cnt; } @@ -86,6 +94,11 @@ struct Span [[nodiscard]] constexpr size_t size() const noexcept { return m_cnt; } [[nodiscard]] constexpr bool empty() const noexcept { return m_cnt == 0; } + [[nodiscard]] constexpr Span subspan(size_t index, size_t length) const { return {m_ptr+index, length}; } + [[nodiscard]] constexpr Span subspan(size_t index) const { return {m_ptr+index, m_cnt-index}; } + template + [[nodiscard]] constexpr Span subspan() const { return {m_ptr+Offset, Count}; } + private: pointer const m_ptr = nullptr; size_t const m_cnt = 0; diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index c6cdc36f1..062b9e59b 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -16,43 +16,43 @@ struct MetadataFor static constexpr inline EnumInfo::Entry entries[] = { { - .value = CmdResult::ACK_OK, - .name = "OK", - .docs = "Command completed successfully", + /*.value =*/ CmdResult::ACK_OK, + /*.name =*/ "OK", + /*.docs =*/ "Command completed successfully", }, { - .value = CmdResult::NACK_COMMAND_UNKNOWN, - .name = "Unknown Command", - .docs = "The device did not recognize the command", + /*.value =*/ CmdResult::NACK_COMMAND_UNKNOWN, + /*.name =*/ "Unknown Command", + /*.docs =*/ "The device did not recognize the command", }, { - .value = CmdResult::NACK_INVALID_CHECKSUM, - .name = "Invalid Checksum", - .docs = "An packet with an invalid checksum was received by the device", + /*.value =*/ CmdResult::NACK_INVALID_CHECKSUM, + /*.name =*/ "Invalid Checksum", + /*.docs =*/ "An packet with an invalid checksum was received by the device", }, { - .value = CmdResult::NACK_INVALID_PARAM, - .name = "Invalid Parameter", - .docs = "One or more parameters to the command were not valid", + /*.value =*/ CmdResult::NACK_INVALID_PARAM, + /*.name =*/ "Invalid Parameter", + /*.docs =*/ "One or more parameters to the command were not valid", }, { - .value = CmdResult::NACK_COMMAND_FAILED, - .name = "Command Failed", - .docs = "The device could not complete the command", + /*.value =*/ CmdResult::NACK_COMMAND_FAILED, + /*.name =*/ "Command Failed", + /*.docs =*/ "The device could not complete the command", }, { - .value = CmdResult::NACK_COMMAND_TIMEOUT, - .name = "Device Timeout", - .docs = "The device reported a timeout condition", + /*.value =*/ CmdResult::NACK_COMMAND_TIMEOUT, + /*.name =*/ "Device Timeout", + /*.docs =*/ "The device reported a timeout condition", }, // Status codes not represented here as they don't come from the device. }; static constexpr inline EnumInfo value = { - .name = "CmdResult", - .docs = "Acknowledgement/reply code from the device after a command is issued", - .type = Type::U8, - .entries = entries, + /*.name =*/ "CmdResult", + /*.docs =*/ "Acknowledgement/reply code from the device after a command is issued", + /*.type =*/ Type::U8, + /*.entries =*/ entries, }; }; @@ -75,22 +75,22 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - .name = "cmd_field_desc", - .docs = "The field descriptor of the command this field acknowledges.", - .type = {Type::U8}, - .accessor = utils::access, - .attributes = NO_FUNCTIONS, - .count = 1, - .condition = {}, + /*.name =*/ "cmd_field_desc", + /*.docs =*/ "The field descriptor of the command this field acknowledges.", + /*.type =*/ {Type::U8}, + /*.accessor =*/ utils::access, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 1, + /*.condition =*/ {}, }, { - .name = "result", - .docs = "Result of the command.", - .type = {Type::ENUM, &MetadataFor::value}, - .accessor = utils::access, - .attributes = NO_FUNCTIONS, - .count = 1, - .condition = {}, + /*.name =*/ "result", + /*.docs =*/ "Result of the command.", + /*.type =*/ {Type::ENUM, &MetadataFor::value}, + /*.accessor =*/ utils::access, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 1, + /*.condition =*/ {}, }, }; @@ -113,30 +113,30 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - .name = "descriptor", - .docs = "MIP data descriptor", - .type = {Type::U8}, - .accessor = utils::access, - .attributes = NO_FUNCTIONS, - .count = 1, - .condition = {}, + /*.name =*/ "descriptor", + /*.docs =*/ "MIP data descriptor", + /*.type =*/ {Type::U8}, + /*.accessor =*/ utils::access, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 1, + /*.condition =*/ {}, }, { - .name = "decimation", - .docs = "Decimation from the base rate", - .type = {Type::U16}, - .accessor = utils::access, - .attributes = NO_FUNCTIONS, - .count = 1, - .condition = {}, + /*.name =*/ "decimation", + /*.docs =*/ "Decimation from the base rate", + /*.type =*/ {Type::U16}, + /*.accessor =*/ utils::access, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 1, + /*.condition =*/ {}, }, }; static constexpr inline StructInfo value = { - .name = "DescriptorRate", - .title = "Descriptor Rate", - .docs = "Descriptor rate information", - .parameters = parameters, + /*.name =*/ "DescriptorRate", + /*.title =*/ "Descriptor Rate", + /*.docs =*/ "Descriptor rate information", + /*.parameters =*/ parameters, }; }; @@ -148,89 +148,89 @@ struct MetadataFor> static constexpr inline ParameterInfo parameters[] = { { - .name = "x", - .docs = "X axis", - .type = {utils::ParamType::value}, - .accessor = nullptr, - .attributes = NO_FUNCTIONS, - .count = 1, - .condition = {}, + /*.name =*/ "x", + /*.docs =*/ "X axis", + /*.type =*/ {utils::ParamType::value}, + /*.accessor =*/ nullptr, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 1, + /*.condition =*/ {}, }, { - .name = "y", - .docs = "Y axis", - .type = {utils::ParamType::value}, - .accessor = nullptr, - .attributes = NO_FUNCTIONS, - .count = 1, - .condition = {}, + /*.name =*/ "y", + /*.docs =*/ "Y axis", + /*.type =*/ {utils::ParamType::value}, + /*.accessor =*/ nullptr, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 1, + /*.condition =*/ {}, }, { - .name = "z", - .docs = "Z axis", - .type = {utils::ParamType::value}, - .accessor = nullptr, - .attributes = NO_FUNCTIONS, - .count = 1, - .condition = {}, + /*.name =*/ "z", + /*.docs =*/ "Z axis", + /*.type =*/ {utils::ParamType::value}, + /*.accessor =*/ nullptr, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 1, + /*.condition =*/ {}, }, { - .name = "w", - .docs = "W axis", - .type = {utils::ParamType::value}, - .accessor = nullptr, - .attributes = NO_FUNCTIONS, - .count = 1, - .condition = {}, + /*.name =*/ "w", + /*.docs =*/ "W axis", + /*.type =*/ {utils::ParamType::value}, + /*.accessor =*/ nullptr, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 1, + /*.condition =*/ {}, }, }; static constexpr inline StructInfo values_f[3] = { { - .name = "Vector2f", - .title = "Vector2f", - .docs = "2-dimensional vector of floats", - .parameters = {parameters, 2} + /*.name =*/ "Vector2f", + /*.title =*/ "Vector2f", + /*.docs =*/ "2-dimensional vector of floats", + /*.parameters =*/ {parameters, 2} }, { - .name = "Vector3f", - .title = "Vector3f", - .docs = "3-dimensional vector of floats", - .parameters = {parameters, 3} + /*.name =*/ "Vector3f", + /*.title =*/ "Vector3f", + /*.docs =*/ "3-dimensional vector of floats", + /*.parameters =*/ {parameters, 3} }, { - .name = "Vector4f", - .title = "Vector4f", - .docs = "4-dimensional vector of floats", - .parameters = {parameters, 4} + /*.name =*/ "Vector4f", + /*.title =*/ "Vector4f", + /*.docs =*/ "4-dimensional vector of floats", + /*.parameters =*/ {parameters, 4} }, }; static constexpr inline StructInfo values_d[3] = { { - .name = "Vector2d", - .title = "Vector2d", - .docs = "2-dimensional vector of doubles", - .parameters = {parameters, 2} + /*.name =*/ "Vector2d", + /*.title =*/ "Vector2d", + /*.docs =*/ "2-dimensional vector of doubles", + /*.parameters =*/ {parameters, 2} }, { - .name = "Vector3d", - .title = "Vector3d", - .docs = "3-dimensional vector of doubles", - .parameters = {parameters, 3} + /*.name =*/ "Vector3d", + /*.title =*/ "Vector3d", + /*.docs =*/ "3-dimensional vector of doubles", + /*.parameters =*/ {parameters, 3} }, { - .name = "Vector4d", - .title = "Vector4d", - .docs = "4-dimensional vector of doubles", - .parameters = {parameters, 4} + /*.name =*/ "Vector4d", + /*.title =*/ "Vector4d", + /*.docs =*/ "4-dimensional vector of doubles", + /*.parameters =*/ {parameters, 4} }, }; - static_assert(std::is_floating_point_v, "Expected either float or double"); + static_assert(std::is_floating_point::value, "Expected either float or double"); static_assert(N >= 2 && N <= 4, "N should be in the range [2,4]."); - static constexpr inline const StructInfo& value = std::is_same_v ? values_d[N-2] : values_f[N-2]; + static constexpr inline const StructInfo& value = std::is_same::value ? values_d[N-2] : values_f[N-2]; }; @@ -241,21 +241,21 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - .name = "m", - .docs = "Matrix data", - .type = {Type::FLOAT}, - .accessor = nullptr, - .attributes = NO_FUNCTIONS, - .count = 3, - .condition = {}, + /*.name =*/ "m", + /*.docs =*/ "Matrix data", + /*.type =*/ {Type::FLOAT}, + /*.accessor =*/ nullptr, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 3, + /*.condition =*/ {}, }, }; static constexpr inline StructInfo value = { - .name = "Matrix3f", - .title = "3x3 Float Matrix", - .docs = "Represents a 3D matrix of floats.", - .parameters = parameters, + /*.name =*/ "Matrix3f", + /*.title =*/ "3x3 Float Matrix", + /*.docs =*/ "Represents a 3D matrix of floats.", + /*.parameters =*/ parameters, }; }; @@ -266,21 +266,21 @@ struct MetadataFor static constexpr inline ParameterInfo parameters[] = { { - .name = "m", - .docs = "Matrix data", - .type = {Type::DOUBLE}, - .accessor = nullptr, - .attributes = NO_FUNCTIONS, - .count = 3, - .condition = {}, + /*.name =*/ "m", + /*.docs =*/ "Matrix data", + /*.type =*/ {Type::DOUBLE}, + /*.accessor =*/ nullptr, + /*.attributes =*/ NO_FUNCTIONS, + /*.count =*/ 3, + /*.condition =*/ {}, }, }; static constexpr inline StructInfo value = { - .name = "Matrix3f", - .title = "3x3 Double Matrix", - .docs = "Represents a 3D matrix of doubles.", - .parameters = parameters, + /*.name =*/ "Matrix3f", + /*.title =*/ "3x3 Double Matrix", + /*.docs =*/ "Represents a 3D matrix of doubles.", + /*.parameters =*/ parameters, }; }; diff --git a/src/cpp/mip/metadata/mip_meta_utils.hpp b/src/cpp/mip/metadata/mip_meta_utils.hpp index ae0f80121..9d48d053c 100644 --- a/src/cpp/mip/metadata/mip_meta_utils.hpp +++ b/src/cpp/mip/metadata/mip_meta_utils.hpp @@ -52,16 +52,21 @@ template<> struct ParamEnum { using type = double; }; // Gets a void pointer to the member identified by Ptr, given an // instance of field passed by void pointer. -template +/*template void* access(void* p) { return &(static_cast(p)->*Ptr); } -template +template void* access(void* p) { - return static_cast(p)->*Ptr; -} + Field* f = static_cast(p); + auto& param = f->*Ptr; + return ¶m; +}*/ + +template +void* access(void* p); } // namespace mip::metadata diff --git a/src/cpp/mip/metadata/mip_metadata.hpp b/src/cpp/mip/metadata/mip_metadata.hpp index 03a1c6cd4..b48ee9b28 100644 --- a/src/cpp/mip/metadata/mip_metadata.hpp +++ b/src/cpp/mip/metadata/mip_metadata.hpp @@ -29,10 +29,10 @@ struct MetadataFor }; static constexpr inline EnumInfo value = { - .name = "FunctionSelector", - .docs = "", - .type = Type::U8, - .entries = entries, + /*.name =*/ "FunctionSelector", + /*.docs =*/ "", + /*.type =*/ Type::U8, + /*.entries =*/ entries, }; }; diff --git a/src/cpp/mip/metadata/mip_structures.hpp b/src/cpp/mip/metadata/mip_structures.hpp index f47460797..25d94fd3e 100644 --- a/src/cpp/mip/metadata/mip_structures.hpp +++ b/src/cpp/mip/metadata/mip_structures.hpp @@ -1,14 +1,16 @@ #pragma once #include +#include #include -#include #include namespace mip::metadata { + template + using Span = microstrain::Span; //struct EnumInfo; //struct BitfieldInfo; @@ -72,7 +74,8 @@ struct EnumInfo const char* name = nullptr; const char* docs = nullptr; Type type = Type::NONE; - std::span entries; + + Span entries; }; struct BitfieldInfo : public EnumInfo {}; @@ -170,7 +173,8 @@ struct StructInfo const char* name = nullptr; const char* title = nullptr; const char* docs = nullptr; - std::span parameters; + + Span parameters; }; struct UnionInfo : public StructInfo {}; diff --git a/src/cpp/mip/mip_field.hpp b/src/cpp/mip/mip_field.hpp index ca3b9bfc0..a7950563e 100644 --- a/src/cpp/mip/mip_field.hpp +++ b/src/cpp/mip/mip_field.hpp @@ -3,15 +3,13 @@ #include "mip_descriptors.hpp" #include "mip_serialization.hpp" +#include + #include #include #include -#if __cpp_lib_span >= 202002L -#include -#endif - namespace mip { @@ -60,9 +58,7 @@ class FieldView : public C::mip_field_view uint8_t operator[](unsigned int index) const { return payload(index); } -#if __cpp_lib_span >= 202002L - std::span payloadSpan() const { return {payload(), payloadLength()}; } -#endif + microstrain::Span payloadSpan() const { return {payload(), payloadLength()}; } ///@copydoc mip_field_is_valid bool isValid() const { return C::mip_field_is_valid(this); } From 43f418da2ef3e2f99e857cc88003de161052173b Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 20 Sep 2024 13:18:12 -0400 Subject: [PATCH 120/147] Remove accessor method for now due to issues. --- .../mip/metadata/definitions/commands_3dm.hpp | 452 ++++++++-------- .../metadata/definitions/commands_aiding.hpp | 128 ++--- .../metadata/definitions/commands_base.hpp | 38 +- .../metadata/definitions/commands_filter.hpp | 400 +++++++------- .../metadata/definitions/commands_gnss.hpp | 38 +- .../mip/metadata/definitions/commands_rtk.hpp | 44 +- .../metadata/definitions/commands_system.hpp | 4 +- .../mip/metadata/definitions/data_filter.hpp | 312 +++++------ .../mip/metadata/definitions/data_gnss.hpp | 492 +++++++++--------- .../mip/metadata/definitions/data_sensor.hpp | 64 +-- .../mip/metadata/definitions/data_shared.hpp | 26 +- .../mip/metadata/definitions/data_system.hpp | 12 +- 12 files changed, 1005 insertions(+), 1005 deletions(-) diff --git a/src/cpp/mip/metadata/definitions/commands_3dm.hpp b/src/cpp/mip/metadata/definitions/commands_3dm.hpp index 5d661329c..abf2df659 100644 --- a/src/cpp/mip/metadata/definitions/commands_3dm.hpp +++ b/src/cpp/mip/metadata/definitions/commands_3dm.hpp @@ -20,7 +20,7 @@ struct MetadataFor /* .name = */ "suppress_ack", /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -29,7 +29,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors in the descriptor list.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -38,7 +38,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "Descriptor list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, @@ -67,7 +67,7 @@ struct MetadataFor /* .name = */ "suppress_ack", /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -76,7 +76,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors in the descriptor list.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -85,7 +85,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "Descriptor list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, @@ -114,7 +114,7 @@ struct MetadataFor /* .name = */ "suppress_ack", /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -123,7 +123,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors in the format list.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -132,7 +132,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {83, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, @@ -161,7 +161,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -170,7 +170,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, @@ -200,7 +200,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -209,7 +209,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, @@ -238,7 +238,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -247,7 +247,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, @@ -277,7 +277,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -286,7 +286,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "Descriptor format list.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, @@ -315,7 +315,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -324,7 +324,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, @@ -354,7 +354,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -363,7 +363,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(0) /* num_descriptors */}, /* .condition = */ {}, @@ -392,7 +392,7 @@ struct MetadataFor /* .name = */ "rate", /* .docs = */ "[hz]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -438,7 +438,7 @@ struct MetadataFor /* .name = */ "rate", /* .docs = */ "[hz]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -484,7 +484,7 @@ struct MetadataFor /* .name = */ "rate", /* .docs = */ "[hz]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -530,7 +530,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "Data descriptor set. Must be supported.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -539,7 +539,7 @@ struct MetadataFor /* .name = */ "suppress_ack", /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -548,7 +548,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors in the format list.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -557,7 +557,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "Descriptor format list.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(2) /* num_descriptors */}, /* .condition = */ {}, @@ -586,7 +586,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "Echoes the parameter in the command.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -595,7 +595,7 @@ struct MetadataFor /* .name = */ "rate", /* .docs = */ "Base rate in Hz (0 = variable, unknown, or user-defined rate. Data will be sent when received).", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -624,7 +624,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "This is the data descriptor set. It must be a supported descriptor.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -653,7 +653,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "Echoes the descriptor set from the command.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -662,7 +662,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors in the list.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -671,7 +671,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "List of descriptors and decimations.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, @@ -701,7 +701,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "Data descriptor set. Must be supported. When function is SAVE, LOAD, or DEFAULT, can be 0 to apply to all descriptor sets.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -710,7 +710,7 @@ struct MetadataFor /* .name = */ "num_descriptors", /* .docs = */ "Number of descriptors (limited by payload size)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -719,7 +719,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "List of descriptors and decimations.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {82, microstrain::Index(1) /* num_descriptors */}, /* .condition = */ {}, @@ -796,7 +796,7 @@ struct MetadataFor /* .name = */ "message_id", /* .docs = */ "NMEA sentence type.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -805,7 +805,7 @@ struct MetadataFor /* .name = */ "talker_id", /* .docs = */ "NMEA talker ID. Ignored for proprietary sentences.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -814,7 +814,7 @@ struct MetadataFor /* .name = */ "source_desc_set", /* .docs = */ "Data descriptor set where the data will be sourced. Available options depend on the sentence.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -823,7 +823,7 @@ struct MetadataFor /* .name = */ "decimation", /* .docs = */ "Decimation from the base rate for source_desc_set. Frequency is limited to 10 Hz or the base rate, whichever is lower. Must be 0 when polling.", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -848,7 +848,7 @@ struct MetadataFor /* .name = */ "suppress_ack", /* .docs = */ "Suppress the usual ACK/NACK reply.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -857,7 +857,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Number of format entries (limited by payload size)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -866,7 +866,7 @@ struct MetadataFor /* .name = */ "format_entries", /* .docs = */ "List of format entries.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {40, microstrain::Index(1) /* count */}, /* .condition = */ {}, @@ -895,7 +895,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Number of format entries (limited by payload size)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -904,7 +904,7 @@ struct MetadataFor /* .name = */ "format_entries", /* .docs = */ "List of format entries.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {40, microstrain::Index(0) /* count */}, /* .condition = */ {}, @@ -934,7 +934,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Number of format entries (limited by payload size)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -943,7 +943,7 @@ struct MetadataFor /* .name = */ "format_entries", /* .docs = */ "List of format entries.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {40, microstrain::Index(0) /* count */}, /* .condition = */ {}, @@ -994,7 +994,7 @@ struct MetadataFor /* .name = */ "baud", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1024,7 +1024,7 @@ struct MetadataFor /* .name = */ "baud", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1073,7 +1073,7 @@ struct MetadataFor /* .name = */ "action", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1082,7 +1082,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "Reserved. Set to 0x00.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1111,7 +1111,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -1120,7 +1120,7 @@ struct MetadataFor /* .name = */ "enabled", /* .docs = */ "", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1150,7 +1150,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "The descriptor set of the stream to control. When function is SAVE, LOAD, or DEFAULT, can be ALL_STREAMS(0) to apply to all descriptor sets.\nOn Generation 5 products, this must be one of the above legacy constants.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -1159,7 +1159,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "True or false to enable or disable the stream.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1229,7 +1229,7 @@ struct MetadataFor /* .name = */ "constellation_id", /* .docs = */ "Constellation ID", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -1238,7 +1238,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "Enable/Disable constellation", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -1247,7 +1247,7 @@ struct MetadataFor /* .name = */ "reserved_channels", /* .docs = */ "Minimum number of channels reserved for this constellation", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -1256,7 +1256,7 @@ struct MetadataFor /* .name = */ "max_channels", /* .docs = */ "Maximum number of channels to use for this constallation", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -1265,7 +1265,7 @@ struct MetadataFor /* .name = */ "option_flags", /* .docs = */ "Constellation option Flags", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -1290,7 +1290,7 @@ struct MetadataFor /* .name = */ "max_channels_available", /* .docs = */ "Maximum channels available", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1299,7 +1299,7 @@ struct MetadataFor /* .name = */ "max_channels_use", /* .docs = */ "Maximum channels to use", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1308,7 +1308,7 @@ struct MetadataFor /* .name = */ "config_count", /* .docs = */ "Number of constellation configurations", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1317,7 +1317,7 @@ struct MetadataFor /* .name = */ "settings", /* .docs = */ "Constellation Settings", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(2) /* config_count */}, /* .condition = */ {}, @@ -1347,7 +1347,7 @@ struct MetadataFor /* .name = */ "max_channels", /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1356,7 +1356,7 @@ struct MetadataFor /* .name = */ "config_count", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1365,7 +1365,7 @@ struct MetadataFor /* .name = */ "settings", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(1) /* config_count */}, /* .condition = */ {}, @@ -1414,7 +1414,7 @@ struct MetadataFor /* .name = */ "enable_sbas", /* .docs = */ "0 - SBAS Disabled, 1 - SBAS enabled", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1423,7 +1423,7 @@ struct MetadataFor /* .name = */ "sbas_options", /* .docs = */ "SBAS options, see definition", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1432,7 +1432,7 @@ struct MetadataFor /* .name = */ "num_included_prns", /* .docs = */ "Number of SBAS PRNs to include in search (0 = include all)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1441,7 +1441,7 @@ struct MetadataFor /* .name = */ "included_prns", /* .docs = */ "List of specific SBAS PRNs to search for", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {39, microstrain::Index(2) /* num_included_prns */}, /* .condition = */ {}, @@ -1471,7 +1471,7 @@ struct MetadataFor /* .name = */ "enable_sbas", /* .docs = */ "0 - SBAS Disabled, 1 - SBAS enabled", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1480,7 +1480,7 @@ struct MetadataFor /* .name = */ "sbas_options", /* .docs = */ "SBAS options, see definition", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1489,7 +1489,7 @@ struct MetadataFor /* .name = */ "num_included_prns", /* .docs = */ "Number of SBAS PRNs to include in search (0 = include all)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1498,7 +1498,7 @@ struct MetadataFor /* .name = */ "included_prns", /* .docs = */ "List of specific SBAS PRNs to search for", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {39, microstrain::Index(2) /* num_included_prns */}, /* .condition = */ {}, @@ -1546,7 +1546,7 @@ struct MetadataFor /* .name = */ "option", /* .docs = */ "Assisted fix options", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1555,7 +1555,7 @@ struct MetadataFor /* .name = */ "flags", /* .docs = */ "Assisted fix flags (set to 0xFF)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1585,7 +1585,7 @@ struct MetadataFor /* .name = */ "option", /* .docs = */ "Assisted fix options", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1594,7 +1594,7 @@ struct MetadataFor /* .name = */ "flags", /* .docs = */ "Assisted fix flags (set to 0xFF)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1623,7 +1623,7 @@ struct MetadataFor /* .name = */ "tow", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1632,7 +1632,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Weeks since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1641,7 +1641,7 @@ struct MetadataFor /* .name = */ "accuracy", /* .docs = */ "Accuracy of time information [seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1671,7 +1671,7 @@ struct MetadataFor /* .name = */ "tow", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1680,7 +1680,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Weeks since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1689,7 +1689,7 @@ struct MetadataFor /* .name = */ "accuracy", /* .docs = */ "Accuracy of time information [seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1718,7 +1718,7 @@ struct MetadataFor /* .name = */ "target_descriptor", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -1727,7 +1727,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "True if the filter is currently enabled.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1736,7 +1736,7 @@ struct MetadataFor /* .name = */ "manual", /* .docs = */ "True if the filter cutoff was manually configured.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1745,7 +1745,7 @@ struct MetadataFor /* .name = */ "frequency", /* .docs = */ "The cutoff frequency of the filter. If the filter is in\nauto mode, this value is unspecified.", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1754,7 +1754,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "Reserved and must be ignored.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1784,7 +1784,7 @@ struct MetadataFor /* .name = */ "target_descriptor", /* .docs = */ "Field descriptor of filtered quantity within the Sensor data set.\nSupported values are accel (0x04), gyro (0x05), mag (0x06), and\npressure (0x17), provided the data is supported by the device.\nExcept with the READ function selector, this can be 0 to apply to all of the above quantities.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -1793,7 +1793,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "The target data will be filtered if this is true.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1802,7 +1802,7 @@ struct MetadataFor /* .name = */ "manual", /* .docs = */ "If false, the cutoff frequency is set to half of the\nstreaming rate as configured by the message format command.\nOtherwise, the cutoff frequency is set according to the\nfollowing 'frequency' parameter.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1811,7 +1811,7 @@ struct MetadataFor /* .name = */ "frequency", /* .docs = */ "-3dB cutoff frequency in Hz. Will not affect filtering if 'manual' is false.", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1820,7 +1820,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "Reserved, set to 0x00.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1871,7 +1871,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1901,7 +1901,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2005,7 +2005,7 @@ struct MetadataFor /* .name = */ "pin", /* .docs = */ "GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2014,7 +2014,7 @@ struct MetadataFor /* .name = */ "feature", /* .docs = */ "Determines how the pin will be used.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2023,7 +2023,7 @@ struct MetadataFor /* .name = */ "behavior", /* .docs = */ "Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.)", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2032,7 +2032,7 @@ struct MetadataFor /* .name = */ "pin_mode", /* .docs = */ "GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2062,7 +2062,7 @@ struct MetadataFor /* .name = */ "pin", /* .docs = */ "GPIO pin number counting from 1. For save, load, and default function selectors, this can be 0 to select all pins.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2071,7 +2071,7 @@ struct MetadataFor /* .name = */ "feature", /* .docs = */ "Determines how the pin will be used.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2080,7 +2080,7 @@ struct MetadataFor /* .name = */ "behavior", /* .docs = */ "Select an appropriate value from the enumeration based on the selected feature (e.g. for PPS, select one of the values prefixed with PPS_.)", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2089,7 +2089,7 @@ struct MetadataFor /* .name = */ "pin_mode", /* .docs = */ "GPIO configuration. May be restricted depending on device, pin, feature, and behavior. See device user manual.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2118,7 +2118,7 @@ struct MetadataFor /* .name = */ "pin", /* .docs = */ "GPIO pin number counting from 1. Cannot be 0.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2127,7 +2127,7 @@ struct MetadataFor /* .name = */ "state", /* .docs = */ "The pin state.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2157,7 +2157,7 @@ struct MetadataFor /* .name = */ "pin", /* .docs = */ "GPIO pin number counting from 1. Cannot be 0.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2166,7 +2166,7 @@ struct MetadataFor /* .name = */ "state", /* .docs = */ "The pin state.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2214,7 +2214,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "Mode setting.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2223,7 +2223,7 @@ struct MetadataFor /* .name = */ "scaling", /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2232,7 +2232,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "Uncertainty in encoder counts to distance translation (1-sigma value) [m/m].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2262,7 +2262,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "Mode setting.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2271,7 +2271,7 @@ struct MetadataFor /* .name = */ "scaling", /* .docs = */ "Encoder pulses per meter of distance traveled [pulses/m].\nDistance traveled is computed using the formula d = p / N * 2R * pi, where d is distance,\np is the number of pulses received, N is the encoder resolution, and R is the wheel radius.\nBy simplifying all of the parameters into one, the formula d = p / S is obtained, where s\nis the odometer scaling factor passed to this command. S is equivalent to N / (2R * pi) and\nhas units of pulses / meter. N is in units of 'A' pulses per revolution and R is in meters.\nMake this value negative if the odometer is mounted so that it rotates backwards.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2280,7 +2280,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "Uncertainty in encoder counts to distance translation (1-sigma value) [m/m].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2328,7 +2328,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "Trigger or action type, as defined in the respective setup command.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2337,7 +2337,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "This is the maximum number of instances supported for this type.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2362,7 +2362,7 @@ struct MetadataFor /* .name = */ "query", /* .docs = */ "Query type specified in the command.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2371,7 +2371,7 @@ struct MetadataFor /* .name = */ "max_instances", /* .docs = */ "Number of slots available. The 'instance' number for\nthe configuration or control commands must be between 1 and this value.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2380,7 +2380,7 @@ struct MetadataFor /* .name = */ "num_entries", /* .docs = */ "Number of supported types.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2389,7 +2389,7 @@ struct MetadataFor /* .name = */ "entries", /* .docs = */ "List of supported types.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(2) /* num_entries */}, /* .condition = */ {}, @@ -2418,7 +2418,7 @@ struct MetadataFor /* .name = */ "query", /* .docs = */ "What type of information to retrieve.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2468,7 +2468,7 @@ struct MetadataFor /* .name = */ "instance", /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2477,7 +2477,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2507,7 +2507,7 @@ struct MetadataFor /* .name = */ "instance", /* .docs = */ "Trigger instance to affect. 0 can be used to apply the mode to all\nconfigured triggers, except when the function selector is READ.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2516,7 +2516,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "How to change the trigger state. Except when instance is 0, the\ncorresponding trigger must be configured, i.e. not have type 0.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2565,7 +2565,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "Configured trigger type.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2574,7 +2574,7 @@ struct MetadataFor /* .name = */ "status", /* .docs = */ "Trigger status.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2599,7 +2599,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Number of entries requested. If requested_count was 0, this is the number of supported trigger slots.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2608,7 +2608,7 @@ struct MetadataFor /* .name = */ "triggers", /* .docs = */ "A list of the configured triggers. Entries are in the order requested, or in increasing order if count was 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {20, microstrain::Index(0) /* count */}, /* .condition = */ {}, @@ -2637,7 +2637,7 @@ struct MetadataFor /* .name = */ "requested_count", /* .docs = */ "Number of entries requested. If 0, requests all trigger slots.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2646,7 +2646,7 @@ struct MetadataFor /* .name = */ "requested_instances", /* .docs = */ "List of trigger instances to query.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {20, microstrain::Index(0) /* requested_count */}, /* .condition = */ {}, @@ -2675,7 +2675,7 @@ struct MetadataFor /* .name = */ "action_type", /* .docs = */ "Configured action type.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2684,7 +2684,7 @@ struct MetadataFor /* .name = */ "trigger_id", /* .docs = */ "Associated trigger instance.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2709,7 +2709,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Number of entries requested. If requested_count was 0, this is the number of supported action slots.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2718,7 +2718,7 @@ struct MetadataFor /* .name = */ "actions", /* .docs = */ "A list of the configured actions. Entries are in the order requested, or in increasing order if count was 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {20, microstrain::Index(0) /* count */}, /* .condition = */ {}, @@ -2747,7 +2747,7 @@ struct MetadataFor /* .name = */ "requested_count", /* .docs = */ "Number of entries requested. If 0, requests all action slots.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2756,7 +2756,7 @@ struct MetadataFor /* .name = */ "requested_instances", /* .docs = */ "List of action instances to query.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {20, microstrain::Index(0) /* requested_count */}, /* .condition = */ {}, @@ -2806,7 +2806,7 @@ struct MetadataFor /* .name = */ "pin", /* .docs = */ "GPIO pin number.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2815,7 +2815,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "How the pin state affects the trigger.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2859,7 +2859,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "Descriptor set of target data quantity.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2868,7 +2868,7 @@ struct MetadataFor /* .name = */ "field_desc", /* .docs = */ "Field descriptor of target data quantity.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2877,7 +2877,7 @@ struct MetadataFor /* .name = */ "param_id", /* .docs = */ "1-based index of the target parameter within the MIP field. E.g. for Scaled Accel (0x80,0x04) a value of 2 would represent the Y axis.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2886,7 +2886,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "Determines the type of comparison.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2895,7 +2895,7 @@ struct MetadataFor /* .name = */ "low_thres", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::WINDOW)} /* type == WINDOW */, @@ -2904,7 +2904,7 @@ struct MetadataFor /* .name = */ "int_thres", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::INTERVAL)} /* type == INTERVAL */, @@ -2913,7 +2913,7 @@ struct MetadataFor /* .name = */ "high_thres", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::WINDOW)} /* type == WINDOW */, @@ -2922,7 +2922,7 @@ struct MetadataFor /* .name = */ "interval", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(3) /* type */, static_cast(commands_3dm::EventTrigger::ThresholdParams::Type::INTERVAL)} /* type == INTERVAL */, @@ -2947,7 +2947,7 @@ struct MetadataFor /* .name = */ "logic_table", /* .docs = */ "The last column of a truth table describing the output given the state of each input.", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -2956,7 +2956,7 @@ struct MetadataFor /* .name = */ "input_triggers", /* .docs = */ "List of trigger IDs for inputs. Use 0 for unused inputs.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 4, /* .condition = */ {}, @@ -3002,7 +3002,7 @@ struct MetadataFor /* .name = */ "gpio", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* type */, static_cast(commands_3dm::EventTrigger::Type::GPIO)} /* type == GPIO */, @@ -3011,7 +3011,7 @@ struct MetadataFor /* .name = */ "threshold", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* type */, static_cast(commands_3dm::EventTrigger::Type::THRESHOLD)} /* type == THRESHOLD */, @@ -3020,7 +3020,7 @@ struct MetadataFor /* .name = */ "combination", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* type */, static_cast(commands_3dm::EventTrigger::Type::COMBINATION)} /* type == COMBINATION */, @@ -3045,7 +3045,7 @@ struct MetadataFor /* .name = */ "instance", /* .docs = */ "Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -3054,7 +3054,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "Type of trigger to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3063,7 +3063,7 @@ struct MetadataFor /* .name = */ "parameters", /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3093,7 +3093,7 @@ struct MetadataFor /* .name = */ "instance", /* .docs = */ "Trigger number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -3102,7 +3102,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "Type of trigger to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3111,7 +3111,7 @@ struct MetadataFor /* .name = */ "parameters", /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3163,7 +3163,7 @@ struct MetadataFor /* .name = */ "pin", /* .docs = */ "GPIO pin number.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -3172,7 +3172,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "Behavior of the pin.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -3197,7 +3197,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "MIP data descriptor set.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -3206,7 +3206,7 @@ struct MetadataFor /* .name = */ "decimation", /* .docs = */ "Decimation from the base rate.\nIf 0, a packet is emitted each time the trigger activates.\nOtherwise, packets will be streamed while the trigger is active.\nThe internal decimation counter is reset if the trigger deactivates.", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -3215,7 +3215,7 @@ struct MetadataFor /* .name = */ "num_fields", /* .docs = */ "Number of mip fields in the packet. Limited to 12.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -3224,7 +3224,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "List of field descriptors.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ {20, microstrain::Index(2) /* num_fields */}, /* .condition = */ {}, @@ -3269,7 +3269,7 @@ struct MetadataFor /* .name = */ "gpio", /* .docs = */ "Gpio parameters, if type == GPIO. Ignore otherwise.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(2) /* type */, static_cast(commands_3dm::EventAction::Type::GPIO)} /* type == GPIO */, @@ -3278,7 +3278,7 @@ struct MetadataFor /* .name = */ "message", /* .docs = */ "Message parameters, if type == MESSAGE. Ignore otherwise.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(2) /* type */, static_cast(commands_3dm::EventAction::Type::MESSAGE)} /* type == MESSAGE */, @@ -3303,7 +3303,7 @@ struct MetadataFor /* .name = */ "instance", /* .docs = */ "Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -3312,7 +3312,7 @@ struct MetadataFor /* .name = */ "trigger", /* .docs = */ "Trigger ID number.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3321,7 +3321,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "Type of action to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3330,7 +3330,7 @@ struct MetadataFor /* .name = */ "parameters", /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3360,7 +3360,7 @@ struct MetadataFor /* .name = */ "instance", /* .docs = */ "Action number. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all instances.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -3369,7 +3369,7 @@ struct MetadataFor /* .name = */ "trigger", /* .docs = */ "Trigger ID number.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3378,7 +3378,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "Type of action to configure.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3387,7 +3387,7 @@ struct MetadataFor /* .name = */ "parameters", /* .docs = */ "", /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3416,7 +3416,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "accelerometer bias in the sensor frame (x,y,z) [g]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3446,7 +3446,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "accelerometer bias in the sensor frame (x,y,z) [g]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3475,7 +3475,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3505,7 +3505,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3534,7 +3534,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "gyro bias in the sensor frame (x,y,z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3563,7 +3563,7 @@ struct MetadataFor /* .name = */ "averaging_time_ms", /* .docs = */ "Averaging time [milliseconds]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3592,7 +3592,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "hard iron offset in the sensor frame (x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3622,7 +3622,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "hard iron offset in the sensor frame (x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3651,7 +3651,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "soft iron matrix [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3681,7 +3681,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "soft iron matrix [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3710,7 +3710,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "If true, coning and sculling compensation is enabled.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3740,7 +3740,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "If true, coning and sculling compensation is enabled.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3769,7 +3769,7 @@ struct MetadataFor /* .name = */ "roll", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3778,7 +3778,7 @@ struct MetadataFor /* .name = */ "pitch", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3787,7 +3787,7 @@ struct MetadataFor /* .name = */ "yaw", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3817,7 +3817,7 @@ struct MetadataFor /* .name = */ "roll", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3826,7 +3826,7 @@ struct MetadataFor /* .name = */ "pitch", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3835,7 +3835,7 @@ struct MetadataFor /* .name = */ "yaw", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3864,7 +3864,7 @@ struct MetadataFor /* .name = */ "q", /* .docs = */ "Unit length quaternion representing transform [w, i, j, k]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3894,7 +3894,7 @@ struct MetadataFor /* .name = */ "q", /* .docs = */ "Unit length quaternion representing transform [w, i, j, k]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3923,7 +3923,7 @@ struct MetadataFor /* .name = */ "dcm", /* .docs = */ "3 x 3 direction cosine matrix, stored in row-major order", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3953,7 +3953,7 @@ struct MetadataFor /* .name = */ "dcm", /* .docs = */ "3 x 3 direction cosine matrix, stored in row-major order", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3982,7 +3982,7 @@ struct MetadataFor /* .name = */ "pitch_roll_enable", /* .docs = */ "Enable Pitch/Roll corrections", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3991,7 +3991,7 @@ struct MetadataFor /* .name = */ "heading_enable", /* .docs = */ "Enable Heading corrections (only available on devices with magnetometer)", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4000,7 +4000,7 @@ struct MetadataFor /* .name = */ "pitch_roll_time_constant", /* .docs = */ "Time constant associated with the pitch/roll corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4009,7 +4009,7 @@ struct MetadataFor /* .name = */ "heading_time_constant", /* .docs = */ "Time constant associated with the heading corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4039,7 +4039,7 @@ struct MetadataFor /* .name = */ "pitch_roll_enable", /* .docs = */ "Enable Pitch/Roll corrections", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4048,7 +4048,7 @@ struct MetadataFor /* .name = */ "heading_enable", /* .docs = */ "Enable Heading corrections (only available on devices with magnetometer)", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4057,7 +4057,7 @@ struct MetadataFor /* .name = */ "pitch_roll_time_constant", /* .docs = */ "Time constant associated with the pitch/roll corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4066,7 +4066,7 @@ struct MetadataFor /* .name = */ "heading_time_constant", /* .docs = */ "Time constant associated with the heading corrections [s]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4117,7 +4117,7 @@ struct MetadataFor /* .name = */ "sensor", /* .docs = */ "Which type of sensor will get the new range value.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -4126,7 +4126,7 @@ struct MetadataFor /* .name = */ "setting", /* .docs = */ "Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4156,7 +4156,7 @@ struct MetadataFor /* .name = */ "sensor", /* .docs = */ "Which type of sensor will get the new range value.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -4165,7 +4165,7 @@ struct MetadataFor /* .name = */ "setting", /* .docs = */ "Use the 3DM Get Calibrated Sensor Ranges (0x0C,0x53) command to determine this value.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4194,7 +4194,7 @@ struct MetadataFor /* .name = */ "setting", /* .docs = */ "The value used in the 3DM Sensor Range command and response.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -4203,7 +4203,7 @@ struct MetadataFor /* .name = */ "range", /* .docs = */ "The actual range value. Units depend on the sensor type.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -4228,7 +4228,7 @@ struct MetadataFor /* .name = */ "sensor", /* .docs = */ "The sensor type from the command.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -4237,7 +4237,7 @@ struct MetadataFor /* .name = */ "num_ranges", /* .docs = */ "Number of supported ranges.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4246,7 +4246,7 @@ struct MetadataFor /* .name = */ "ranges", /* .docs = */ "List of possible range settings.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(1) /* num_ranges */}, /* .condition = */ {}, @@ -4275,7 +4275,7 @@ struct MetadataFor /* .name = */ "sensor", /* .docs = */ "The sensor to query. Cannot be ALL.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -4304,7 +4304,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "Descriptor set of the quantity to be filtered.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -4313,7 +4313,7 @@ struct MetadataFor /* .name = */ "field_desc", /* .docs = */ "Field descriptor of the quantity to be filtered.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -4322,7 +4322,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "The filter will be enabled if this is true.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4331,7 +4331,7 @@ struct MetadataFor /* .name = */ "manual", /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4340,7 +4340,7 @@ struct MetadataFor /* .name = */ "frequency", /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4370,7 +4370,7 @@ struct MetadataFor /* .name = */ "desc_set", /* .docs = */ "Descriptor set of the quantity to be filtered.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -4379,7 +4379,7 @@ struct MetadataFor /* .name = */ "field_desc", /* .docs = */ "Field descriptor of the quantity to be filtered.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -4388,7 +4388,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "The filter will be enabled if this is true.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4397,7 +4397,7 @@ struct MetadataFor /* .name = */ "manual", /* .docs = */ "If false, the frequency parameter is ignored and the filter\nwill track to half of the configured message format frequency.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4406,7 +4406,7 @@ struct MetadataFor /* .name = */ "frequency", /* .docs = */ "Cutoff frequency in Hz. This will return the actual frequency\nwhen read out in automatic mode.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/commands_aiding.hpp b/src/cpp/mip/metadata/definitions/commands_aiding.hpp index 5b15d17b5..474f72eec 100644 --- a/src/cpp/mip/metadata/definitions/commands_aiding.hpp +++ b/src/cpp/mip/metadata/definitions/commands_aiding.hpp @@ -39,7 +39,7 @@ struct MetadataFor /* .name = */ "euler", /* .docs = */ "Rotation represented as euler angles in RPY format [rad]. Range +/- pi.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* format */, static_cast(commands_aiding::FrameConfig::Format::EULER)} /* format == EULER */, @@ -48,7 +48,7 @@ struct MetadataFor /* .name = */ "quaternion", /* .docs = */ "Rotation represented as a quaternion in WXYZ format.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {ParameterInfo::Condition::Type::ENUM, microstrain::Index(1) /* format */, static_cast(commands_aiding::FrameConfig::Format::QUATERNION)} /* format == QUATERNION */, @@ -73,7 +73,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Reference frame number. Limit 4.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -82,7 +82,7 @@ struct MetadataFor /* .name = */ "format", /* .docs = */ "Format of the transformation.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -91,7 +91,7 @@ struct MetadataFor /* .name = */ "tracking_enabled", /* .docs = */ "If enabled, the Kalman filter will track errors.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -100,7 +100,7 @@ struct MetadataFor /* .name = */ "translation", /* .docs = */ "Translation X, Y, and Z.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -109,7 +109,7 @@ struct MetadataFor /* .name = */ "rotation", /* .docs = */ "Rotation as specified by format.", /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -139,7 +139,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Reference frame number. Limit 4.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -148,7 +148,7 @@ struct MetadataFor /* .name = */ "format", /* .docs = */ "Format of the transformation.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -157,7 +157,7 @@ struct MetadataFor /* .name = */ "tracking_enabled", /* .docs = */ "If enabled, the Kalman filter will track errors.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -166,7 +166,7 @@ struct MetadataFor /* .name = */ "translation", /* .docs = */ "Translation X, Y, and Z.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -175,7 +175,7 @@ struct MetadataFor /* .name = */ "rotation", /* .docs = */ "Rotation as specified by format.", /* .type = */ {Type::UNION, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -224,7 +224,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "Controls data echoing.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -254,7 +254,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "Controls data echoing.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -303,7 +303,7 @@ struct MetadataFor /* .name = */ "timebase", /* .docs = */ "Timebase reference, e.g. internal, external, GPS, UTC, etc.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -312,7 +312,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "Reserved, set to 0x01.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -321,7 +321,7 @@ struct MetadataFor /* .name = */ "nanoseconds", /* .docs = */ "Nanoseconds since the timebase epoch.", /* .type = */ {Type::U64, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -366,7 +366,7 @@ struct MetadataFor /* .name = */ "time", /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -375,7 +375,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -384,7 +384,7 @@ struct MetadataFor /* .name = */ "position", /* .docs = */ "ECEF position [m].", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -393,7 +393,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "ECEF position uncertainty [m]. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -402,7 +402,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -451,7 +451,7 @@ struct MetadataFor /* .name = */ "time", /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -460,7 +460,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -469,7 +469,7 @@ struct MetadataFor /* .name = */ "latitude", /* .docs = */ "[deg]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -478,7 +478,7 @@ struct MetadataFor /* .name = */ "longitude", /* .docs = */ "[deg]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -487,7 +487,7 @@ struct MetadataFor /* .name = */ "height", /* .docs = */ "[m]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -496,7 +496,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "NED position uncertainty. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -505,7 +505,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -534,7 +534,7 @@ struct MetadataFor /* .name = */ "time", /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -543,7 +543,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -552,7 +552,7 @@ struct MetadataFor /* .name = */ "height", /* .docs = */ "[m]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -561,7 +561,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "[m]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -570,7 +570,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -619,7 +619,7 @@ struct MetadataFor /* .name = */ "time", /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -628,7 +628,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -637,7 +637,7 @@ struct MetadataFor /* .name = */ "velocity", /* .docs = */ "ECEF velocity [m/s].", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -646,7 +646,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "ECEF velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -655,7 +655,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -704,7 +704,7 @@ struct MetadataFor /* .name = */ "time", /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -713,7 +713,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -722,7 +722,7 @@ struct MetadataFor /* .name = */ "velocity", /* .docs = */ "NED velocity [m/s].", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -731,7 +731,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "NED velocity uncertainty [m/s]. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -740,7 +740,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -789,7 +789,7 @@ struct MetadataFor /* .name = */ "time", /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -798,7 +798,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -807,7 +807,7 @@ struct MetadataFor /* .name = */ "velocity", /* .docs = */ "[m/s]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -816,7 +816,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "[m/s] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -825,7 +825,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -854,7 +854,7 @@ struct MetadataFor /* .name = */ "time", /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -863,7 +863,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -872,7 +872,7 @@ struct MetadataFor /* .name = */ "heading", /* .docs = */ "Heading [radians]. Range +/- Pi.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -881,7 +881,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "Cannot be 0 unless the valid flags are 0.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -890,7 +890,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -939,7 +939,7 @@ struct MetadataFor /* .name = */ "time", /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -948,7 +948,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -957,7 +957,7 @@ struct MetadataFor /* .name = */ "magnetic_field", /* .docs = */ "[G]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -966,7 +966,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "[G] 1-sigma uncertainty. Cannot be 0 unless the corresponding valid flags are 0.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -975,7 +975,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "Valid flags. Axes with 0 will be completely ignored.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1004,7 +1004,7 @@ struct MetadataFor /* .name = */ "time", /* .docs = */ "Timestamp of the measurement.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1013,7 +1013,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Source ID for this estimate (source_id == 0 indicates this sensor, source_id > 0 indicates an external estimate).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1022,7 +1022,7 @@ struct MetadataFor /* .name = */ "pressure", /* .docs = */ "[mbar]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1031,7 +1031,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "[mbar] 1-sigma uncertainty. Cannot be 0 unless the valid flags are 0.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1040,7 +1040,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/commands_base.hpp b/src/cpp/mip/metadata/definitions/commands_base.hpp index a88a99dd0..a8b12c207 100644 --- a/src/cpp/mip/metadata/definitions/commands_base.hpp +++ b/src/cpp/mip/metadata/definitions/commands_base.hpp @@ -54,7 +54,7 @@ struct MetadataFor /* .name = */ "firmware_version", /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -63,7 +63,7 @@ struct MetadataFor /* .name = */ "model_name", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, @@ -72,7 +72,7 @@ struct MetadataFor /* .name = */ "model_number", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, @@ -81,7 +81,7 @@ struct MetadataFor /* .name = */ "serial_number", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, @@ -90,7 +90,7 @@ struct MetadataFor /* .name = */ "lot_number", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, @@ -99,7 +99,7 @@ struct MetadataFor /* .name = */ "device_options", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 16, /* .condition = */ {}, @@ -124,7 +124,7 @@ struct MetadataFor /* .name = */ "device_info", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -170,7 +170,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(1) /* descriptors_count */}, /* .condition = */ {}, @@ -179,7 +179,7 @@ struct MetadataFor /* .name = */ "descriptors_count", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {false, false, false, false, false, /*echo*/false, /*virtual*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -225,7 +225,7 @@ struct MetadataFor /* .name = */ "result", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -288,7 +288,7 @@ struct MetadataFor /* .name = */ "descriptors", /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {0, microstrain::Index(1) /* descriptors_count */}, /* .condition = */ {}, @@ -297,7 +297,7 @@ struct MetadataFor /* .name = */ "descriptors_count", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {false, false, false, false, false, /*echo*/false, /*virtual*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -343,7 +343,7 @@ struct MetadataFor /* .name = */ "result", /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 16, /* .condition = */ {}, @@ -389,7 +389,7 @@ struct MetadataFor /* .name = */ "port", /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -398,7 +398,7 @@ struct MetadataFor /* .name = */ "baud", /* .docs = */ "Port baud rate. Must be a supported rate.", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -428,7 +428,7 @@ struct MetadataFor /* .name = */ "port", /* .docs = */ "Port ID number, starting with 1. When function is SAVE, LOAD, or DEFAULT, this can be 0 to apply to all ports. See the device user manual for details.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -437,7 +437,7 @@ struct MetadataFor /* .name = */ "baud", /* .docs = */ "Port baud rate. Must be a supported rate.", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -486,7 +486,7 @@ struct MetadataFor /* .name = */ "field_id", /* .docs = */ "Determines how to interpret value.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -495,7 +495,7 @@ struct MetadataFor /* .name = */ "value", /* .docs = */ "Week number or time of week, depending on the field_id.", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/commands_filter.hpp b/src/cpp/mip/metadata/definitions/commands_filter.hpp index 3fa759901..006128be0 100644 --- a/src/cpp/mip/metadata/definitions/commands_filter.hpp +++ b/src/cpp/mip/metadata/definitions/commands_filter.hpp @@ -37,7 +37,7 @@ struct MetadataFor /* .name = */ "roll", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -46,7 +46,7 @@ struct MetadataFor /* .name = */ "pitch", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -55,7 +55,7 @@ struct MetadataFor /* .name = */ "heading", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -108,7 +108,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "See above", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -138,7 +138,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "See above", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -167,7 +167,7 @@ struct MetadataFor /* .name = */ "gps_time", /* .docs = */ "[seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -176,7 +176,7 @@ struct MetadataFor /* .name = */ "gps_week", /* .docs = */ "[GPS week number, not modulus 1024]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -185,7 +185,7 @@ struct MetadataFor /* .name = */ "latitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -194,7 +194,7 @@ struct MetadataFor /* .name = */ "longitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -203,7 +203,7 @@ struct MetadataFor /* .name = */ "height", /* .docs = */ "Above WGS84 ellipsoid [meters]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -212,7 +212,7 @@ struct MetadataFor /* .name = */ "velocity", /* .docs = */ "NED Frame [meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -221,7 +221,7 @@ struct MetadataFor /* .name = */ "pos_uncertainty", /* .docs = */ "NED Frame, 1-sigma [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -230,7 +230,7 @@ struct MetadataFor /* .name = */ "vel_uncertainty", /* .docs = */ "NED Frame, 1-sigma [meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -259,7 +259,7 @@ struct MetadataFor /* .name = */ "heading", /* .docs = */ "Bounded by +-PI [radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -268,7 +268,7 @@ struct MetadataFor /* .name = */ "heading_uncertainty", /* .docs = */ "1-sigma [radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -277,7 +277,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "1 - True, 2 - Magnetic", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -306,7 +306,7 @@ struct MetadataFor /* .name = */ "gps_time", /* .docs = */ "[seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -315,7 +315,7 @@ struct MetadataFor /* .name = */ "gps_week", /* .docs = */ "[GPS week number, not modulus 1024]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -324,7 +324,7 @@ struct MetadataFor /* .name = */ "heading", /* .docs = */ "Relative to true north, bounded by +-PI [radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -333,7 +333,7 @@ struct MetadataFor /* .name = */ "heading_uncertainty", /* .docs = */ "1-sigma [radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -342,7 +342,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "1 - True, 2 - Magnetic", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -391,7 +391,7 @@ struct MetadataFor /* .name = */ "axes", /* .docs = */ "Axes to tare", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -421,7 +421,7 @@ struct MetadataFor /* .name = */ "axes", /* .docs = */ "Axes to tare", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -471,7 +471,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -501,7 +501,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -530,7 +530,7 @@ struct MetadataFor /* .name = */ "roll", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -539,7 +539,7 @@ struct MetadataFor /* .name = */ "pitch", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -548,7 +548,7 @@ struct MetadataFor /* .name = */ "yaw", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -578,7 +578,7 @@ struct MetadataFor /* .name = */ "roll", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -587,7 +587,7 @@ struct MetadataFor /* .name = */ "pitch", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -596,7 +596,7 @@ struct MetadataFor /* .name = */ "yaw", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -625,7 +625,7 @@ struct MetadataFor /* .name = */ "dcm", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -655,7 +655,7 @@ struct MetadataFor /* .name = */ "dcm", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -684,7 +684,7 @@ struct MetadataFor /* .name = */ "quat", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -714,7 +714,7 @@ struct MetadataFor /* .name = */ "quat", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -743,7 +743,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -773,7 +773,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -802,7 +802,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -832,7 +832,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -882,7 +882,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -912,7 +912,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -966,7 +966,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -996,7 +996,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1025,7 +1025,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "See above", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1055,7 +1055,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "See above", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1084,7 +1084,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1114,7 +1114,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1143,7 +1143,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Gyro Noise 1-sigma [rad/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1173,7 +1173,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Gyro Noise 1-sigma [rad/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1202,7 +1202,7 @@ struct MetadataFor /* .name = */ "beta", /* .docs = */ "Accel Bias Beta [1/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1211,7 +1211,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1241,7 +1241,7 @@ struct MetadataFor /* .name = */ "beta", /* .docs = */ "Accel Bias Beta [1/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1250,7 +1250,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Accel Noise 1-sigma [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1279,7 +1279,7 @@ struct MetadataFor /* .name = */ "beta", /* .docs = */ "Gyro Bias Beta [1/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1288,7 +1288,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Gyro Noise 1-sigma [rad/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1318,7 +1318,7 @@ struct MetadataFor /* .name = */ "beta", /* .docs = */ "Gyro Bias Beta [1/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1327,7 +1327,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Gyro Noise 1-sigma [rad/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1375,7 +1375,7 @@ struct MetadataFor /* .name = */ "selector", /* .docs = */ "See above", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1405,7 +1405,7 @@ struct MetadataFor /* .name = */ "selector", /* .docs = */ "See above", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1453,7 +1453,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Controls the aiding source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1483,7 +1483,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Controls the aiding source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1512,7 +1512,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1521,7 +1521,7 @@ struct MetadataFor /* .name = */ "threshold", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1551,7 +1551,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1560,7 +1560,7 @@ struct MetadataFor /* .name = */ "threshold", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1589,7 +1589,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1598,7 +1598,7 @@ struct MetadataFor /* .name = */ "threshold", /* .docs = */ "[radians/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1628,7 +1628,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1637,7 +1637,7 @@ struct MetadataFor /* .name = */ "threshold", /* .docs = */ "[radians/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1722,7 +1722,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Gravity Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1752,7 +1752,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Gravity Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1781,7 +1781,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Pressure Altitude Noise 1-sigma [m]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1811,7 +1811,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Pressure Altitude Noise 1-sigma [m]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1840,7 +1840,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Hard Iron Offset Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1870,7 +1870,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Hard Iron Offset Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1899,7 +1899,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Soft Iron Matrix Noise 1-sigma [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1929,7 +1929,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Soft Iron Matrix Noise 1-sigma [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1958,7 +1958,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Mag Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1988,7 +1988,7 @@ struct MetadataFor /* .name = */ "noise", /* .docs = */ "Mag Noise 1-sigma [gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2037,7 +2037,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Inclination Source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2046,7 +2046,7 @@ struct MetadataFor /* .name = */ "inclination", /* .docs = */ "Inclination angle [radians] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2076,7 +2076,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Inclination Source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2085,7 +2085,7 @@ struct MetadataFor /* .name = */ "inclination", /* .docs = */ "Inclination angle [radians] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2114,7 +2114,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Magnetic field declination angle source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2123,7 +2123,7 @@ struct MetadataFor /* .name = */ "declination", /* .docs = */ "Declination angle [radians] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2153,7 +2153,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Magnetic field declination angle source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2162,7 +2162,7 @@ struct MetadataFor /* .name = */ "declination", /* .docs = */ "Declination angle [radians] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2191,7 +2191,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Magnetic Field Magnitude Source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2200,7 +2200,7 @@ struct MetadataFor /* .name = */ "magnitude", /* .docs = */ "Magnitude [gauss] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2230,7 +2230,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Magnetic Field Magnitude Source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2239,7 +2239,7 @@ struct MetadataFor /* .name = */ "magnitude", /* .docs = */ "Magnitude [gauss] (only required if source = MANUAL)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2268,7 +2268,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "enable/disable", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2277,7 +2277,7 @@ struct MetadataFor /* .name = */ "latitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2286,7 +2286,7 @@ struct MetadataFor /* .name = */ "longitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2295,7 +2295,7 @@ struct MetadataFor /* .name = */ "altitude", /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2325,7 +2325,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "enable/disable", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2334,7 +2334,7 @@ struct MetadataFor /* .name = */ "latitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2343,7 +2343,7 @@ struct MetadataFor /* .name = */ "longitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2352,7 +2352,7 @@ struct MetadataFor /* .name = */ "altitude", /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2401,7 +2401,7 @@ struct MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2410,7 +2410,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2419,7 +2419,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2428,7 +2428,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2437,7 +2437,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2446,7 +2446,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2455,7 +2455,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2485,7 +2485,7 @@ struct MetadataFor /* .name = */ "adaptive_measurement", /* .docs = */ "Adaptive measurement selector", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2494,7 +2494,7 @@ struct MetadataFor /* .name = */ "frequency", /* .docs = */ "Low-pass filter curoff frequency [hertz]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2503,7 +2503,7 @@ struct MetadataFor /* .name = */ "low_limit", /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2512,7 +2512,7 @@ struct MetadataFor /* .name = */ "high_limit", /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2521,7 +2521,7 @@ struct MetadataFor /* .name = */ "low_limit_uncertainty", /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2530,7 +2530,7 @@ struct MetadataFor /* .name = */ "high_limit_uncertainty", /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2539,7 +2539,7 @@ struct MetadataFor /* .name = */ "minimum_uncertainty", /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2568,7 +2568,7 @@ struct MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2577,7 +2577,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2586,7 +2586,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2595,7 +2595,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2604,7 +2604,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2613,7 +2613,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2622,7 +2622,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2652,7 +2652,7 @@ struct MetadataFor /* .name = */ "adaptive_measurement", /* .docs = */ "Adaptive measurement selector", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2661,7 +2661,7 @@ struct MetadataFor /* .name = */ "frequency", /* .docs = */ "Low-pass filter curoff frequency [hertz]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2670,7 +2670,7 @@ struct MetadataFor /* .name = */ "low_limit", /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2679,7 +2679,7 @@ struct MetadataFor /* .name = */ "high_limit", /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2688,7 +2688,7 @@ struct MetadataFor /* .name = */ "low_limit_uncertainty", /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2697,7 +2697,7 @@ struct MetadataFor /* .name = */ "high_limit_uncertainty", /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2706,7 +2706,7 @@ struct MetadataFor /* .name = */ "minimum_uncertainty", /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2735,7 +2735,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2744,7 +2744,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2753,7 +2753,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2762,7 +2762,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2771,7 +2771,7 @@ struct MetadataFor, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2801,7 +2801,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "Enable/Disable", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2810,7 +2810,7 @@ struct MetadataFor /* .name = */ "frequency", /* .docs = */ "Low-pass filter curoff frequency [hertz]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2819,7 +2819,7 @@ struct MetadataFor /* .name = */ "high_limit", /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2828,7 +2828,7 @@ struct MetadataFor /* .name = */ "high_limit_uncertainty", /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2837,7 +2837,7 @@ struct MetadataFor /* .name = */ "minimum_uncertainty", /* .docs = */ "1-Sigma [meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2893,7 +2893,7 @@ struct MetadataFor /* .name = */ "aiding_source", /* .docs = */ "Aiding measurement source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2902,7 +2902,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "Controls the aiding source", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2932,7 +2932,7 @@ struct MetadataFor /* .name = */ "aiding_source", /* .docs = */ "Aiding measurement source", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -2941,7 +2941,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "Controls the aiding source", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2987,7 +2987,7 @@ struct MetadataFor /* .name = */ "acceleration_constraint_selection", /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2996,7 +2996,7 @@ struct MetadataFor /* .name = */ "velocity_constraint_selection", /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3005,7 +3005,7 @@ struct MetadataFor /* .name = */ "angular_constraint_selection", /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3035,7 +3035,7 @@ struct MetadataFor /* .name = */ "acceleration_constraint_selection", /* .docs = */ "Acceleration constraint:
\n0=None (default),
\n1=Zero-acceleration.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3044,7 +3044,7 @@ struct MetadataFor /* .name = */ "velocity_constraint_selection", /* .docs = */ "0=None (default),
\n1=Zero-velocity,
\n2=Wheeled-vehicle.
", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3053,7 +3053,7 @@ struct MetadataFor /* .name = */ "angular_constraint_selection", /* .docs = */ "0=None (default),\n1=Zero-angular rate (ZUPT).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3143,7 +3143,7 @@ struct MetadataFor /* .name = */ "wait_for_run_command", /* .docs = */ "Initialize filter only after receiving 'run' command", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3152,7 +3152,7 @@ struct MetadataFor /* .name = */ "initial_cond_src", /* .docs = */ "Initial condition source:", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3161,7 +3161,7 @@ struct MetadataFor /* .name = */ "auto_heading_alignment_selector", /* .docs = */ "Bitfield specifying the allowed automatic heading alignment methods for automatic initial conditions. Bits are set to 1 to enable, and the correspond to the following:
", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3170,7 +3170,7 @@ struct MetadataFor /* .name = */ "initial_heading", /* .docs = */ "User-specified initial platform heading (degrees).", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3179,7 +3179,7 @@ struct MetadataFor /* .name = */ "initial_pitch", /* .docs = */ "User-specified initial platform pitch (degrees)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3188,7 +3188,7 @@ struct MetadataFor /* .name = */ "initial_roll", /* .docs = */ "User-specified initial platform roll (degrees)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3197,7 +3197,7 @@ struct MetadataFor /* .name = */ "initial_position", /* .docs = */ "User-specified initial platform position (units determined by reference frame selector, see note.)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3206,7 +3206,7 @@ struct MetadataFor /* .name = */ "initial_velocity", /* .docs = */ "User-specified initial platform velocity (units determined by reference frame selector, see note.)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3215,7 +3215,7 @@ struct MetadataFor /* .name = */ "reference_frame_selector", /* .docs = */ "User-specified initial position/velocity reference frames", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3245,7 +3245,7 @@ struct MetadataFor /* .name = */ "wait_for_run_command", /* .docs = */ "Initialize filter only after receiving 'run' command", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3254,7 +3254,7 @@ struct MetadataFor /* .name = */ "initial_cond_src", /* .docs = */ "Initial condition source:", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3263,7 +3263,7 @@ struct MetadataFor /* .name = */ "auto_heading_alignment_selector", /* .docs = */ "Bitfield specifying the allowed automatic heading alignment methods for automatic initial conditions. Bits are set to 1 to enable, and the correspond to the following:
", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3272,7 +3272,7 @@ struct MetadataFor /* .name = */ "initial_heading", /* .docs = */ "User-specified initial platform heading (degrees).", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3281,7 +3281,7 @@ struct MetadataFor /* .name = */ "initial_pitch", /* .docs = */ "User-specified initial platform pitch (degrees)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3290,7 +3290,7 @@ struct MetadataFor /* .name = */ "initial_roll", /* .docs = */ "User-specified initial platform roll (degrees)", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3299,7 +3299,7 @@ struct MetadataFor /* .name = */ "initial_position", /* .docs = */ "User-specified initial platform position (units determined by reference frame selector, see note.)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3308,7 +3308,7 @@ struct MetadataFor /* .name = */ "initial_velocity", /* .docs = */ "User-specified initial platform velocity (units determined by reference frame selector, see note.)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3317,7 +3317,7 @@ struct MetadataFor /* .name = */ "reference_frame_selector", /* .docs = */ "User-specified initial position/velocity reference frames", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3346,7 +3346,7 @@ struct MetadataFor /* .name = */ "level", /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3355,7 +3355,7 @@ struct MetadataFor /* .name = */ "time_limit", /* .docs = */ "Maximum duration of measurement rejection before entering recovery mode (ms)", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3385,7 +3385,7 @@ struct MetadataFor /* .name = */ "level", /* .docs = */ "Auto-adaptive operating level:
\n0=Off,
\n1=Conservative,
\n2=Moderate (default),
\n3=Aggressive.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3394,7 +3394,7 @@ struct MetadataFor /* .name = */ "time_limit", /* .docs = */ "Maximum duration of measurement rejection before entering recovery mode (ms)", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3423,7 +3423,7 @@ struct MetadataFor /* .name = */ "receiver_id", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -3432,7 +3432,7 @@ struct MetadataFor /* .name = */ "antenna_offset", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3462,7 +3462,7 @@ struct MetadataFor /* .name = */ "receiver_id", /* .docs = */ "Receiver: 1, 2, etc...", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -3471,7 +3471,7 @@ struct MetadataFor /* .name = */ "antenna_offset", /* .docs = */ "Antenna lever arm offset vector in the vehicle frame (m)", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3500,7 +3500,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "0 - auto (RTK base station), 1 - manual", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3509,7 +3509,7 @@ struct MetadataFor /* .name = */ "reference_frame_selector", /* .docs = */ "ECEF or LLH", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3518,7 +3518,7 @@ struct MetadataFor /* .name = */ "reference_coordinates", /* .docs = */ "reference coordinates, units determined by source selection", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3548,7 +3548,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "0 - auto (RTK base station), 1 - manual", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3557,7 +3557,7 @@ struct MetadataFor /* .name = */ "reference_frame_selector", /* .docs = */ "ECEF or LLH", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3566,7 +3566,7 @@ struct MetadataFor /* .name = */ "reference_coordinates", /* .docs = */ "reference coordinates, units determined by source selection", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3613,7 +3613,7 @@ struct MetadataFor /* .name = */ "ref_point_sel", /* .docs = */ "Reserved, must be 1", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3622,7 +3622,7 @@ struct MetadataFor /* .name = */ "lever_arm_offset", /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3652,7 +3652,7 @@ struct MetadataFor /* .name = */ "ref_point_sel", /* .docs = */ "Reserved, must be 1", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3661,7 +3661,7 @@ struct MetadataFor /* .name = */ "lever_arm_offset", /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3690,7 +3690,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Reserved, must be 1.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3699,7 +3699,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS time of week when speed was sampled", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3708,7 +3708,7 @@ struct MetadataFor /* .name = */ "speed", /* .docs = */ "Estimated speed along vehicle's x-axis (may be positive or negative) [meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3717,7 +3717,7 @@ struct MetadataFor /* .name = */ "speed_uncertainty", /* .docs = */ "Estimated uncertainty in the speed measurement (1-sigma value) [meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3746,7 +3746,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Reserved, must be 1.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -3755,7 +3755,7 @@ struct MetadataFor /* .name = */ "lever_arm_offset", /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3785,7 +3785,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "Reserved, must be 1.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, true, true, true, true, /*echo*/true}, /* .count = */ 1, /* .condition = */ {}, @@ -3794,7 +3794,7 @@ struct MetadataFor /* .name = */ "lever_arm_offset", /* .docs = */ "[m] Lever arm offset vector in the vehicle's reference frame.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3823,7 +3823,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3853,7 +3853,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3882,7 +3882,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3912,7 +3912,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3941,7 +3941,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3950,7 +3950,7 @@ struct MetadataFor /* .name = */ "max_offset", /* .docs = */ "Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3980,7 +3980,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disable, 1 - Enable", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3989,7 +3989,7 @@ struct MetadataFor /* .name = */ "max_offset", /* .docs = */ "Maximum absolute value of lever arm offset error in the vehicle frame [meters]. See device user manual for the valid range of this parameter.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -4018,7 +4018,7 @@ struct MetadataFor /* .name = */ "heading", /* .docs = */ "Initial heading in radians [-pi, pi]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/commands_gnss.hpp b/src/cpp/mip/metadata/definitions/commands_gnss.hpp index ecb421bb5..33b422c95 100644 --- a/src/cpp/mip/metadata/definitions/commands_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/commands_gnss.hpp @@ -20,7 +20,7 @@ struct MetadataFor /* .name = */ "receiver_id", /* .docs = */ "Receiver id: e.g. 1, 2, etc.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -29,7 +29,7 @@ struct MetadataFor /* .name = */ "mip_data_descriptor_set", /* .docs = */ "MIP descriptor set associated with this receiver", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 1, /* .condition = */ {}, @@ -38,7 +38,7 @@ struct MetadataFor /* .name = */ "description", /* .docs = */ "Ascii description of receiver. Contains the following info (comma-delimited):
\nModule name/model
\nFirmware version info", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ NO_FUNCTIONS, /* .count = */ 32, /* .condition = */ {}, @@ -63,7 +63,7 @@ struct MetadataFor /* .name = */ "num_receivers", /* .docs = */ "Number of physical receivers in the device", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -72,7 +72,7 @@ struct MetadataFor /* .name = */ "receiver_info", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ {5, microstrain::Index(0) /* num_receivers */}, /* .condition = */ {}, @@ -118,7 +118,7 @@ struct MetadataFor /* .name = */ "gps_enable", /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -127,7 +127,7 @@ struct MetadataFor /* .name = */ "glonass_enable", /* .docs = */ "Bitfield 0: Enable L1OF, 1: Enable L2OF", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -136,7 +136,7 @@ struct MetadataFor /* .name = */ "galileo_enable", /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -145,7 +145,7 @@ struct MetadataFor /* .name = */ "beidou_enable", /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -154,7 +154,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, @@ -184,7 +184,7 @@ struct MetadataFor /* .name = */ "gps_enable", /* .docs = */ "Bitfield 0: Enable L1CA, 1: Enable L2C, 2: Enable L5", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -193,7 +193,7 @@ struct MetadataFor /* .name = */ "glonass_enable", /* .docs = */ "Bitfield 0: Enable L1OF, 1: Enable L2OF", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -202,7 +202,7 @@ struct MetadataFor /* .name = */ "galileo_enable", /* .docs = */ "Bitfield 0: Enable E1, 1: Enable E5B, 2: Enable E5A", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -211,7 +211,7 @@ struct MetadataFor /* .name = */ "beidou_enable", /* .docs = */ "Bitfield 0: Enable B1, 1: Enable B2, 2: Enable B2A", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -220,7 +220,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, @@ -249,7 +249,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -258,7 +258,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 3, /* .condition = */ {}, @@ -288,7 +288,7 @@ struct MetadataFor /* .name = */ "enable", /* .docs = */ "0 - Disabled, 1- Enabled", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -297,7 +297,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 3, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/commands_rtk.hpp b/src/cpp/mip/metadata/definitions/commands_rtk.hpp index 45f67104a..ebc4e079e 100644 --- a/src/cpp/mip/metadata/definitions/commands_rtk.hpp +++ b/src/cpp/mip/metadata/definitions/commands_rtk.hpp @@ -77,7 +77,7 @@ struct MetadataFor /* .name = */ "flags", /* .docs = */ "Model number dependent. See above structures.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -123,7 +123,7 @@ struct MetadataFor /* .name = */ "IMEI", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, @@ -169,7 +169,7 @@ struct MetadataFor /* .name = */ "IMSI", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, @@ -215,7 +215,7 @@ struct MetadataFor /* .name = */ "ICCID", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, @@ -280,7 +280,7 @@ struct MetadataFor /* .name = */ "devType", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -310,7 +310,7 @@ struct MetadataFor /* .name = */ "devType", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -339,7 +339,7 @@ struct MetadataFor /* .name = */ "ActivationCode", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, @@ -385,7 +385,7 @@ struct MetadataFor /* .name = */ "ModemFirmwareVersion", /* .docs = */ "", /* .type = */ {Type::CHAR, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 32, /* .condition = */ {}, @@ -431,7 +431,7 @@ struct MetadataFor /* .name = */ "valid", /* .docs = */ "", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -440,7 +440,7 @@ struct MetadataFor /* .name = */ "rssi", /* .docs = */ "", /* .type = */ {Type::S32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -449,7 +449,7 @@ struct MetadataFor /* .name = */ "signalQuality", /* .docs = */ "", /* .type = */ {Type::S32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -515,7 +515,7 @@ struct MetadataFor /* .name = */ "flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -524,7 +524,7 @@ struct MetadataFor /* .name = */ "receivedBytes", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -533,7 +533,7 @@ struct MetadataFor /* .name = */ "lastBytes", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -542,7 +542,7 @@ struct MetadataFor /* .name = */ "lastBytesTime", /* .docs = */ "", /* .type = */ {Type::U64, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -571,7 +571,7 @@ struct MetadataFor /* .name = */ "reserved1", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -580,7 +580,7 @@ struct MetadataFor /* .name = */ "reserved2", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -628,7 +628,7 @@ struct MetadataFor /* .name = */ "media", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -677,7 +677,7 @@ struct MetadataFor /* .name = */ "primaryColor", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 3, /* .condition = */ {}, @@ -686,7 +686,7 @@ struct MetadataFor /* .name = */ "altColor", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 3, /* .condition = */ {}, @@ -695,7 +695,7 @@ struct MetadataFor /* .name = */ "act", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -704,7 +704,7 @@ struct MetadataFor /* .name = */ "period", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/commands_system.hpp b/src/cpp/mip/metadata/definitions/commands_system.hpp index 559b30fd5..1c3352eb5 100644 --- a/src/cpp/mip/metadata/definitions/commands_system.hpp +++ b/src/cpp/mip/metadata/definitions/commands_system.hpp @@ -20,7 +20,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -50,7 +50,7 @@ struct MetadataFor /* .name = */ "mode", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/data_filter.hpp b/src/cpp/mip/metadata/definitions/data_filter.hpp index 09e7e8415..59935548c 100644 --- a/src/cpp/mip/metadata/definitions/data_filter.hpp +++ b/src/cpp/mip/metadata/definitions/data_filter.hpp @@ -20,7 +20,7 @@ struct MetadataFor /* .name = */ "latitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -29,7 +29,7 @@ struct MetadataFor /* .name = */ "longitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -38,7 +38,7 @@ struct MetadataFor /* .name = */ "ellipsoid_height", /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -47,7 +47,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - Invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -76,7 +76,7 @@ struct MetadataFor /* .name = */ "north", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -85,7 +85,7 @@ struct MetadataFor /* .name = */ "east", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -94,7 +94,7 @@ struct MetadataFor /* .name = */ "down", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -103,7 +103,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - Invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -132,7 +132,7 @@ struct MetadataFor /* .name = */ "q", /* .docs = */ "Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -141,7 +141,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -170,7 +170,7 @@ struct MetadataFor /* .name = */ "dcm", /* .docs = */ "Matrix elements in row-major order.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -179,7 +179,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -208,7 +208,7 @@ struct MetadataFor /* .name = */ "roll", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -217,7 +217,7 @@ struct MetadataFor /* .name = */ "pitch", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -226,7 +226,7 @@ struct MetadataFor /* .name = */ "yaw", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -235,7 +235,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -264,7 +264,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "(x, y, z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -273,7 +273,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -302,7 +302,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "(x, y, z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -311,7 +311,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -340,7 +340,7 @@ struct MetadataFor /* .name = */ "north", /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -349,7 +349,7 @@ struct MetadataFor /* .name = */ "east", /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -358,7 +358,7 @@ struct MetadataFor /* .name = */ "down", /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -367,7 +367,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -396,7 +396,7 @@ struct MetadataFor /* .name = */ "north", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -405,7 +405,7 @@ struct MetadataFor /* .name = */ "east", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -414,7 +414,7 @@ struct MetadataFor /* .name = */ "down", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -423,7 +423,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -452,7 +452,7 @@ struct MetadataFor /* .name = */ "roll", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -461,7 +461,7 @@ struct MetadataFor /* .name = */ "pitch", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -470,7 +470,7 @@ struct MetadataFor /* .name = */ "yaw", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -479,7 +479,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -508,7 +508,7 @@ struct MetadataFor /* .name = */ "bias_uncert", /* .docs = */ "(x,y,z) [radians/sec]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -517,7 +517,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -546,7 +546,7 @@ struct MetadataFor /* .name = */ "bias_uncert", /* .docs = */ "(x,y,z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -555,7 +555,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -584,7 +584,7 @@ struct MetadataFor /* .name = */ "tow", /* .docs = */ "GPS Time of Week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -593,7 +593,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week Number since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -602,7 +602,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -722,7 +722,7 @@ struct MetadataFor /* .name = */ "filter_state", /* .docs = */ "Device-specific filter state. Please consult the user manual for definition.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -731,7 +731,7 @@ struct MetadataFor /* .name = */ "dynamics_mode", /* .docs = */ "Device-specific dynamics mode. Please consult the user manual for definition.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -740,7 +740,7 @@ struct MetadataFor /* .name = */ "status_flags", /* .docs = */ "Device-specific status flags. Please consult the user manual for definition.", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -769,7 +769,7 @@ struct MetadataFor /* .name = */ "accel", /* .docs = */ "(x,y,z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -778,7 +778,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -807,7 +807,7 @@ struct MetadataFor /* .name = */ "gravity", /* .docs = */ "(x, y, z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -816,7 +816,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -845,7 +845,7 @@ struct MetadataFor /* .name = */ "accel", /* .docs = */ "(x,y,z) [meters/second^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -854,7 +854,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -883,7 +883,7 @@ struct MetadataFor /* .name = */ "gyro", /* .docs = */ "(x, y, z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -892,7 +892,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -921,7 +921,7 @@ struct MetadataFor /* .name = */ "q", /* .docs = */ "[dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -930,7 +930,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -959,7 +959,7 @@ struct MetadataFor /* .name = */ "magnitude", /* .docs = */ "[meters/second^2]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -968,7 +968,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1019,7 +1019,7 @@ struct MetadataFor /* .name = */ "heading", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1028,7 +1028,7 @@ struct MetadataFor /* .name = */ "heading_1sigma", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1037,7 +1037,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1046,7 +1046,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "1 if a valid heading update was received in 2 seconds, 0 otherwise.", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1075,7 +1075,7 @@ struct MetadataFor /* .name = */ "intensity_north", /* .docs = */ "[Gauss]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1084,7 +1084,7 @@ struct MetadataFor /* .name = */ "intensity_east", /* .docs = */ "[Gauss]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1093,7 +1093,7 @@ struct MetadataFor /* .name = */ "intensity_down", /* .docs = */ "[Gauss]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1102,7 +1102,7 @@ struct MetadataFor /* .name = */ "inclination", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1111,7 +1111,7 @@ struct MetadataFor /* .name = */ "declination", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1120,7 +1120,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1149,7 +1149,7 @@ struct MetadataFor /* .name = */ "scale_factor", /* .docs = */ "(x,y,z) [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1158,7 +1158,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1187,7 +1187,7 @@ struct MetadataFor /* .name = */ "scale_factor_uncert", /* .docs = */ "(x,y,z) [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1196,7 +1196,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1225,7 +1225,7 @@ struct MetadataFor /* .name = */ "scale_factor", /* .docs = */ "(x,y,z) [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1234,7 +1234,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1263,7 +1263,7 @@ struct MetadataFor /* .name = */ "scale_factor_uncert", /* .docs = */ "(x,y,z) [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1272,7 +1272,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1301,7 +1301,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1310,7 +1310,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1339,7 +1339,7 @@ struct MetadataFor /* .name = */ "bias_uncert", /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1348,7 +1348,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1377,7 +1377,7 @@ struct MetadataFor /* .name = */ "geometric_altitude", /* .docs = */ "Input into calculation [meters]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1386,7 +1386,7 @@ struct MetadataFor /* .name = */ "geopotential_altitude", /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1395,7 +1395,7 @@ struct MetadataFor /* .name = */ "standard_temperature", /* .docs = */ "[degC]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1404,7 +1404,7 @@ struct MetadataFor /* .name = */ "standard_pressure", /* .docs = */ "[milliBar]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1413,7 +1413,7 @@ struct MetadataFor /* .name = */ "standard_density", /* .docs = */ "[kilogram/meter^3]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1422,7 +1422,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1451,7 +1451,7 @@ struct MetadataFor /* .name = */ "pressure_altitude", /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1460,7 +1460,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1489,7 +1489,7 @@ struct MetadataFor /* .name = */ "density_altitude", /* .docs = */ "m", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1498,7 +1498,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1527,7 +1527,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "(x,y,z) [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1536,7 +1536,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1565,7 +1565,7 @@ struct MetadataFor /* .name = */ "offset_uncert", /* .docs = */ "(x,y,z) [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1574,7 +1574,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1603,7 +1603,7 @@ struct MetadataFor /* .name = */ "receiver_id", /* .docs = */ "Receiver ID for the receiver to which the antenna is attached", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1612,7 +1612,7 @@ struct MetadataFor /* .name = */ "offset", /* .docs = */ "(x,y,z) [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1621,7 +1621,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1650,7 +1650,7 @@ struct MetadataFor /* .name = */ "receiver_id", /* .docs = */ "Receiver ID for the receiver to which the antenna is attached", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1659,7 +1659,7 @@ struct MetadataFor /* .name = */ "offset_uncert", /* .docs = */ "(x,y,z) [meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1668,7 +1668,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1697,7 +1697,7 @@ struct MetadataFor /* .name = */ "hard_iron", /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1706,7 +1706,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1735,7 +1735,7 @@ struct MetadataFor /* .name = */ "soft_iron", /* .docs = */ "Row-major [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1744,7 +1744,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1773,7 +1773,7 @@ struct MetadataFor /* .name = */ "hard_iron_uncertainty", /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1782,7 +1782,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1811,7 +1811,7 @@ struct MetadataFor /* .name = */ "soft_iron_uncertainty", /* .docs = */ "Row-major [dimensionless]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1820,7 +1820,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1849,7 +1849,7 @@ struct MetadataFor /* .name = */ "covariance", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1858,7 +1858,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1887,7 +1887,7 @@ struct MetadataFor /* .name = */ "residual", /* .docs = */ "(x,y,z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1896,7 +1896,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1925,7 +1925,7 @@ struct MetadataFor /* .name = */ "receiver_id", /* .docs = */ "1, 2, etc.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1934,7 +1934,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "[seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1943,7 +1943,7 @@ struct MetadataFor /* .name = */ "bias_drift", /* .docs = */ "[seconds/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1952,7 +1952,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1981,7 +1981,7 @@ struct MetadataFor /* .name = */ "receiver_id", /* .docs = */ "1, 2, etc.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1990,7 +1990,7 @@ struct MetadataFor /* .name = */ "bias_uncertainty", /* .docs = */ "[seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1999,7 +1999,7 @@ struct MetadataFor /* .name = */ "bias_drift_uncertainty", /* .docs = */ "[seconds/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2008,7 +2008,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2070,7 +2070,7 @@ struct MetadataFor /* .name = */ "receiver_id", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2079,7 +2079,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "Last GNSS aiding measurement time of week [seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2088,7 +2088,7 @@ struct MetadataFor /* .name = */ "status", /* .docs = */ "Aiding measurement status bitfield", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2097,7 +2097,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 8, /* .condition = */ {}, @@ -2126,7 +2126,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "Last valid aiding measurement time of week [seconds] [processed instead of measured?]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2135,7 +2135,7 @@ struct MetadataFor /* .name = */ "status", /* .docs = */ "Last valid aiding measurement status bitfield", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2144,7 +2144,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 8, /* .condition = */ {}, @@ -2192,7 +2192,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "Last valid aiding measurement time of week [seconds] [processed instead of measured?]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2201,7 +2201,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "1 - Dual antenna, 2 - External heading message (user supplied)", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2210,7 +2210,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 2, /* .condition = */ {}, @@ -2239,7 +2239,7 @@ struct MetadataFor /* .name = */ "relative_position", /* .docs = */ "[meters, NED]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2248,7 +2248,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2277,7 +2277,7 @@ struct MetadataFor /* .name = */ "position_ecef", /* .docs = */ "[meters, ECEF]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2286,7 +2286,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2315,7 +2315,7 @@ struct MetadataFor /* .name = */ "velocity_ecef", /* .docs = */ "[meters/second, ECEF]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2324,7 +2324,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2353,7 +2353,7 @@ struct MetadataFor /* .name = */ "pos_uncertainty", /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2362,7 +2362,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2391,7 +2391,7 @@ struct MetadataFor /* .name = */ "vel_uncertainty", /* .docs = */ "[meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2400,7 +2400,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2484,7 +2484,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "[seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2493,7 +2493,7 @@ struct MetadataFor /* .name = */ "source", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2502,7 +2502,7 @@ struct MetadataFor /* .name = */ "type", /* .docs = */ "(see product manual for supported types) Note: values 0x20 and above correspond to commanded aiding measurements in the 0x13 Aiding command set.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2511,7 +2511,7 @@ struct MetadataFor /* .name = */ "indicator", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2540,7 +2540,7 @@ struct MetadataFor /* .name = */ "scale_factor_error", /* .docs = */ "[dimensionless]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2549,7 +2549,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2578,7 +2578,7 @@ struct MetadataFor /* .name = */ "scale_factor_error_uncertainty", /* .docs = */ "[dimensionless]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2587,7 +2587,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2656,7 +2656,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "Last dual-antenna GNSS aiding measurement time of week [seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2665,7 +2665,7 @@ struct MetadataFor /* .name = */ "heading", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2674,7 +2674,7 @@ struct MetadataFor /* .name = */ "heading_unc", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2683,7 +2683,7 @@ struct MetadataFor /* .name = */ "fix_type", /* .docs = */ "Fix type indicator", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2692,7 +2692,7 @@ struct MetadataFor /* .name = */ "status_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2701,7 +2701,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "0 - invalid, 1 - valid", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2730,7 +2730,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Frame ID for the receiver to which the antenna is attached", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2739,7 +2739,7 @@ struct MetadataFor /* .name = */ "translation", /* .docs = */ "Translation config X, Y, and Z (m).", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2748,7 +2748,7 @@ struct MetadataFor /* .name = */ "attitude", /* .docs = */ "Attitude quaternion", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2777,7 +2777,7 @@ struct MetadataFor /* .name = */ "frame_id", /* .docs = */ "Frame ID for the receiver to which the antenna is attached", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2786,7 +2786,7 @@ struct MetadataFor /* .name = */ "translation_unc", /* .docs = */ "Translation uncertaint X, Y, and Z (m).", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2795,7 +2795,7 @@ struct MetadataFor /* .name = */ "attitude_unc", /* .docs = */ "Attitude uncertainty, X, Y, and Z (radians).", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/data_gnss.hpp b/src/cpp/mip/metadata/definitions/data_gnss.hpp index 173087f18..ab0ca985e 100644 --- a/src/cpp/mip/metadata/definitions/data_gnss.hpp +++ b/src/cpp/mip/metadata/definitions/data_gnss.hpp @@ -43,7 +43,7 @@ struct MetadataFor /* .name = */ "latitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -52,7 +52,7 @@ struct MetadataFor /* .name = */ "longitude", /* .docs = */ "[degrees]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -61,7 +61,7 @@ struct MetadataFor /* .name = */ "ellipsoid_height", /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -70,7 +70,7 @@ struct MetadataFor /* .name = */ "msl_height", /* .docs = */ "[meters]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -79,7 +79,7 @@ struct MetadataFor /* .name = */ "horizontal_accuracy", /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -88,7 +88,7 @@ struct MetadataFor /* .name = */ "vertical_accuracy", /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -97,7 +97,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -146,7 +146,7 @@ struct MetadataFor /* .name = */ "x", /* .docs = */ "[meters]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -155,7 +155,7 @@ struct MetadataFor /* .name = */ "x_accuracy", /* .docs = */ "[meters]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -164,7 +164,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -217,7 +217,7 @@ struct MetadataFor /* .name = */ "v", /* .docs = */ "[meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -226,7 +226,7 @@ struct MetadataFor /* .name = */ "speed", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -235,7 +235,7 @@ struct MetadataFor /* .name = */ "ground_speed", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -244,7 +244,7 @@ struct MetadataFor /* .name = */ "heading", /* .docs = */ "[degrees]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -253,7 +253,7 @@ struct MetadataFor /* .name = */ "speed_accuracy", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -262,7 +262,7 @@ struct MetadataFor /* .name = */ "heading_accuracy", /* .docs = */ "[degrees]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -271,7 +271,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -320,7 +320,7 @@ struct MetadataFor /* .name = */ "v", /* .docs = */ "[meters/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -329,7 +329,7 @@ struct MetadataFor /* .name = */ "v_accuracy", /* .docs = */ "[meters/second]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -338,7 +338,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -392,7 +392,7 @@ struct MetadataFor /* .name = */ "gdop", /* .docs = */ "Geometric DOP", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -401,7 +401,7 @@ struct MetadataFor /* .name = */ "pdop", /* .docs = */ "Position DOP", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -410,7 +410,7 @@ struct MetadataFor /* .name = */ "hdop", /* .docs = */ "Horizontal DOP", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -419,7 +419,7 @@ struct MetadataFor /* .name = */ "vdop", /* .docs = */ "Vertical DOP", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -428,7 +428,7 @@ struct MetadataFor /* .name = */ "tdop", /* .docs = */ "Time DOP", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -437,7 +437,7 @@ struct MetadataFor /* .name = */ "ndop", /* .docs = */ "Northing DOP", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -446,7 +446,7 @@ struct MetadataFor /* .name = */ "edop", /* .docs = */ "Easting DOP", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -455,7 +455,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -504,7 +504,7 @@ struct MetadataFor /* .name = */ "year", /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -513,7 +513,7 @@ struct MetadataFor /* .name = */ "month", /* .docs = */ "Month (1-12)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -522,7 +522,7 @@ struct MetadataFor /* .name = */ "day", /* .docs = */ "Day (1-31)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -531,7 +531,7 @@ struct MetadataFor /* .name = */ "hour", /* .docs = */ "Hour (0-23)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -540,7 +540,7 @@ struct MetadataFor /* .name = */ "min", /* .docs = */ "Minute (0-59)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -549,7 +549,7 @@ struct MetadataFor /* .name = */ "sec", /* .docs = */ "Second (0-59)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -558,7 +558,7 @@ struct MetadataFor /* .name = */ "msec", /* .docs = */ "Millisecond(0-999)", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -567,7 +567,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -616,7 +616,7 @@ struct MetadataFor /* .name = */ "tow", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -625,7 +625,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -634,7 +634,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -684,7 +684,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "[seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -693,7 +693,7 @@ struct MetadataFor /* .name = */ "drift", /* .docs = */ "[seconds/second]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -702,7 +702,7 @@ struct MetadataFor /* .name = */ "accuracy_estimate", /* .docs = */ "[seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -711,7 +711,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -805,7 +805,7 @@ struct MetadataFor /* .name = */ "fix_type", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -814,7 +814,7 @@ struct MetadataFor /* .name = */ "num_sv", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -823,7 +823,7 @@ struct MetadataFor /* .name = */ "fix_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -832,7 +832,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -904,7 +904,7 @@ struct MetadataFor /* .name = */ "channel", /* .docs = */ "Receiver channel number", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -913,7 +913,7 @@ struct MetadataFor /* .name = */ "sv_id", /* .docs = */ "GNSS Satellite ID", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -922,7 +922,7 @@ struct MetadataFor /* .name = */ "carrier_noise_ratio", /* .docs = */ "[dBHz]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -931,7 +931,7 @@ struct MetadataFor /* .name = */ "azimuth", /* .docs = */ "[deg]", /* .type = */ {Type::S16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -940,7 +940,7 @@ struct MetadataFor /* .name = */ "elevation", /* .docs = */ "[deg]", /* .type = */ {Type::S16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -949,7 +949,7 @@ struct MetadataFor /* .name = */ "sv_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -958,7 +958,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1070,7 +1070,7 @@ struct MetadataFor /* .name = */ "receiver_state", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1079,7 +1079,7 @@ struct MetadataFor /* .name = */ "antenna_state", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1088,7 +1088,7 @@ struct MetadataFor /* .name = */ "antenna_power", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1097,7 +1097,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1148,7 +1148,7 @@ struct MetadataFor /* .name = */ "sv_id", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1157,7 +1157,7 @@ struct MetadataFor /* .name = */ "age", /* .docs = */ "", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1166,7 +1166,7 @@ struct MetadataFor /* .name = */ "range_correction", /* .docs = */ "", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1175,7 +1175,7 @@ struct MetadataFor /* .name = */ "range_rate_correction", /* .docs = */ "", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1184,7 +1184,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1235,7 +1235,7 @@ struct MetadataFor /* .name = */ "sv_id", /* .docs = */ "", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1244,7 +1244,7 @@ struct MetadataFor /* .name = */ "age", /* .docs = */ "[s]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1253,7 +1253,7 @@ struct MetadataFor /* .name = */ "range_correction", /* .docs = */ "[m]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1262,7 +1262,7 @@ struct MetadataFor /* .name = */ "range_rate_correction", /* .docs = */ "[m/s]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1271,7 +1271,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1322,7 +1322,7 @@ struct MetadataFor /* .name = */ "bias", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1331,7 +1331,7 @@ struct MetadataFor /* .name = */ "drift", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1340,7 +1340,7 @@ struct MetadataFor /* .name = */ "bias_accuracy_estimate", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1349,7 +1349,7 @@ struct MetadataFor /* .name = */ "drift_accuracy_estimate", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1358,7 +1358,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1405,7 +1405,7 @@ struct MetadataFor /* .name = */ "leap_seconds", /* .docs = */ "[s]", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1414,7 +1414,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1510,7 +1510,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1519,7 +1519,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1528,7 +1528,7 @@ struct MetadataFor /* .name = */ "sbas_system", /* .docs = */ "SBAS system id", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1537,7 +1537,7 @@ struct MetadataFor /* .name = */ "sbas_id", /* .docs = */ "SBAS satellite id.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1546,7 +1546,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Number of SBAS corrections", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1555,7 +1555,7 @@ struct MetadataFor /* .name = */ "sbas_status", /* .docs = */ "Status of the SBAS service", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1564,7 +1564,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1637,7 +1637,7 @@ struct MetadataFor /* .name = */ "index", /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1646,7 +1646,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1655,7 +1655,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week the message was received [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1664,7 +1664,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1673,7 +1673,7 @@ struct MetadataFor /* .name = */ "gnss_id", /* .docs = */ "GNSS constellation id", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1682,7 +1682,7 @@ struct MetadataFor /* .name = */ "sv_id", /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1691,7 +1691,7 @@ struct MetadataFor /* .name = */ "udrei", /* .docs = */ "[See above 0-13 usable, 14 not monitored, 15 - do not use]", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1700,7 +1700,7 @@ struct MetadataFor /* .name = */ "pseudorange_correction", /* .docs = */ "Pseudo-range correction [meters].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1709,7 +1709,7 @@ struct MetadataFor /* .name = */ "iono_correction", /* .docs = */ "Ionospheric correction [meters].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1718,7 +1718,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1831,7 +1831,7 @@ struct MetadataFor /* .name = */ "rf_band", /* .docs = */ "RF Band of the reported information", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1840,7 +1840,7 @@ struct MetadataFor /* .name = */ "jamming_state", /* .docs = */ "GNSS Jamming State (as reported by the GNSS module)", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1849,7 +1849,7 @@ struct MetadataFor /* .name = */ "spoofing_state", /* .docs = */ "GNSS Spoofing State (as reported by the GNSS module)", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1858,7 +1858,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "Reserved for future use", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, @@ -1867,7 +1867,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1946,7 +1946,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week the message was received [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1955,7 +1955,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1964,7 +1964,7 @@ struct MetadataFor /* .name = */ "ecef_pos", /* .docs = */ "Earth-centered, Earth-fixed [m]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1973,7 +1973,7 @@ struct MetadataFor /* .name = */ "height", /* .docs = */ "Antenna Height above the marker used in the survey [m]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1982,7 +1982,7 @@ struct MetadataFor /* .name = */ "station_id", /* .docs = */ "Range: 0-4095", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -1991,7 +1991,7 @@ struct MetadataFor /* .name = */ "indicators", /* .docs = */ "Bitfield", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2000,7 +2000,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2081,7 +2081,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2090,7 +2090,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2099,7 +2099,7 @@ struct MetadataFor /* .name = */ "epoch_status", /* .docs = */ "Status of the corrections received during this epoch", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2108,7 +2108,7 @@ struct MetadataFor /* .name = */ "dongle_status", /* .docs = */ "RTK Dongle Status Flags (valid only when using RTK dongle, see Get RTK Device Status Flags (0x0F,0x01) for details)", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2117,7 +2117,7 @@ struct MetadataFor /* .name = */ "gps_correction_latency", /* .docs = */ "Latency of last GPS correction [seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2126,7 +2126,7 @@ struct MetadataFor /* .name = */ "glonass_correction_latency", /* .docs = */ "Latency of last GLONASS correction [seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2135,7 +2135,7 @@ struct MetadataFor /* .name = */ "galileo_correction_latency", /* .docs = */ "Latency of last Galileo correction [seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2144,7 +2144,7 @@ struct MetadataFor /* .name = */ "beidou_correction_latency", /* .docs = */ "Latency of last Beidou correction [seconds]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2153,7 +2153,7 @@ struct MetadataFor /* .name = */ "reserved", /* .docs = */ "Reserved for future use", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, @@ -2162,7 +2162,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2216,7 +2216,7 @@ struct MetadataFor /* .name = */ "index", /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2225,7 +2225,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2234,7 +2234,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2243,7 +2243,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2252,7 +2252,7 @@ struct MetadataFor /* .name = */ "gnss_id", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2261,7 +2261,7 @@ struct MetadataFor /* .name = */ "satellite_id", /* .docs = */ "GNSS satellite id within the constellation", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2270,7 +2270,7 @@ struct MetadataFor /* .name = */ "elevation", /* .docs = */ "Elevation of the satellite relative to the rover [degrees]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2279,7 +2279,7 @@ struct MetadataFor /* .name = */ "azimuth", /* .docs = */ "Azimuth of the satellite relative to the rover [degrees]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2288,7 +2288,7 @@ struct MetadataFor /* .name = */ "health", /* .docs = */ "True if the satellite is healthy.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2297,7 +2297,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2466,7 +2466,7 @@ struct MetadataFor /* .name = */ "index", /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2475,7 +2475,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2484,7 +2484,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2493,7 +2493,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2502,7 +2502,7 @@ struct MetadataFor /* .name = */ "receiver_id", /* .docs = */ "When the measurement comes from RTCM, this will be the reference station ID; otherwise, it's the receiver number (1,2,...)", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2511,7 +2511,7 @@ struct MetadataFor /* .name = */ "tracking_channel", /* .docs = */ "Channel the receiver is using to track this satellite.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2520,7 +2520,7 @@ struct MetadataFor /* .name = */ "gnss_id", /* .docs = */ "", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2529,7 +2529,7 @@ struct MetadataFor /* .name = */ "satellite_id", /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2538,7 +2538,7 @@ struct MetadataFor /* .name = */ "signal_id", /* .docs = */ "Signal identifier for the satellite.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2547,7 +2547,7 @@ struct MetadataFor /* .name = */ "signal_strength", /* .docs = */ "Carrier to noise ratio [dBHz].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2556,7 +2556,7 @@ struct MetadataFor /* .name = */ "quality", /* .docs = */ "Indicator of signal quality.", /* .type = */ {Type::ENUM, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2565,7 +2565,7 @@ struct MetadataFor /* .name = */ "pseudorange", /* .docs = */ "Pseudo-range measurement [meters].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2574,7 +2574,7 @@ struct MetadataFor /* .name = */ "carrier_phase", /* .docs = */ "Carrier phase measurement [Carrier periods].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2583,7 +2583,7 @@ struct MetadataFor /* .name = */ "doppler", /* .docs = */ "Measured doppler shift [Hz].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2592,7 +2592,7 @@ struct MetadataFor /* .name = */ "range_uncert", /* .docs = */ "Uncertainty of the pseudo-range measurement [m].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2601,7 +2601,7 @@ struct MetadataFor /* .name = */ "phase_uncert", /* .docs = */ "Uncertainty of the phase measurement [Carrier periods].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2610,7 +2610,7 @@ struct MetadataFor /* .name = */ "doppler_uncert", /* .docs = */ "Uncertainty of the measured doppler shift [Hz].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2619,7 +2619,7 @@ struct MetadataFor /* .name = */ "lock_time", /* .docs = */ "DOC\nMinimum carrier phase lock time [s]. Note: the maximum value is dependent on the receiver.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2628,7 +2628,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2678,7 +2678,7 @@ struct MetadataFor /* .name = */ "index", /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2687,7 +2687,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2696,7 +2696,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2705,7 +2705,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2714,7 +2714,7 @@ struct MetadataFor /* .name = */ "satellite_id", /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2723,7 +2723,7 @@ struct MetadataFor /* .name = */ "health", /* .docs = */ "Satellite and signal health", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2732,7 +2732,7 @@ struct MetadataFor /* .name = */ "iodc", /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2741,7 +2741,7 @@ struct MetadataFor /* .name = */ "iode", /* .docs = */ "Issue of Data Ephemeris.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2750,7 +2750,7 @@ struct MetadataFor /* .name = */ "t_oc", /* .docs = */ "Reference time for clock data.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2759,7 +2759,7 @@ struct MetadataFor /* .name = */ "af0", /* .docs = */ "Clock bias in [s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2768,7 +2768,7 @@ struct MetadataFor /* .name = */ "af1", /* .docs = */ "Clock drift in [s/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2777,7 +2777,7 @@ struct MetadataFor /* .name = */ "af2", /* .docs = */ "Clock drift rate in [s/s^2].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2786,7 +2786,7 @@ struct MetadataFor /* .name = */ "t_gd", /* .docs = */ "T Group Delay [s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2795,7 +2795,7 @@ struct MetadataFor /* .name = */ "ISC_L1CA", /* .docs = */ "Inter-signal correction (L1).", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2804,7 +2804,7 @@ struct MetadataFor /* .name = */ "ISC_L2C", /* .docs = */ "Inter-signal correction (L2, or L5 if isc_l5 flag is set).", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2813,7 +2813,7 @@ struct MetadataFor /* .name = */ "t_oe", /* .docs = */ "Reference time for ephemeris in [s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2822,7 +2822,7 @@ struct MetadataFor /* .name = */ "a", /* .docs = */ "Semi-major axis [m].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2831,7 +2831,7 @@ struct MetadataFor /* .name = */ "a_dot", /* .docs = */ "Semi-major axis rate [m/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2840,7 +2840,7 @@ struct MetadataFor /* .name = */ "mean_anomaly", /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2849,7 +2849,7 @@ struct MetadataFor /* .name = */ "delta_mean_motion", /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2858,7 +2858,7 @@ struct MetadataFor /* .name = */ "delta_mean_motion_dot", /* .docs = */ "[rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2867,7 +2867,7 @@ struct MetadataFor /* .name = */ "eccentricity", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2876,7 +2876,7 @@ struct MetadataFor /* .name = */ "argument_of_perigee", /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2885,7 +2885,7 @@ struct MetadataFor /* .name = */ "omega", /* .docs = */ "Longitude of Ascending Node [rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2894,7 +2894,7 @@ struct MetadataFor /* .name = */ "omega_dot", /* .docs = */ "Rate of Right Ascension [rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2903,7 +2903,7 @@ struct MetadataFor /* .name = */ "inclination", /* .docs = */ "Inclination angle [rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2912,7 +2912,7 @@ struct MetadataFor /* .name = */ "inclination_dot", /* .docs = */ "Inclination angle rate of change [rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2921,7 +2921,7 @@ struct MetadataFor /* .name = */ "c_ic", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2930,7 +2930,7 @@ struct MetadataFor /* .name = */ "c_is", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2939,7 +2939,7 @@ struct MetadataFor /* .name = */ "c_uc", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2948,7 +2948,7 @@ struct MetadataFor /* .name = */ "c_us", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2957,7 +2957,7 @@ struct MetadataFor /* .name = */ "c_rc", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2966,7 +2966,7 @@ struct MetadataFor /* .name = */ "c_rs", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -2975,7 +2975,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3025,7 +3025,7 @@ struct MetadataFor /* .name = */ "index", /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3034,7 +3034,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3043,7 +3043,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3052,7 +3052,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3061,7 +3061,7 @@ struct MetadataFor /* .name = */ "satellite_id", /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3070,7 +3070,7 @@ struct MetadataFor /* .name = */ "health", /* .docs = */ "Satellite and signal health", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3079,7 +3079,7 @@ struct MetadataFor /* .name = */ "iodc", /* .docs = */ "Issue of Data Clock. This increments each time the data changes and\nrolls over at 4. It is used to make sure various raw data elements from\ndifferent sources line up correctly.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3088,7 +3088,7 @@ struct MetadataFor /* .name = */ "iode", /* .docs = */ "Issue of Data Ephemeris.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3097,7 +3097,7 @@ struct MetadataFor /* .name = */ "t_oc", /* .docs = */ "Reference time for clock data.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3106,7 +3106,7 @@ struct MetadataFor /* .name = */ "af0", /* .docs = */ "Clock bias in [s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3115,7 +3115,7 @@ struct MetadataFor /* .name = */ "af1", /* .docs = */ "Clock drift in [s/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3124,7 +3124,7 @@ struct MetadataFor /* .name = */ "af2", /* .docs = */ "Clock drift rate in [s/s^2].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3133,7 +3133,7 @@ struct MetadataFor /* .name = */ "t_gd", /* .docs = */ "T Group Delay [s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3142,7 +3142,7 @@ struct MetadataFor /* .name = */ "ISC_L1CA", /* .docs = */ "Inter-signal correction (L1).", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3151,7 +3151,7 @@ struct MetadataFor /* .name = */ "ISC_L2C", /* .docs = */ "Inter-signal correction (L2, or L5 if isc_l5 flag is set).", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3160,7 +3160,7 @@ struct MetadataFor /* .name = */ "t_oe", /* .docs = */ "Reference time for ephemeris in [s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3169,7 +3169,7 @@ struct MetadataFor /* .name = */ "a", /* .docs = */ "Semi-major axis [m].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3178,7 +3178,7 @@ struct MetadataFor /* .name = */ "a_dot", /* .docs = */ "Semi-major axis rate [m/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3187,7 +3187,7 @@ struct MetadataFor /* .name = */ "mean_anomaly", /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3196,7 +3196,7 @@ struct MetadataFor /* .name = */ "delta_mean_motion", /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3205,7 +3205,7 @@ struct MetadataFor /* .name = */ "delta_mean_motion_dot", /* .docs = */ "[rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3214,7 +3214,7 @@ struct MetadataFor /* .name = */ "eccentricity", /* .docs = */ "", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3223,7 +3223,7 @@ struct MetadataFor /* .name = */ "argument_of_perigee", /* .docs = */ "[rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3232,7 +3232,7 @@ struct MetadataFor /* .name = */ "omega", /* .docs = */ "Longitude of Ascending Node [rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3241,7 +3241,7 @@ struct MetadataFor /* .name = */ "omega_dot", /* .docs = */ "Rate of Right Ascension [rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3250,7 +3250,7 @@ struct MetadataFor /* .name = */ "inclination", /* .docs = */ "Inclination angle [rad].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3259,7 +3259,7 @@ struct MetadataFor /* .name = */ "inclination_dot", /* .docs = */ "Inclination angle rate of change [rad/s].", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3268,7 +3268,7 @@ struct MetadataFor /* .name = */ "c_ic", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3277,7 +3277,7 @@ struct MetadataFor /* .name = */ "c_is", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3286,7 +3286,7 @@ struct MetadataFor /* .name = */ "c_uc", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3295,7 +3295,7 @@ struct MetadataFor /* .name = */ "c_us", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3304,7 +3304,7 @@ struct MetadataFor /* .name = */ "c_rc", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3313,7 +3313,7 @@ struct MetadataFor /* .name = */ "c_rs", /* .docs = */ "Harmonic Correction Term.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3322,7 +3322,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3370,7 +3370,7 @@ struct MetadataFor /* .name = */ "index", /* .docs = */ "Index of this field in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3379,7 +3379,7 @@ struct MetadataFor /* .name = */ "count", /* .docs = */ "Total number of fields in this epoch.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3388,7 +3388,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3397,7 +3397,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3406,7 +3406,7 @@ struct MetadataFor /* .name = */ "satellite_id", /* .docs = */ "GNSS satellite id within the constellation.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3415,7 +3415,7 @@ struct MetadataFor /* .name = */ "freq_number", /* .docs = */ "GLONASS frequency number (-7 to 24)", /* .type = */ {Type::S8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3424,7 +3424,7 @@ struct MetadataFor /* .name = */ "tk", /* .docs = */ "Frame start time within current day [seconds]", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3433,7 +3433,7 @@ struct MetadataFor /* .name = */ "tb", /* .docs = */ "Ephemeris reference time [seconds]", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3442,7 +3442,7 @@ struct MetadataFor /* .name = */ "sat_type", /* .docs = */ "Type of satellite (M) GLONASS = 0, GLONASS-M = 1", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3451,7 +3451,7 @@ struct MetadataFor /* .name = */ "gamma", /* .docs = */ "Relative deviation of carrier frequency from nominal [dimensionless]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3460,7 +3460,7 @@ struct MetadataFor /* .name = */ "tau_n", /* .docs = */ "Time correction relative to GLONASS Time [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3469,7 +3469,7 @@ struct MetadataFor /* .name = */ "x", /* .docs = */ "Satellite PE-90 position [m]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3478,7 +3478,7 @@ struct MetadataFor /* .name = */ "v", /* .docs = */ "Satellite PE-90 velocity [m/s]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3487,7 +3487,7 @@ struct MetadataFor /* .name = */ "a", /* .docs = */ "Satellite PE-90 acceleration due to perturbations [m/s^2]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3496,7 +3496,7 @@ struct MetadataFor /* .name = */ "health", /* .docs = */ "Satellite Health (Bn), Non-zero indicates satellite malfunction", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3505,7 +3505,7 @@ struct MetadataFor /* .name = */ "P", /* .docs = */ "Satellite operation mode (See GLONASS ICD)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3514,7 +3514,7 @@ struct MetadataFor /* .name = */ "NT", /* .docs = */ "Day number within a 4 year period.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3523,7 +3523,7 @@ struct MetadataFor /* .name = */ "delta_tau_n", /* .docs = */ "Time difference between L1 and L2[m/s]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3532,7 +3532,7 @@ struct MetadataFor /* .name = */ "Ft", /* .docs = */ "User Range Accuracy (See GLONASS ICD)", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3541,7 +3541,7 @@ struct MetadataFor /* .name = */ "En", /* .docs = */ "Age of current information [days]", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3550,7 +3550,7 @@ struct MetadataFor /* .name = */ "P1", /* .docs = */ "Time interval between adjacent values of tb [minutes]", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3559,7 +3559,7 @@ struct MetadataFor /* .name = */ "P2", /* .docs = */ "Oddness '1' or evenness '0' of the value of tb.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3568,7 +3568,7 @@ struct MetadataFor /* .name = */ "P3", /* .docs = */ "Number of satellites in almanac for this frame", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3577,7 +3577,7 @@ struct MetadataFor /* .name = */ "P4", /* .docs = */ "Flag indicating ephemeris parameters are present", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3586,7 +3586,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3637,7 +3637,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3646,7 +3646,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3655,7 +3655,7 @@ struct MetadataFor /* .name = */ "alpha", /* .docs = */ "Ionospheric Correction Terms.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, @@ -3664,7 +3664,7 @@ struct MetadataFor /* .name = */ "beta", /* .docs = */ "Ionospheric Correction Terms.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, @@ -3673,7 +3673,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3724,7 +3724,7 @@ struct MetadataFor /* .name = */ "time_of_week", /* .docs = */ "GPS Time of week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3733,7 +3733,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3742,7 +3742,7 @@ struct MetadataFor /* .name = */ "alpha", /* .docs = */ "Coefficients for the model.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3751,7 +3751,7 @@ struct MetadataFor /* .name = */ "disturbance_flags", /* .docs = */ "Region disturbance flags (bits 1-5).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -3760,7 +3760,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/data_sensor.hpp b/src/cpp/mip/metadata/definitions/data_sensor.hpp index 84d0b6b0a..344f0ebd7 100644 --- a/src/cpp/mip/metadata/definitions/data_sensor.hpp +++ b/src/cpp/mip/metadata/definitions/data_sensor.hpp @@ -20,7 +20,7 @@ struct MetadataFor /* .name = */ "raw_accel", /* .docs = */ "Native sensor counts", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -49,7 +49,7 @@ struct MetadataFor /* .name = */ "raw_gyro", /* .docs = */ "Native sensor counts", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -78,7 +78,7 @@ struct MetadataFor /* .name = */ "raw_mag", /* .docs = */ "Native sensor counts", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -107,7 +107,7 @@ struct MetadataFor /* .name = */ "raw_pressure", /* .docs = */ "Native sensor counts", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -136,7 +136,7 @@ struct MetadataFor /* .name = */ "scaled_accel", /* .docs = */ "(x, y, z)[g]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -165,7 +165,7 @@ struct MetadataFor /* .name = */ "scaled_gyro", /* .docs = */ "(x, y, z) [radians/second]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -194,7 +194,7 @@ struct MetadataFor /* .name = */ "scaled_mag", /* .docs = */ "(x, y, z) [Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -223,7 +223,7 @@ struct MetadataFor /* .name = */ "scaled_pressure", /* .docs = */ "[mBar]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -252,7 +252,7 @@ struct MetadataFor /* .name = */ "delta_theta", /* .docs = */ "(x, y, z) [radians]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -281,7 +281,7 @@ struct MetadataFor /* .name = */ "delta_velocity", /* .docs = */ "(x, y, z) [g*sec]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -310,7 +310,7 @@ struct MetadataFor /* .name = */ "m", /* .docs = */ "Matrix elements in row-major order.", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -339,7 +339,7 @@ struct MetadataFor /* .name = */ "q", /* .docs = */ "Quaternion elements EQSTART q = (q_w, q_x, q_y, q_z) EQEND", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -368,7 +368,7 @@ struct MetadataFor /* .name = */ "roll", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -377,7 +377,7 @@ struct MetadataFor /* .name = */ "pitch", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -386,7 +386,7 @@ struct MetadataFor /* .name = */ "yaw", /* .docs = */ "[radians]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -415,7 +415,7 @@ struct MetadataFor /* .name = */ "m", /* .docs = */ "", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -444,7 +444,7 @@ struct MetadataFor /* .name = */ "raw_temp", /* .docs = */ "", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 4, /* .condition = */ {}, @@ -473,7 +473,7 @@ struct MetadataFor /* .name = */ "counts", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -502,7 +502,7 @@ struct MetadataFor /* .name = */ "seconds", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -511,7 +511,7 @@ struct MetadataFor /* .name = */ "useconds", /* .docs = */ "", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -562,7 +562,7 @@ struct MetadataFor /* .name = */ "tow", /* .docs = */ "GPS Time of Week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -571,7 +571,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week Number since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -580,7 +580,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -609,7 +609,7 @@ struct MetadataFor /* .name = */ "min_temp", /* .docs = */ "[degC]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -618,7 +618,7 @@ struct MetadataFor /* .name = */ "max_temp", /* .docs = */ "[degC]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -627,7 +627,7 @@ struct MetadataFor /* .name = */ "mean_temp", /* .docs = */ "[degC]", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -656,7 +656,7 @@ struct MetadataFor /* .name = */ "up", /* .docs = */ "[Gs]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -685,7 +685,7 @@ struct MetadataFor /* .name = */ "north", /* .docs = */ "[Gauss]", /* .type = */ {Type::STRUCT, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -741,7 +741,7 @@ struct MetadataFor /* .name = */ "status", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -770,7 +770,7 @@ struct MetadataFor /* .name = */ "speed", /* .docs = */ "Average speed over the time interval [m/s]. Can be negative for quadrature encoders.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -779,7 +779,7 @@ struct MetadataFor /* .name = */ "uncertainty", /* .docs = */ "Uncertainty of velocity [m/s].", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -788,7 +788,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "If odometer is configured, bit 0 will be set to 1.", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/data_shared.hpp b/src/cpp/mip/metadata/definitions/data_shared.hpp index d50165899..4122ba7d0 100644 --- a/src/cpp/mip/metadata/definitions/data_shared.hpp +++ b/src/cpp/mip/metadata/definitions/data_shared.hpp @@ -20,7 +20,7 @@ struct MetadataFor /* .name = */ "trigger_id", /* .docs = */ "Trigger ID number. If 0, this message was emitted due to being\nscheduled in the 3DM Message Format Command (0x0C,0x0F).", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -49,7 +49,7 @@ struct MetadataFor /* .name = */ "ticks", /* .docs = */ "Ticks since powerup.", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -78,7 +78,7 @@ struct MetadataFor /* .name = */ "ticks", /* .docs = */ "Ticks since last output.", /* .type = */ {Type::U32, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -127,7 +127,7 @@ struct MetadataFor /* .name = */ "tow", /* .docs = */ "GPS Time of Week [seconds]", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -136,7 +136,7 @@ struct MetadataFor /* .name = */ "week_number", /* .docs = */ "GPS Week Number since 1980 [weeks]", /* .type = */ {Type::U16, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -145,7 +145,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -174,7 +174,7 @@ struct MetadataFor /* .name = */ "seconds", /* .docs = */ "Seconds since last output.", /* .type = */ {Type::DOUBLE, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -203,7 +203,7 @@ struct MetadataFor /* .name = */ "nanoseconds", /* .docs = */ "Nanoseconds since initialization.", /* .type = */ {Type::U64, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -232,7 +232,7 @@ struct MetadataFor /* .name = */ "dt_nanos", /* .docs = */ "Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source.", /* .type = */ {Type::U64, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -279,7 +279,7 @@ struct MetadataFor /* .name = */ "nanoseconds", /* .docs = */ "", /* .type = */ {Type::U64, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -288,7 +288,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -335,7 +335,7 @@ struct MetadataFor /* .name = */ "dt_nanos", /* .docs = */ "Nanoseconds since the last occurrence of this field in a packet of the same descriptor set and event source.", /* .type = */ {Type::U64, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -344,7 +344,7 @@ struct MetadataFor /* .name = */ "valid_flags", /* .docs = */ "", /* .type = */ {Type::BITS, &MetadataFor::value}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, diff --git a/src/cpp/mip/metadata/definitions/data_system.hpp b/src/cpp/mip/metadata/definitions/data_system.hpp index dd382fc1a..70b21cfc4 100644 --- a/src/cpp/mip/metadata/definitions/data_system.hpp +++ b/src/cpp/mip/metadata/definitions/data_system.hpp @@ -20,7 +20,7 @@ struct MetadataFor /* .name = */ "result", /* .docs = */ "Device-specific bitfield (128 bits). See device user manual.\nBits are least-significant-byte first. For example, bit 0 is\nlocated at bit 0 of result[0], bit 1 is located at bit 1 of result[0],\nbit 8 is located at bit 0 of result[1], and bit 127 is located at bit\n7 of result[15].", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 16, /* .condition = */ {}, @@ -49,7 +49,7 @@ struct MetadataFor /* .name = */ "time_sync", /* .docs = */ "True if sync with the PPS signal is currently valid. False if PPS\nfeature is disabled or a PPS signal is not detected.", /* .type = */ {Type::BOOL, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -58,7 +58,7 @@ struct MetadataFor /* .name = */ "last_pps_rcvd", /* .docs = */ "Elapsed time in seconds since last PPS was received, with a maximum\nvalue of 255.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -87,7 +87,7 @@ struct MetadataFor /* .name = */ "states", /* .docs = */ "Bitfield containing the states for each GPIO pin.
\nBit 0 (0x01): pin 1
\nBit 1 (0x02): pin 2
\nBit 2 (0x04): pin 3
\nBit 3 (0x08): pin 4
\nBits for pins that don't exist will read as 0.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -116,7 +116,7 @@ struct MetadataFor /* .name = */ "gpio_id", /* .docs = */ "GPIO pin number starting with 1.", /* .type = */ {Type::U8, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, @@ -125,7 +125,7 @@ struct MetadataFor /* .name = */ "value", /* .docs = */ "Value of the GPIO line in scaled volts.", /* .type = */ {Type::FLOAT, nullptr}, - /* .accessor = */ utils::access, + /* .accessor = */ nullptr, //utils::access, /* .attributes = */ {true, false, false, false, false}, /* .count = */ 1, /* .condition = */ {}, From 1f3f7762db9117725bdf258816ebfc69b287c671 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 20 Sep 2024 13:31:24 -0400 Subject: [PATCH 121/147] Moved documentation build back to Windows Need to configure the Linux builder with Doxygen before switching --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 11e97bb50..2bd14a899 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -39,7 +39,7 @@ pipeline { // Run all the builds in parallel parallel { stage('Documentation') { - agent { label 'linux-amd64' } + agent { label 'windows10' } options { skipDefaultCheckout() timeout(time: 5, activity: true, unit: 'MINUTES') From 820a3f15fffc4859b8cbe6d3f7a702f42b63d458 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 20 Sep 2024 14:14:15 -0400 Subject: [PATCH 122/147] Fix warning in mip_device_models.c --- src/c/mip/mip_device_models.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/c/mip/mip_device_models.c b/src/c/mip/mip_device_models.c index 12b8bed75..5bd4d47bd 100644 --- a/src/c/mip/mip_device_models.c +++ b/src/c/mip/mip_device_models.c @@ -41,7 +41,7 @@ mip_model_number get_model_from_string(const char* model_or_serial) if (i < start_index + 4) return MODEL_UNKNOWN; - return atoi(model_or_serial + start_index); + return (mip_model_number)atoi(model_or_serial + start_index); } const char* get_model_name_from_number(mip_model_number model) From 26085796926b4f47d01863f316c588151f95ecbf Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 20 Sep 2024 14:23:45 -0400 Subject: [PATCH 123/147] Remove access references in metadata common. --- src/cpp/mip/metadata/definitions/common.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/cpp/mip/metadata/definitions/common.hpp b/src/cpp/mip/metadata/definitions/common.hpp index 062b9e59b..1d2dc2e6c 100644 --- a/src/cpp/mip/metadata/definitions/common.hpp +++ b/src/cpp/mip/metadata/definitions/common.hpp @@ -78,7 +78,7 @@ struct MetadataFor /*.name =*/ "cmd_field_desc", /*.docs =*/ "The field descriptor of the command this field acknowledges.", /*.type =*/ {Type::U8}, - /*.accessor =*/ utils::access, + /*.accessor =*/ nullptr, //utils::access, /*.attributes =*/ NO_FUNCTIONS, /*.count =*/ 1, /*.condition =*/ {}, @@ -87,7 +87,7 @@ struct MetadataFor /*.name =*/ "result", /*.docs =*/ "Result of the command.", /*.type =*/ {Type::ENUM, &MetadataFor::value}, - /*.accessor =*/ utils::access, + /*.accessor =*/ nullptr, //utils::access, /*.attributes =*/ NO_FUNCTIONS, /*.count =*/ 1, /*.condition =*/ {}, @@ -116,7 +116,7 @@ struct MetadataFor /*.name =*/ "descriptor", /*.docs =*/ "MIP data descriptor", /*.type =*/ {Type::U8}, - /*.accessor =*/ utils::access, + /*.accessor =*/ nullptr, //utils::access, /*.attributes =*/ NO_FUNCTIONS, /*.count =*/ 1, /*.condition =*/ {}, @@ -125,7 +125,7 @@ struct MetadataFor /*.name =*/ "decimation", /*.docs =*/ "Decimation from the base rate", /*.type =*/ {Type::U16}, - /*.accessor =*/ utils::access, + /*.accessor =*/ nullptr, //utils::access, /*.attributes =*/ NO_FUNCTIONS, /*.count =*/ 1, /*.condition =*/ {}, From 794ca890d41c38f7941fc18b57c45d736873d6f4 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 20 Sep 2024 14:47:55 -0400 Subject: [PATCH 124/147] Fixed nested namespace (C++17 feature) --- .../common/serialization/readwrite.hpp | 21 +++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/src/cpp/microstrain/common/serialization/readwrite.hpp b/src/cpp/microstrain/common/serialization/readwrite.hpp index 66697534e..7fc092b54 100644 --- a/src/cpp/microstrain/common/serialization/readwrite.hpp +++ b/src/cpp/microstrain/common/serialization/readwrite.hpp @@ -20,14 +20,19 @@ #include -namespace microstrain::serialization +namespace microstrain +{ +namespace serialization { using Endian = std::endian; -} // namespace microstrain::serialization +} // namespace serialization +} // namespace microstrain #else // MICROSTRAIN_USE_STD_ENDIAN -namespace microstrain::serialization +namespace microstrain +{ +namespace serialization { enum class Endian @@ -37,11 +42,14 @@ enum class Endian //native = little, }; -} // namespace microstrain::serialization +} // namespace serialization +} // namespace microstrain #endif // MICROSTRAIN_USE_STD_ENDIAN -namespace microstrain::serialization +namespace microstrain +{ +namespace serialization { // @@ -194,4 +202,5 @@ T read(const uint8_t* buffer) return value; } -} // namespace microstrain::serialization +} // namespace serialization +} // namespace microstrain From 6520dea4513fc0a80073bff4af0ca4b4c91ab166 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 20 Sep 2024 14:48:18 -0400 Subject: [PATCH 125/147] Examples improvements Made examples more explicit --- examples/CSV/stringify.cpp | 110 ++++++++--------- examples/CV7/CV7_example.cpp | 105 ++++++++-------- examples/CV7_INS/CV7_INS_simple_example.cpp | 93 +++++++------- .../CV7_INS/CV7_INS_simple_ublox_example.cpp | 115 +++++++++--------- examples/CX5_GX5_45/CX5_GX5_45_example.cpp | 95 +++++++-------- .../CX5_GX5_CV5_15_25_example.cpp | 83 ++++++------- examples/GQ7/GQ7_example.cpp | 113 +++++++++-------- 7 files changed, 349 insertions(+), 365 deletions(-) diff --git a/examples/CSV/stringify.cpp b/examples/CSV/stringify.cpp index 3156e2005..ad519a207 100644 --- a/examples/CSV/stringify.cpp +++ b/examples/CSV/stringify.cpp @@ -17,9 +17,7 @@ #error "Needs optional support" #endif -using namespace mip::metadata; - -extern Definitions mipdefs; +extern mip::metadata::Definitions mipdefs; struct Formatter @@ -30,12 +28,12 @@ struct Formatter std::ostream& ss; std::array offsets; - std::ostream& formatEnum(const EnumInfo* info); - std::ostream& formatBitfield(const BitfieldInfo* info); - std::ostream& formatUnion(const UnionInfo* info, const StructInfo& parent, size_t offset_index); - std::ostream& formatStruct(const StructInfo* info, size_t offset_index=0); + std::ostream& formatEnum(const mip::metadata::EnumInfo* info); + std::ostream& formatBitfield(const mip::metadata::BitfieldInfo* info); + std::ostream& formatUnion(const mip::metadata::UnionInfo* info, const mip::metadata::StructInfo& parent, size_t offset_index); + std::ostream& formatStruct(const mip::metadata::StructInfo* info, size_t offset_index=0); - void formatParameter(const ParameterInfo& param, const StructInfo& parent, size_t offset_index=0); + void formatParameter(const mip::metadata::ParameterInfo& param, const mip::metadata::StructInfo& parent, size_t offset_index=0); template std::ostream& formatBasicType(); @@ -77,18 +75,18 @@ std::ostream& Formatter::formatBasicType() ///@returns A uint64_t containing the value. All smaller integers are converted to this type. ///@returns std::nullopt (no value) if the offset/size is beyond the end of the buffer. /// -static std::optional readIntegralValue(Type type, mip::Serializer& serializer) +static std::optional readIntegralValue(mip::metadata::Type type, mip::Serializer& serializer) { switch(type) { - case Type::U8: return microstrain::extract< uint8_t>(serializer); - case Type::S8: return microstrain::extract< int8_t>(serializer); - case Type::U16: return microstrain::extract(serializer); - case Type::S16: return microstrain::extract< int32_t>(serializer); - case Type::U32: return microstrain::extract(serializer); - case Type::S32: return microstrain::extract< int64_t>(serializer); - case Type::U64: return microstrain::extract(serializer); - case Type::S64: return microstrain::extract< int64_t>(serializer); + case mip::metadata::Type::U8: return microstrain::extract< uint8_t>(serializer); + case mip::metadata::Type::S8: return microstrain::extract< int8_t>(serializer); + case mip::metadata::Type::U16: return microstrain::extract(serializer); + case mip::metadata::Type::S16: return microstrain::extract< int32_t>(serializer); + case mip::metadata::Type::U32: return microstrain::extract(serializer); + case mip::metadata::Type::S32: return microstrain::extract< int64_t>(serializer); + case mip::metadata::Type::U64: return microstrain::extract(serializer); + case mip::metadata::Type::S64: return microstrain::extract< int64_t>(serializer); default: return std::nullopt; } } @@ -104,7 +102,7 @@ static std::optional readIntegralValue(Type type, mip::Serializer& ser /// ///@returns ss /// -std::ostream& Formatter::formatEnum(const EnumInfo* info) +std::ostream& Formatter::formatEnum(const mip::metadata::EnumInfo* info) { if(!info) return ss << ""; @@ -116,7 +114,7 @@ std::ostream& Formatter::formatEnum(const EnumInfo* info) auto it = std::find_if( info->entries.begin(), info->entries.end(), - [value](const auto& entry){ return entry.value == value; } + [value](const mip::metadata::EnumInfo::Entry& entry){ return entry.value == value; } ); const char* name = (it != info->entries.end()) ? it->name : "?"; @@ -134,7 +132,7 @@ std::ostream& Formatter::formatEnum(const EnumInfo* info) /// ///@returns ss /// -std::ostream& Formatter::formatBitfield(const BitfieldInfo* info) +std::ostream& Formatter::formatBitfield(const mip::metadata::BitfieldInfo* info) { if(!info) return ss << ""; @@ -146,7 +144,7 @@ std::ostream& Formatter::formatBitfield(const BitfieldInfo* info) ss << '{'; size_t i=0; - for(const auto& entry : info->entries) + for(const mip::metadata::EnumInfo::Entry& entry : info->entries) { if(i > 0) ss << ", "; @@ -162,41 +160,41 @@ std::ostream& Formatter::formatBitfield(const BitfieldInfo* info) return ss; } -void Formatter::formatParameter(const mip::metadata::ParameterInfo ¶m, const StructInfo& parent, size_t offset_index) +void Formatter::formatParameter(const mip::metadata::ParameterInfo ¶m, const mip::metadata::StructInfo& parent, size_t offset_index) { switch(param.type.type) { - case Type::NONE: + case mip::metadata::Type::NONE: ss << "-"; break; - case Type::CHAR: formatBasicType(); break; - case Type::BOOL: formatBasicType(); break; - case Type::U8: formatBasicType(); break; - case Type::S8: formatBasicType< int8_t >(); break; - case Type::U16: formatBasicType(); break; - case Type::S16: formatBasicType< int16_t>(); break; - case Type::U32: formatBasicType(); break; - case Type::S32: formatBasicType< int32_t>(); break; - case Type::U64: formatBasicType(); break; - case Type::S64: formatBasicType< int64_t>(); break; - case Type::FLOAT: formatBasicType(); break; - case Type::DOUBLE: formatBasicType(); break; - - case Type::ENUM: - formatEnum(static_cast(param.type.infoPtr)); + case mip::metadata::Type::CHAR: formatBasicType(); break; + case mip::metadata::Type::BOOL: formatBasicType(); break; + case mip::metadata::Type::U8: formatBasicType(); break; + case mip::metadata::Type::S8: formatBasicType< int8_t >(); break; + case mip::metadata::Type::U16: formatBasicType(); break; + case mip::metadata::Type::S16: formatBasicType< int16_t>(); break; + case mip::metadata::Type::U32: formatBasicType(); break; + case mip::metadata::Type::S32: formatBasicType< int32_t>(); break; + case mip::metadata::Type::U64: formatBasicType(); break; + case mip::metadata::Type::S64: formatBasicType< int64_t>(); break; + case mip::metadata::Type::FLOAT: formatBasicType(); break; + case mip::metadata::Type::DOUBLE: formatBasicType(); break; + + case mip::metadata::Type::ENUM: + formatEnum(static_cast(param.type.infoPtr)); break; - case Type::BITS: - formatBitfield(static_cast(param.type.infoPtr)); + case mip::metadata::Type::BITS: + formatBitfield(static_cast(param.type.infoPtr)); break; - case Type::STRUCT: - formatStruct(static_cast(param.type.infoPtr), offset_index); + case mip::metadata::Type::STRUCT: + formatStruct(static_cast(param.type.infoPtr), offset_index); break; - case Type::UNION: - formatUnion(static_cast(param.type.infoPtr), parent, offset_index); + case mip::metadata::Type::UNION: + formatUnion(static_cast(param.type.infoPtr), parent, offset_index); break; } } @@ -213,7 +211,7 @@ void Formatter::formatParameter(const mip::metadata::ParameterInfo ¶m, const /// ///@returns ss /// -std::ostream& Formatter::formatUnion(const UnionInfo* info, const StructInfo& parent, size_t offset_index) +std::ostream& Formatter::formatUnion(const mip::metadata::UnionInfo* info, const mip::metadata::StructInfo& parent, size_t offset_index) { if(!info) return ss << ""; @@ -222,14 +220,14 @@ std::ostream& Formatter::formatUnion(const UnionInfo* info, const StructInfo& pa ss << info->name << '{'; - for(const auto& param : info->parameters) + for(const mip::metadata::ParameterInfo& param : info->parameters) { // Enum condition, where the active union member depends on a previous parameter's value. - if(param.condition.type == ParameterInfo::Condition::Type::ENUM) + if(param.condition.type == mip::metadata::ParameterInfo::Condition::Type::ENUM) { // Parameter index is within the parent's parameter array. assert(param.condition.paramIdx.isValid(parent.parameters.size())); - const ParameterInfo &discriminant = parent.parameters[param.condition.paramIdx.index()]; + const mip::metadata::ParameterInfo &discriminant = parent.parameters[param.condition.paramIdx.index()]; // Index is within the offset array relative to the parent. assert(offset_index+param.condition.paramIdx.index() < MAX_PARAMETERS); @@ -270,7 +268,7 @@ std::ostream& Formatter::formatUnion(const UnionInfo* info, const StructInfo& pa /// ///@returns ss /// -std::ostream& Formatter::formatStruct(const StructInfo* info, size_t offset_index) +std::ostream& Formatter::formatStruct(const mip::metadata::StructInfo* info, size_t offset_index) { if(!info) return ss << ""; @@ -296,7 +294,7 @@ std::ostream& Formatter::formatStruct(const StructInfo* info, size_t offset_inde for(size_t i=0; iparameters.size(); i++) { - const auto& param = info->parameters[i]; + const mip::metadata::ParameterInfo& param = info->parameters[i]; if(i > 0) ss << ", "; @@ -313,7 +311,7 @@ std::ostream& Formatter::formatStruct(const StructInfo* info, size_t offset_inde { assert(param.count.paramIdx.isValid(i)); // Array size can't come after the array - const ParameterInfo& counter = info->parameters[param.count.paramIdx.index()]; + const mip::metadata::ParameterInfo& counter = info->parameters[param.count.paramIdx.index()]; const size_t counterOffset = offsets[offset_index+param.count.paramIdx.index()]; // Counters must be arithmetic types and can't be arrays. @@ -334,17 +332,17 @@ std::ostream& Formatter::formatStruct(const StructInfo* info, size_t offset_inde count = (uint8_t)*counterValue; } if(param.count.count != 1) - ss << (param.type.type == Type::CHAR ? '"' : '['); + ss << (param.type.type == mip::metadata::Type::CHAR ? '"' : '['); for(uint8_t j=0; j 0 && param.type.type != Type::CHAR) + if(j > 0 && param.type.type != mip::metadata::Type::CHAR) ss << ", "; formatParameter(param, *info, offset_index+i); } if(param.count.count != 1) - ss << (param.type.type == Type::CHAR ? '"' : ']'); + ss << (param.type.type == mip::metadata::Type::CHAR ? '"' : ']'); } ss << '}'; @@ -361,7 +359,7 @@ std::ostream& Formatter::formatStruct(const StructInfo* info, size_t offset_inde /// std::ostream& formatField(std::ostream& ss, const mip::FieldView& field) { - const FieldInfo* info = mipdefs.findField(field.descriptor()); + const mip::metadata::FieldInfo* info = mipdefs.findField(field.descriptor()); if(!info) { @@ -380,7 +378,7 @@ std::ostream& formatField(std::ostream& ss, const mip::FieldView& field) ss, }; - formatter.formatStruct(static_cast(info)); + formatter.formatStruct(static_cast(info)); } return ss; } diff --git a/examples/CV7/CV7_example.cpp b/examples/CV7/CV7_example.cpp index 0c85cfc33..a414e3174 100644 --- a/examples/CV7/CV7_example.cpp +++ b/examples/CV7/CV7_example.cpp @@ -33,8 +33,6 @@ #include -using namespace mip; - //////////////////////////////////////////////////////////////////////////////// // Global Variables //////////////////////////////////////////////////////////////////////////////// @@ -43,14 +41,14 @@ using namespace mip; float sensor_to_vehicle_transformation_euler[3] = {0.0, 0.0, 0.0}; //Device data stores -data_shared::GpsTimestamp sensor_gps_time; -data_sensor::ScaledAccel sensor_accel; -data_sensor::ScaledGyro sensor_gyro; -data_sensor::ScaledMag sensor_mag; +mip::data_shared::GpsTimestamp sensor_gps_time; +mip::data_sensor::ScaledAccel sensor_accel; +mip::data_sensor::ScaledGyro sensor_gyro; +mip::data_sensor::ScaledMag sensor_mag; -data_shared::GpsTimestamp filter_gps_time; -data_filter::Status filter_status; -data_filter::EulerAngles filter_euler_angles; +mip::data_shared::GpsTimestamp filter_gps_time; +mip::data_filter::Status filter_status; +mip::data_filter::EulerAngles filter_euler_angles; bool filter_state_ahrs = false; @@ -94,7 +92,7 @@ int main(int argc, const char* argv[]) //Ping the device (note: this is good to do to make sure the device is present) // - if(commands_base::ping(*device) != CmdResult::ACK_OK) + if(mip::commands_base::ping(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not ping the device!"); @@ -102,7 +100,7 @@ int main(int argc, const char* argv[]) //Idle the device (note: this is good to do during setup) // - if(commands_base::setIdle(*device) != CmdResult::ACK_OK) + if(mip::commands_base::setIdle(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set the device to idle!"); @@ -110,7 +108,7 @@ int main(int argc, const char* argv[]) //Load the device default settings (so the device is in a known state) // - if(commands_3dm::defaultDeviceSettings(*device) != CmdResult::ACK_OK) + if(mip::commands_3dm::defaultDeviceSettings(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not load default device settings!"); @@ -123,20 +121,20 @@ int main(int argc, const char* argv[]) //Note: Querying the device base rate is only one way to calculate the descriptor decimation. //We could have also set it directly with information from the datasheet (shown in GNSS setup). - if(commands_3dm::getBaseRate(*device, data_sensor::DESCRIPTOR_SET, &sensor_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::getBaseRate(*device, mip::data_sensor::DESCRIPTOR_SET, &sensor_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get sensor base rate format!"); const uint16_t sensor_sample_rate = 100; // Hz const uint16_t sensor_decimation = sensor_base_rate / sensor_sample_rate; - std::array sensor_descriptors = {{ - { data_shared::DATA_GPS_TIME, sensor_decimation }, - { data_sensor::DATA_ACCEL_SCALED, sensor_decimation }, - { data_sensor::DATA_GYRO_SCALED, sensor_decimation }, - { data_sensor::DATA_MAG_SCALED, sensor_decimation }, + std::array sensor_descriptors = {{ + { mip::data_shared::DATA_GPS_TIME, sensor_decimation }, + { mip::data_sensor::DATA_ACCEL_SCALED, sensor_decimation }, + { mip::data_sensor::DATA_GYRO_SCALED, sensor_decimation }, + { mip::data_sensor::DATA_MAG_SCALED, sensor_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_sensor::DESCRIPTOR_SET, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeMessageFormat(*device, mip::data_sensor::DESCRIPTOR_SET, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor message format!"); @@ -146,19 +144,19 @@ int main(int argc, const char* argv[]) uint16_t filter_base_rate; - if(commands_3dm::getBaseRate(*device, data_filter::DESCRIPTOR_SET, &filter_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::getBaseRate(*device, mip::data_filter::DESCRIPTOR_SET, &filter_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get filter base rate format!"); const uint16_t filter_sample_rate = 100; // Hz const uint16_t filter_decimation = filter_base_rate / filter_sample_rate; - std::array filter_descriptors = {{ - { data_shared::DATA_GPS_TIME, filter_decimation }, - { data_filter::DATA_FILTER_STATUS, filter_decimation }, - { data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, + std::array filter_descriptors = {{ + { mip::data_shared::DATA_GPS_TIME, filter_decimation }, + { mip::data_filter::DATA_FILTER_STATUS, filter_decimation }, + { mip::data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeMessageFormat(*device, mip::data_filter::DESCRIPTOR_SET, static_cast(filter_descriptors.size()), filter_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); @@ -171,55 +169,55 @@ int main(int argc, const char* argv[]) //EVENTS //Roll - commands_3dm::EventTrigger::Parameters event_params; - event_params.threshold.type = commands_3dm::EventTrigger::ThresholdParams::Type::WINDOW; - event_params.threshold.desc_set = data_filter::DESCRIPTOR_SET; - event_params.threshold.field_desc = data_filter::DATA_ATT_EULER_ANGLES; + mip::commands_3dm::EventTrigger::Parameters event_params; + event_params.threshold.type = mip::commands_3dm::EventTrigger::ThresholdParams::Type::WINDOW; + event_params.threshold.desc_set = mip::data_filter::DESCRIPTOR_SET; + event_params.threshold.field_desc = mip::data_filter::DATA_ATT_EULER_ANGLES; event_params.threshold.param_id = 1; event_params.threshold.high_thres = -0.7853981; event_params.threshold.low_thres = 0.7853981; - if(commands_3dm::writeEventTrigger(*device, FILTER_ROLL_EVENT_ACTION_ID, commands_3dm::EventTrigger::Type::THRESHOLD, event_params) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeEventTrigger(*device, FILTER_ROLL_EVENT_ACTION_ID, mip::commands_3dm::EventTrigger::Type::THRESHOLD, event_params) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set roll event parameters!"); - //Pitch + //Pitch event_params.threshold.param_id = 2; - if(commands_3dm::writeEventTrigger(*device, FILTER_PITCH_EVENT_ACTION_ID, commands_3dm::EventTrigger::Type::THRESHOLD, event_params) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeEventTrigger(*device, FILTER_PITCH_EVENT_ACTION_ID, mip::commands_3dm::EventTrigger::Type::THRESHOLD, event_params) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set pitch event parameters!"); //ACTIONS - //Roll - commands_3dm::EventAction::Parameters event_action; - event_action.message.desc_set = data_filter::DESCRIPTOR_SET; + //Roll + mip::commands_3dm::EventAction::Parameters event_action; + event_action.message.desc_set = mip::data_filter::DESCRIPTOR_SET; event_action.message.num_fields = 1; - event_action.message.descriptors[0] = data_shared::DATA_EVENT_SOURCE; + event_action.message.descriptors[0] = mip::data_shared::DATA_EVENT_SOURCE; event_action.message.decimation = 0; - if(writeEventAction(*device, FILTER_ROLL_EVENT_ACTION_ID, FILTER_ROLL_EVENT_ACTION_ID, commands_3dm::EventAction::Type::MESSAGE, event_action) != CmdResult::ACK_OK) + if(writeEventAction(*device, FILTER_ROLL_EVENT_ACTION_ID, FILTER_ROLL_EVENT_ACTION_ID, mip::commands_3dm::EventAction::Type::MESSAGE, event_action) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set roll action parameters!"); - //Pitch - if(writeEventAction(*device, FILTER_PITCH_EVENT_ACTION_ID, FILTER_PITCH_EVENT_ACTION_ID, commands_3dm::EventAction::Type::MESSAGE, event_action) != CmdResult::ACK_OK) + //Pitch + if(writeEventAction(*device, FILTER_PITCH_EVENT_ACTION_ID, FILTER_PITCH_EVENT_ACTION_ID, mip::commands_3dm::EventAction::Type::MESSAGE, event_action) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set pitch action parameters!"); //ENABLE EVENTS //Roll - if(writeEventControl(*device, FILTER_ROLL_EVENT_ACTION_ID, commands_3dm::EventControl::Mode::ENABLED) != CmdResult::ACK_OK) + if(writeEventControl(*device, FILTER_ROLL_EVENT_ACTION_ID, mip::commands_3dm::EventControl::Mode::ENABLED) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not enable roll event!"); - + //Pitch - if(writeEventControl(*device, FILTER_PITCH_EVENT_ACTION_ID, commands_3dm::EventControl::Mode::ENABLED) != CmdResult::ACK_OK) + if(writeEventControl(*device, FILTER_PITCH_EVENT_ACTION_ID, mip::commands_3dm::EventControl::Mode::ENABLED) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not enable pitch event!"); // //Setup the sensor to vehicle transformation // - if(commands_3dm::writeSensor2VehicleTransformEuler(*device, sensor_to_vehicle_transformation_euler[0], sensor_to_vehicle_transformation_euler[1], sensor_to_vehicle_transformation_euler[2]) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeSensor2VehicleTransformEuler(*device, sensor_to_vehicle_transformation_euler[0], sensor_to_vehicle_transformation_euler[1], sensor_to_vehicle_transformation_euler[2]) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor-to-vehicle transformation!"); @@ -227,7 +225,7 @@ int main(int argc, const char* argv[]) //Setup the filter aiding measurements (GNSS position/velocity and dual antenna [aka gnss heading]) // - if(commands_filter::writeAidingMeasurementEnable(*device, commands_filter::AidingMeasurementEnable::AidingSource::MAGNETOMETER, true) != CmdResult::ACK_OK) + if(mip::commands_filter::writeAidingMeasurementEnable(*device, mip::commands_filter::AidingMeasurementEnable::AidingSource::MAGNETOMETER, true) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter aiding measurement enable!"); @@ -235,7 +233,7 @@ int main(int argc, const char* argv[]) //Reset the filter (note: this is good to do after filter setup is complete) // - if(commands_filter::reset(*device) != CmdResult::ACK_OK) + if(mip::commands_filter::reset(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not reset the filter!"); @@ -244,27 +242,27 @@ int main(int argc, const char* argv[]) // //Sensor Data - DispatchHandler sensor_data_handlers[4]; + mip::DispatchHandler sensor_data_handlers[4]; - device->registerExtractor(sensor_data_handlers[0], &sensor_gps_time, data_sensor::DESCRIPTOR_SET); + device->registerExtractor(sensor_data_handlers[0], &sensor_gps_time, mip::data_sensor::DESCRIPTOR_SET); device->registerExtractor(sensor_data_handlers[1], &sensor_accel); device->registerExtractor(sensor_data_handlers[2], &sensor_gyro); device->registerExtractor(sensor_data_handlers[3], &sensor_mag); //Filter Data - DispatchHandler filter_data_handlers[4]; + mip::DispatchHandler filter_data_handlers[4]; - device->registerExtractor(filter_data_handlers[0], &filter_gps_time, data_filter::DESCRIPTOR_SET); + device->registerExtractor(filter_data_handlers[0], &filter_gps_time, mip::data_filter::DESCRIPTOR_SET); device->registerExtractor(filter_data_handlers[1], &filter_status); device->registerExtractor(filter_data_handlers[2], &filter_euler_angles); - device->registerFieldCallback<&handleFilterEventSource>(filter_data_handlers[3], data_filter::DESCRIPTOR_SET, data_shared::DATA_EVENT_SOURCE); + device->registerFieldCallback<&handleFilterEventSource>(filter_data_handlers[3], mip::data_filter::DESCRIPTOR_SET, mip::data_shared::DATA_EVENT_SOURCE); // //Resume the device // - if(commands_base::resume(*device) != CmdResult::ACK_OK) + if(mip::commands_base::resume(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not resume the device!"); @@ -277,14 +275,14 @@ int main(int argc, const char* argv[]) printf("Sensor is configured... waiting for filter to enter AHRS mode (AHRS).\n"); - auto current_state = std::string{""}; + std::string current_state = ""; while(running) { device->update(); displayFilterState(filter_status.filter_state, current_state); //Check Filter State - if((!filter_state_ahrs) && (filter_status.filter_state == data_filter::FilterMode::AHRS)) + if((!filter_state_ahrs) && (filter_status.filter_state == mip::data_filter::FilterMode::AHRS)) { printf("NOTE: Filter has entered AHRS mode.\n"); filter_state_ahrs = true; @@ -368,4 +366,3 @@ bool should_exit() return false; } - diff --git a/examples/CV7_INS/CV7_INS_simple_example.cpp b/examples/CV7_INS/CV7_INS_simple_example.cpp index c07754dd4..905bb5056 100644 --- a/examples/CV7_INS/CV7_INS_simple_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_example.cpp @@ -30,17 +30,15 @@ #include "example_utils.hpp" #include -using namespace mip; - //////////////////////////////////////////////////////////////////////////////// // Global Variables //////////////////////////////////////////////////////////////////////////////// -data_shared::GpsTimestamp filter_gps_time; -data_filter::Status filter_status; -data_filter::EulerAngles filter_euler_angles; -data_filter::PositionLlh filter_llh_position; -data_filter::VelocityNed filter_ned_velocity; +mip::data_shared::GpsTimestamp filter_gps_time; +mip::data_filter::Status filter_status; +mip::data_filter::EulerAngles filter_euler_angles; +mip::data_filter::PositionLlh filter_llh_position; +mip::data_filter::VelocityNed filter_ned_velocity; uint8_t external_heading_sensor_id = 1; uint8_t gnss_antenna_sensor_id = 2; @@ -54,7 +52,7 @@ bool filter_state_full_nav = false; int usage(const char* argv0); -void print_device_information(const commands_base::BaseDeviceInfo& device_info); +void print_device_information(const mip::commands_base::BaseDeviceInfo& device_info); void exit_gracefully(const char *message); bool should_exit(); @@ -83,15 +81,15 @@ int main(int argc, const char* argv[]) //Ping the device (note: this is good to do to make sure the device is present) // - if(commands_base::ping(*device) != CmdResult::ACK_OK) + if(mip::commands_base::ping(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not ping the device!"); // //Read device information // - commands_base::BaseDeviceInfo device_info; - if(commands_base::getDeviceInfo(*device, &device_info) != CmdResult::ACK_OK) + mip::commands_base::BaseDeviceInfo device_info; + if(mip::commands_base::getDeviceInfo(*device, &device_info) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Failed to get device info"); print_device_information(device_info); @@ -100,7 +98,7 @@ int main(int argc, const char* argv[]) //Idle the device (note: this is good to do during setup) // - if(commands_base::setIdle(*device) != CmdResult::ACK_OK) + if(mip::commands_base::setIdle(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set the device to idle!"); @@ -108,7 +106,7 @@ int main(int argc, const char* argv[]) //Load the device default settings (so the device is in a known state) // - if(commands_3dm::defaultDeviceSettings(*device) != CmdResult::ACK_OK) + if(mip::commands_3dm::defaultDeviceSettings(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not load default device settings!"); @@ -120,33 +118,33 @@ int main(int argc, const char* argv[]) // //External heading sensor reference frame. // - commands_aiding::FrameConfig::Rotation external_heading_sensor_to_vehicle_frame_rotation; + mip::commands_aiding::FrameConfig::Rotation external_heading_sensor_to_vehicle_frame_rotation; external_heading_sensor_to_vehicle_frame_rotation.euler = mip::Vector3f(0.0f, 0.0f, 0.0f); // External heading sensor is aligned with vehicle frame float external_heading_sensor_to_vehicle_frame_translation[3] = {0.0, 0.0, 0.0}; // Heading measurements are agnostic to translation, translation set to zero - if(commands_aiding::writeFrameConfig(*device, external_heading_sensor_id, mip::commands_aiding::FrameConfig::Format::EULER, true, - external_heading_sensor_to_vehicle_frame_translation, external_heading_sensor_to_vehicle_frame_rotation) != CmdResult::ACK_OK) + if(mip::commands_aiding::writeFrameConfig(*device, external_heading_sensor_id, mip::commands_aiding::FrameConfig::Format::EULER, true, + external_heading_sensor_to_vehicle_frame_translation, external_heading_sensor_to_vehicle_frame_rotation) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Unable to configure external heading sensor frame ID"); // //External GNSS antenna reference frame // - commands_aiding::FrameConfig::Rotation external_gnss_antenna_to_vehicle_frame_rotation; + mip::commands_aiding::FrameConfig::Rotation external_gnss_antenna_to_vehicle_frame_rotation; external_gnss_antenna_to_vehicle_frame_rotation.euler = mip::Vector3f(0.0f, 0.0f, 0.0f); // GNSS position/velocity measurements are agnostic to rotation, rotation set to zero float external_gnss_antenna_to_vehicle_frame_translation[3] = {0.0, 1.0, 0.0}; // Antenna is translated 1 meter in vehicle frame Y direction - if(commands_aiding::writeFrameConfig(*device, gnss_antenna_sensor_id, mip::commands_aiding::FrameConfig::Format::EULER, true, - external_gnss_antenna_to_vehicle_frame_translation, external_gnss_antenna_to_vehicle_frame_rotation) != CmdResult::ACK_OK) + if(mip::commands_aiding::writeFrameConfig(*device, gnss_antenna_sensor_id, mip::commands_aiding::FrameConfig::Format::EULER, true, + external_gnss_antenna_to_vehicle_frame_translation, external_gnss_antenna_to_vehicle_frame_rotation) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Unable to configure external GNSS antenna frame ID"); // //External bodyframe velocity reference frame // - commands_aiding::FrameConfig::Rotation external_velocity_sensor_to_vehicle_frame_rotation; + mip::commands_aiding::FrameConfig::Rotation external_velocity_sensor_to_vehicle_frame_rotation; external_velocity_sensor_to_vehicle_frame_rotation.euler= mip::Vector3f(0.0f, 0.0f, 1.57f); // Rotated 90 deg around yaw axis float external_velocity_sensor_to_vehicle_frame_translation[3] = {1.0, 0.0, 0.0}; // Sensor is translated 1 meter in X direction - if(commands_aiding::writeFrameConfig(*device, vehicle_frame_velocity_sensor_id, mip::commands_aiding::FrameConfig::Format::EULER, true, - external_velocity_sensor_to_vehicle_frame_translation, external_velocity_sensor_to_vehicle_frame_rotation) != CmdResult::ACK_OK) + if(mip::commands_aiding::writeFrameConfig(*device, vehicle_frame_velocity_sensor_id, mip::commands_aiding::FrameConfig::Format::EULER, true, + external_velocity_sensor_to_vehicle_frame_translation, external_velocity_sensor_to_vehicle_frame_rotation) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Unable to configure external vehicle frame velocity sensor ID"); @@ -156,39 +154,40 @@ int main(int argc, const char* argv[]) uint16_t filter_base_rate; - if(commands_3dm::getBaseRate(*device, data_filter::DESCRIPTOR_SET, &filter_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::getBaseRate(*device, mip::data_filter::DESCRIPTOR_SET, &filter_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get filter base rate format!"); const uint16_t filter_sample_rate = 100; // Hz const uint16_t filter_decimation = filter_base_rate / filter_sample_rate; - std::array filter_descriptors = {{ - { data_shared::DATA_GPS_TIME, filter_decimation }, - { data_filter::DATA_FILTER_STATUS, filter_decimation }, - { data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, - { data_filter::DATA_POS_LLH, filter_decimation }, - { data_filter::DATA_VEL_NED, filter_decimation }, + std::array filter_descriptors = {{ + { mip::data_shared::DATA_GPS_TIME, filter_decimation }, + { mip::data_filter::DATA_FILTER_STATUS, filter_decimation }, + { mip::data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, + { mip::data_filter::DATA_POS_LLH, filter_decimation }, + { mip::data_filter::DATA_VEL_NED, filter_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeMessageFormat(*device, mip::data_filter::DESCRIPTOR_SET, static_cast(filter_descriptors.size()), filter_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); // //Configure the filter to accept external heading // - const auto initConfig = commands_filter::InitializationConfiguration::InitialConditionSource::AUTO_POS_VEL_PITCH_ROLL; - commands_filter::InitializationConfiguration::AlignmentSelector alignment; + const mip::commands_filter::InitializationConfiguration::InitialConditionSource initConfig = + mip::commands_filter::InitializationConfiguration::InitialConditionSource::AUTO_POS_VEL_PITCH_ROLL; + mip::commands_filter::InitializationConfiguration::AlignmentSelector alignment; alignment.external(true); - const Vector3f zero3({0, 0, 0}); - if(commands_filter::writeInitializationConfiguration(*device, 0, initConfig, alignment, 0, 0, 0, zero3, zero3, commands_filter::FilterReferenceFrame::LLH) != CmdResult::ACK_OK) + const mip::Vector3f zero3({0, 0, 0}); + if(mip::commands_filter::writeInitializationConfiguration(*device, 0, initConfig, alignment, 0, 0, 0, zero3, zero3, mip::commands_filter::FilterReferenceFrame::LLH) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set heading source!"); // //Reset the filter (note: this is good to do after filter setup is complete) // - if(commands_filter::reset(*device) != CmdResult::ACK_OK) + if(mip::commands_filter::reset(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not reset the filter!"); @@ -197,9 +196,9 @@ int main(int argc, const char* argv[]) // //Filter Data - DispatchHandler filter_data_handlers[5]; + mip::DispatchHandler filter_data_handlers[5]; - device->registerExtractor(filter_data_handlers[0], &filter_gps_time, data_filter::DESCRIPTOR_SET); + device->registerExtractor(filter_data_handlers[0], &filter_gps_time, mip::data_filter::DESCRIPTOR_SET); device->registerExtractor(filter_data_handlers[1], &filter_status); device->registerExtractor(filter_data_handlers[2], &filter_euler_angles); device->registerExtractor(filter_data_handlers[3], &filter_llh_position); @@ -209,7 +208,7 @@ int main(int argc, const char* argv[]) //Resume the device // - if(commands_base::resume(*device) != CmdResult::ACK_OK) + if(mip::commands_base::resume(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not resume the device!"); @@ -230,7 +229,7 @@ int main(int argc, const char* argv[]) displayFilterState(filter_status.filter_state, current_state); //Check for full nav filter state transition - if((!filter_state_full_nav) && (filter_status.filter_state == data_filter::FilterMode::FULL_NAV)) + if((!filter_state_full_nav) && (filter_status.filter_state == mip::data_filter::FilterMode::FULL_NAV)) { printf("NOTE: Filter has entered full navigation mode.\n"); filter_state_full_nav = true; @@ -244,15 +243,15 @@ int main(int argc, const char* argv[]) if (elapsed_time_from_last_measurement_update > 500) { // Use measurement time of arrival for timestamping method - commands_aiding::Time external_measurement_time; - external_measurement_time.timebase = commands_aiding::Time::Timebase::TIME_OF_ARRIVAL; + mip::commands_aiding::Time external_measurement_time; + external_measurement_time.timebase = mip::commands_aiding::Time::Timebase::TIME_OF_ARRIVAL; external_measurement_time.reserved = 1; external_measurement_time.nanoseconds = current_timestamp * uint64_t(1000000); // External heading command float external_heading = 0.0f; float external_heading_uncertainty = 0.001f; - if(commands_aiding::headingTrue(*device, external_measurement_time, external_heading_sensor_id, external_heading, external_heading_uncertainty, 0x0001) != CmdResult::ACK_OK) + if(mip::commands_aiding::headingTrue(*device, external_measurement_time, external_heading_sensor_id, external_heading, external_heading_uncertainty, 0x0001) != mip::CmdResult::ACK_OK) printf("WARNING: Failed to send external heading to CV7-INS\n"); // External position command @@ -260,26 +259,26 @@ int main(int argc, const char* argv[]) double longitude = -73.10628129871753; double height = 122.0; float llh_uncertainty[3] = {1.0, 1.0, 1.0}; - if(commands_aiding::posLlh(*device, external_measurement_time, gnss_antenna_sensor_id, latitude, longitude, height, llh_uncertainty, 0x0007) != CmdResult::ACK_OK) + if(mip::commands_aiding::posLlh(*device, external_measurement_time, gnss_antenna_sensor_id, latitude, longitude, height, llh_uncertainty, 0x0007) != mip::CmdResult::ACK_OK) printf("WARNING: Failed to send external position to CV7-INS\n"); // External global velocity command float ned_velocity[3] = {0.0f, 0.0f, 0.0f}; float ned_velocity_uncertainty[3] = {0.1f, 0.1f, 0.1f}; - if(commands_aiding::velNed(*device, external_measurement_time, gnss_antenna_sensor_id, ned_velocity, ned_velocity_uncertainty, 0x0007) != CmdResult::ACK_OK) + if(mip::commands_aiding::velNed(*device, external_measurement_time, gnss_antenna_sensor_id, ned_velocity, ned_velocity_uncertainty, 0x0007) != mip::CmdResult::ACK_OK) printf("WARNING: Failed to send external NED velocity to CV7-INS\n"); // External vehicle frame velocity command float vehicle_frame_velocity[3] = {0.0f, 0.0f, 0.0f}; float vehicle_frame_velocity_uncertainty[3] = {0.1f, 0.1f, 0.1f}; - if(commands_aiding::velBodyFrame(*device, external_measurement_time, vehicle_frame_velocity_sensor_id, vehicle_frame_velocity, vehicle_frame_velocity_uncertainty, 0x0007) != CmdResult::ACK_OK) + if(mip::commands_aiding::velBodyFrame(*device, external_measurement_time, vehicle_frame_velocity_sensor_id, vehicle_frame_velocity, vehicle_frame_velocity_uncertainty, 0x0007) != mip::CmdResult::ACK_OK) printf("WARNING: Failed to send external vehicle frame velocity to CV7-INS\n"); prev_measurement_update_timestamp = current_timestamp; } //Once in full nav, print out data at 1 Hz - if((filter_status.filter_state == data_filter::FilterMode::FULL_NAV) && (elapsed_time_from_last_message_print >= 1000)) + if((filter_status.filter_state == mip::data_filter::FilterMode::FULL_NAV) && (elapsed_time_from_last_message_print >= 1000)) { printf("\n\n****Filter navigation state****\n"); printf("TIMESTAMP: %f\n", filter_gps_time.tow); @@ -301,7 +300,7 @@ int main(int argc, const char* argv[]) // Print device information //////////////////////////////////////////////////////////////////////////////// -void print_device_information(const commands_base::BaseDeviceInfo& device_info) +void print_device_information(const mip::commands_base::BaseDeviceInfo& device_info) { printf("Connected to:\n"); diff --git a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp index e222ffe60..531a283b5 100644 --- a/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp +++ b/examples/CV7_INS/CV7_INS_simple_ublox_example.cpp @@ -33,18 +33,16 @@ #include #include -using namespace mip; - //////////////////////////////////////////////////////////////////////////////// // Global Variables //////////////////////////////////////////////////////////////////////////////// -data_shared::GpsTimestamp filter_gps_time; -data_filter::Status filter_status; -data_filter::EulerAngles filter_euler_angles; -data_filter::PositionLlh filter_llh_position; -data_filter::VelocityNed filter_ned_velocity; -data_system::TimeSyncStatus system_time_sync_status; +mip::data_shared::GpsTimestamp filter_gps_time; +mip::data_filter::Status filter_status; +mip::data_filter::EulerAngles filter_euler_angles; +mip::data_filter::PositionLlh filter_llh_position; +mip::data_filter::VelocityNed filter_ned_velocity; +mip::data_system::TimeSyncStatus system_time_sync_status; uint8_t gnss_antenna_sensor_id = 1; @@ -63,7 +61,7 @@ struct InputArguments uint8_t pps_input_pin_id = 1; - commands_filter::InitializationConfiguration::AlignmentSelector filter_heading_alignment_method = commands_filter::InitializationConfiguration::AlignmentSelector::KINEMATIC; + mip::commands_filter::InitializationConfiguration::AlignmentSelector filter_heading_alignment_method = mip::commands_filter::InitializationConfiguration::AlignmentSelector::KINEMATIC; float gnss_antenna_lever_arm[3] = {0,0,0}; }; @@ -74,7 +72,7 @@ struct InputArguments int usage(const char* argv0); -void print_device_information(const commands_base::BaseDeviceInfo& device_info); +void print_device_information(const mip::commands_base::BaseDeviceInfo& device_info); void exit_gracefully(const char *message); bool should_exit(); @@ -91,33 +89,33 @@ int main(int argc, const char* argv[]) std::unique_ptr utils = openFromArgs(input_arguments.mip_device_port_name, input_arguments.mip_device_baudrate, input_arguments.mip_binary_filepath); std::unique_ptr& device = utils->device; - + // // Open uBlox serial port // printf("Connecting to UBlox F9P on %s at %s...\n", input_arguments.ublox_device_port_name.c_str(), input_arguments.ublox_device_baudrate.c_str()); std::unique_ptr utils_ublox = openFromArgs(input_arguments.ublox_device_port_name, input_arguments.ublox_device_baudrate, {}); - ublox::UbloxDevice ublox_device(std::move(utils_ublox->connection)); + mip::ublox::UbloxDevice ublox_device(std::move(utils_ublox->connection)); // //Attempt to idle the device before pinging // - commands_base::setIdle(*device); + mip::commands_base::setIdle(*device); // //Ping the device (note: this is good to do to make sure the device is present) // - if(commands_base::ping(*device) != CmdResult::ACK_OK) + if(mip::commands_base::ping(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not ping the device!"); // //Read device information // - commands_base::BaseDeviceInfo device_info; - if(commands_base::getDeviceInfo(*device, &device_info) != CmdResult::ACK_OK) + mip::commands_base::BaseDeviceInfo device_info; + if(mip::commands_base::getDeviceInfo(*device, &device_info) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Failed to get device info"); print_device_information(device_info); @@ -125,7 +123,7 @@ int main(int argc, const char* argv[]) //Idle the device (note: this is good to do during setup) // - if(commands_base::setIdle(*device) != CmdResult::ACK_OK) + if(mip::commands_base::setIdle(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set the device to idle!"); @@ -133,17 +131,17 @@ int main(int argc, const char* argv[]) //Load the device default settings (so the device is in a known state) // - if(commands_3dm::defaultDeviceSettings(*device) != CmdResult::ACK_OK) + if(mip::commands_3dm::defaultDeviceSettings(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not load default device settings!"); // //External GNSS antenna reference frame // - commands_aiding::FrameConfig::Rotation external_gnss_antenna_to_vehicle_frame_rotation; + mip::commands_aiding::FrameConfig::Rotation external_gnss_antenna_to_vehicle_frame_rotation; external_gnss_antenna_to_vehicle_frame_rotation.euler = mip::Vector3f(0.0f, 0.0f, 0.0f); // GNSS position/velocity measurements are agnostic to rotation, rotation set to zero // GNSS position/velocity measurements are agnostic to rotation, rotation set to zero - if(commands_aiding::writeFrameConfig(*device, gnss_antenna_sensor_id, mip::commands_aiding::FrameConfig::Format::EULER, true, - input_arguments.gnss_antenna_lever_arm, external_gnss_antenna_to_vehicle_frame_rotation) != CmdResult::ACK_OK) + if(mip::commands_aiding::writeFrameConfig(*device, gnss_antenna_sensor_id, mip::commands_aiding::FrameConfig::Format::EULER, true, + input_arguments.gnss_antenna_lever_arm, external_gnss_antenna_to_vehicle_frame_rotation) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Unable to configure external GNSS antenna frame ID"); @@ -152,8 +150,8 @@ int main(int argc, const char* argv[]) // float default_init[3] = {0,0,0}; - if(commands_filter::writeInitializationConfiguration(*device, false, commands_filter::InitializationConfiguration::InitialConditionSource::AUTO_POS_VEL_ATT, input_arguments.filter_heading_alignment_method, - 0, 0, 0, default_init, default_init, commands_filter::FilterReferenceFrame::ECEF) != CmdResult::ACK_OK) + if(mip::commands_filter::writeInitializationConfiguration(*device, false, mip::commands_filter::InitializationConfiguration::InitialConditionSource::AUTO_POS_VEL_ATT, input_arguments.filter_heading_alignment_method, + 0, 0, 0, default_init, default_init, mip::commands_filter::FilterReferenceFrame::ECEF) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not load default device settings!"); @@ -165,18 +163,18 @@ int main(int argc, const char* argv[]) // uint16_t system_data_base_rate; - if(commands_3dm::getBaseRate(*device, data_system::DESCRIPTOR_SET, &system_data_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::getBaseRate(*device, mip::data_system::DESCRIPTOR_SET, &system_data_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get system data base rate format!"); const uint16_t system_data_sample_rate = 10; // Hz const uint16_t system_data_decimation = system_data_base_rate / system_data_sample_rate; - std::array system_data_descriptors = {{ - { data_shared::DATA_GPS_TIME, system_data_decimation }, - { data_system::DATA_TIME_SYNC_STATUS, system_data_decimation }, + std::array system_data_descriptors = {{ + { mip::data_shared::DATA_GPS_TIME, system_data_decimation }, + { mip::data_system::DATA_TIME_SYNC_STATUS, system_data_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_system::DESCRIPTOR_SET, static_cast(system_data_descriptors.size()), system_data_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeMessageFormat(*device, mip::data_system::DESCRIPTOR_SET, static_cast(system_data_descriptors.size()), system_data_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set system data message format!"); @@ -184,7 +182,7 @@ int main(int argc, const char* argv[]) // Setup GPIO for PPS input functionality // - if (commands_3dm::writeGpioConfig(*device, input_arguments.pps_input_pin_id, mip::commands_3dm::GpioConfig::Feature::PPS, mip::commands_3dm::GpioConfig::Behavior::PPS_INPUT, mip::commands_3dm::GpioConfig::PinMode::NONE) != CmdResult::ACK_OK) + if (mip::commands_3dm::writeGpioConfig(*device, input_arguments.pps_input_pin_id, mip::commands_3dm::GpioConfig::Feature::PPS, mip::commands_3dm::GpioConfig::Behavior::PPS_INPUT, mip::commands_3dm::GpioConfig::PinMode::NONE) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GPIO to PPS input!"); @@ -192,7 +190,7 @@ int main(int argc, const char* argv[]) // Setup PPS source as GPIO // - if (mip::commands_3dm::writePpsSource(*device, mip::commands_3dm::PpsSource::Source::GPIO) != CmdResult::ACK_OK) + if (mip::commands_3dm::writePpsSource(*device, mip::commands_3dm::PpsSource::Source::GPIO) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Failed to set PPS source to GPIO!"); } @@ -201,26 +199,27 @@ int main(int argc, const char* argv[]) //Configure factory streaming data. This enables all critical data channels required for post-processing analysis // - if(commands_3dm::factoryStreaming(*device, commands_3dm::FactoryStreaming::Action::MERGE, 0) != CmdResult::ACK_OK) + if(mip::commands_3dm::factoryStreaming(*device, mip::commands_3dm::FactoryStreaming::Action::MERGE, 0) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not enable factory streaming support!"); // //Configure the filter to use magnetometer or GNSS kinematic heading // - const auto initConfig = commands_filter::InitializationConfiguration::InitialConditionSource::AUTO_POS_VEL_PITCH_ROLL; - commands_filter::InitializationConfiguration::AlignmentSelector alignment; + const mip::commands_filter::InitializationConfiguration::InitialConditionSource initConfig = + mip::commands_filter::InitializationConfiguration::InitialConditionSource::AUTO_POS_VEL_PITCH_ROLL; + mip::commands_filter::InitializationConfiguration::AlignmentSelector alignment; alignment.magnetometer(true); alignment.kinematic(true); - const Vector3f zero3({0, 0, 0}); - if(commands_filter::writeInitializationConfiguration(*device, 0, initConfig, alignment, 0, 0, 0, zero3, zero3, commands_filter::FilterReferenceFrame::LLH) != CmdResult::ACK_OK) + const mip::Vector3f zero3({0, 0, 0}); + if(mip::commands_filter::writeInitializationConfiguration(*device, 0, initConfig, alignment, 0, 0, 0, zero3, zero3, mip::commands_filter::FilterReferenceFrame::LLH) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set heading source!"); // //Reset the filter (note: this is good to do after filter setup is complete) // - if(commands_filter::reset(*device) != CmdResult::ACK_OK) + if(mip::commands_filter::reset(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not reset the filter!"); @@ -229,26 +228,26 @@ int main(int argc, const char* argv[]) // //Filter Data - DispatchHandler filter_data_handlers[5]; + mip::DispatchHandler filter_data_handlers[5]; - device->registerExtractor(filter_data_handlers[0], &filter_gps_time, data_filter::DESCRIPTOR_SET); + device->registerExtractor(filter_data_handlers[0], &filter_gps_time, mip::data_filter::DESCRIPTOR_SET); device->registerExtractor(filter_data_handlers[1], &filter_status); device->registerExtractor(filter_data_handlers[2], &filter_euler_angles); device->registerExtractor(filter_data_handlers[3], &filter_llh_position); device->registerExtractor(filter_data_handlers[4], &filter_ned_velocity); //System Data - DispatchHandler system_data_handlers[1]; + mip::DispatchHandler system_data_handlers[1]; - device->registerExtractor(system_data_handlers[0], &system_time_sync_status, data_system::DESCRIPTOR_SET); + device->registerExtractor(system_data_handlers[0], &system_time_sync_status, mip::data_system::DESCRIPTOR_SET); // //Resume the device // - if(commands_base::resume(*device) != CmdResult::ACK_OK) + if(mip::commands_base::resume(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not resume the device!"); - + //Main Loop: Update the interface and process data // @@ -266,10 +265,10 @@ int main(int argc, const char* argv[]) device->update(); // Get ublox data - std::pair ubox_parser_result = ublox_device.update(); + std::pair ubox_parser_result = ublox_device.update(); bool pvt_message_valid = ubox_parser_result.first; - ublox::UbloxPVTMessage pvt_message = ubox_parser_result.second; - + mip::ublox::UbloxPVTMessage pvt_message = ubox_parser_result.second; + // Wait for valid PPS lock if (input_arguments.enable_pps_sync && !pps_sync_valid) { @@ -283,9 +282,9 @@ int main(int argc, const char* argv[]) } continue; } - + //Check for full nav filter state transition - if((!filter_state_full_nav) && (filter_status.filter_state == data_filter::FilterMode::FULL_NAV)) + if((!filter_state_full_nav) && (filter_status.filter_state == mip::data_filter::FilterMode::FULL_NAV)) { printf("NOTE: Filter has entered full navigation mode.\n"); filter_state_full_nav = true; @@ -296,7 +295,7 @@ int main(int argc, const char* argv[]) bool print_new_update_message = elapsed_time_from_last_message_print >= 1000; if (print_new_update_message) { - if(filter_status.filter_state == data_filter::FilterMode::FULL_NAV) + if(filter_status.filter_state == mip::data_filter::FilterMode::FULL_NAV) { printf("\n\n****Filter navigation state****\n"); printf("TIMESTAMP: %f\n", filter_gps_time.tow); @@ -321,38 +320,38 @@ int main(int argc, const char* argv[]) printf("LLH_POSITION_GNSS_MEAS = [%f %f %f]\n", pvt_message.latitude, pvt_message.longitude, pvt_message.height_above_ellipsoid); printf("NED_VELOCITY_GNSS_MEAS = [%f %f %f]\n", pvt_message.ned_velocity[0], pvt_message.ned_velocity[1], pvt_message.ned_velocity[2]); - commands_aiding::Time external_measurement_time; + mip::commands_aiding::Time external_measurement_time; external_measurement_time.reserved = 1; if (input_arguments.enable_pps_sync) { // Send week number update to device uint32_t week_number = get_gps_week(pvt_message.utc_year, pvt_message.utc_month, pvt_message.utc_day); - if (!commands_base::writeGpsTimeUpdate(*device, commands_base::GpsTimeUpdate::FieldId::WEEK_NUMBER, week_number)) + if (!mip::commands_base::writeGpsTimeUpdate(*device, mip::commands_base::GpsTimeUpdate::FieldId::WEEK_NUMBER, week_number)) printf("WARNING: Failed to send week number time update to CV7-INS\n"); // Send time of week update to device uint32_t time_of_week_int = static_cast(floor(pvt_message.time_of_week)); - if (!commands_base::writeGpsTimeUpdate(*device, commands_base::GpsTimeUpdate::FieldId::TIME_OF_WEEK, time_of_week_int)) + if (!mip::commands_base::writeGpsTimeUpdate(*device, mip::commands_base::GpsTimeUpdate::FieldId::TIME_OF_WEEK, time_of_week_int)) printf("WARNING: Failed to send time of week update to CV7-INS\n"); // Mark timestamp for aiding message input - external_measurement_time.timebase = commands_aiding::Time::Timebase::EXTERNAL_TIME; + external_measurement_time.timebase = mip::commands_aiding::Time::Timebase::EXTERNAL_TIME; external_measurement_time.nanoseconds = convert_gps_tow_to_nanoseconds(week_number, pvt_message.time_of_week); } else { // If no PPS sync is supplied, use device time of arrival for data timestamping method - external_measurement_time.timebase = commands_aiding::Time::Timebase::TIME_OF_ARRIVAL; + external_measurement_time.timebase = mip::commands_aiding::Time::Timebase::TIME_OF_ARRIVAL; external_measurement_time.nanoseconds = 0; // Not used, but should be set to 0 } // External position command - if (commands_aiding::posLlh(*device, external_measurement_time, gnss_antenna_sensor_id, pvt_message.latitude, pvt_message.longitude, pvt_message.height_above_ellipsoid, pvt_message.llh_position_uncertainty, 0x0007) != CmdResult::ACK_OK) + if (mip::commands_aiding::posLlh(*device, external_measurement_time, gnss_antenna_sensor_id, pvt_message.latitude, pvt_message.longitude, pvt_message.height_above_ellipsoid, pvt_message.llh_position_uncertainty, 0x0007) != mip::CmdResult::ACK_OK) printf("WARNING: Failed to send external position to CV7-INS\n"); // External global velocity command - if (commands_aiding::velNed(*device, external_measurement_time, gnss_antenna_sensor_id,pvt_message.ned_velocity, pvt_message.ned_velocity_uncertainty, 0x0007) != CmdResult::ACK_OK) + if (mip::commands_aiding::velNed(*device, external_measurement_time, gnss_antenna_sensor_id,pvt_message.ned_velocity, pvt_message.ned_velocity_uncertainty, 0x0007) != mip::CmdResult::ACK_OK) printf("WARNING: Failed to send external NED velocity to CV7-INS\n"); prev_measurement_update_timestamp = current_timestamp; @@ -396,7 +395,7 @@ int get_gps_week(int year, int month, int day) // Print device information //////////////////////////////////////////////////////////////////////////////// -void print_device_information(const commands_base::BaseDeviceInfo& device_info) +void print_device_information(const mip::commands_base::BaseDeviceInfo& device_info) { printf("Connected to:\n"); @@ -459,9 +458,9 @@ InputArguments parse_input_arguments(int argc, const char* argv[]) int heading_alignment_int = std::stoi(argv[8]); if (heading_alignment_int == 0) - input_arguments.filter_heading_alignment_method = commands_filter::InitializationConfiguration::AlignmentSelector::KINEMATIC; + input_arguments.filter_heading_alignment_method = mip::commands_filter::InitializationConfiguration::AlignmentSelector::KINEMATIC; else if (heading_alignment_int == 1) - input_arguments.filter_heading_alignment_method = commands_filter::InitializationConfiguration::AlignmentSelector::MAGNETOMETER; + input_arguments.filter_heading_alignment_method = mip::commands_filter::InitializationConfiguration::AlignmentSelector::MAGNETOMETER; else exit_gracefully("Heading alignment selector out of range"); } diff --git a/examples/CX5_GX5_45/CX5_GX5_45_example.cpp b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp index 0b1d4c3e0..f2060c84d 100644 --- a/examples/CX5_GX5_45/CX5_GX5_45_example.cpp +++ b/examples/CX5_GX5_45/CX5_GX5_45_example.cpp @@ -33,8 +33,6 @@ #include "example_utils.hpp" -using namespace mip; - //////////////////////////////////////////////////////////////////////////////// // Global Variables @@ -48,20 +46,20 @@ float sensor_to_vehicle_rotation_euler[3] = {0.0, 0.0, 0.0}; float gnss_antenna_offset_meters[3] = {-0.25, 0.0, 0.0}; //Device data stores -data_sensor::GpsTimestamp sensor_gps_time; -data_sensor::ScaledAccel sensor_accel; -data_sensor::ScaledGyro sensor_gyro; -data_sensor::ScaledMag sensor_mag; +mip::data_sensor::GpsTimestamp sensor_gps_time; +mip::data_sensor::ScaledAccel sensor_accel; +mip::data_sensor::ScaledGyro sensor_gyro; +mip::data_sensor::ScaledMag sensor_mag; -data_gnss::FixInfo gnss_fix_info; +mip::data_gnss::FixInfo gnss_fix_info; bool gnss_fix_info_valid = false; -data_filter::Timestamp filter_gps_time; -data_filter::Status filter_status; -data_filter::PositionLlh filter_position_llh; -data_filter::VelocityNed filter_velocity_ned; -data_filter::EulerAngles filter_euler_angles; +mip::data_filter::Timestamp filter_gps_time; +mip::data_filter::Status filter_status; +mip::data_filter::PositionLlh filter_position_llh; +mip::data_filter::VelocityNed filter_velocity_ned; +mip::data_filter::EulerAngles filter_euler_angles; bool filter_state_running = false; @@ -101,7 +99,7 @@ int main(int argc, const char* argv[]) //Ping the device (note: this is good to do to make sure the device is present) // - if(commands_base::ping(*device) != CmdResult::ACK_OK) + if(mip::commands_base::ping(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not ping the device!"); @@ -109,7 +107,7 @@ int main(int argc, const char* argv[]) //Idle the device (note: this is good to do during setup) // - if(commands_base::setIdle(*device) != CmdResult::ACK_OK) + if(mip::commands_base::setIdle(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set the device to idle!"); @@ -117,7 +115,7 @@ int main(int argc, const char* argv[]) //Load the device default settings (so the device is in a known state) // - if(commands_3dm::defaultDeviceSettings(*device) != CmdResult::ACK_OK) + if(mip::commands_3dm::defaultDeviceSettings(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not load default device settings!"); @@ -130,20 +128,20 @@ int main(int argc, const char* argv[]) //Note: Querying the device base rate is only one way to calculate the descriptor decimation. //We could have also set it directly with information from the datasheet (shown in GNSS setup). - if(commands_3dm::imuGetBaseRate(*device, &sensor_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::imuGetBaseRate(*device, &sensor_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get sensor base rate format!"); const uint16_t sensor_sample_rate = 100; // Hz const uint16_t sensor_decimation = sensor_base_rate / sensor_sample_rate; - std::array sensor_descriptors = {{ - { data_sensor::DATA_TIME_STAMP_GPS, sensor_decimation }, - { data_sensor::DATA_ACCEL_SCALED, sensor_decimation }, - { data_sensor::DATA_GYRO_SCALED, sensor_decimation }, - { data_sensor::DATA_MAG_SCALED, sensor_decimation }, + std::array sensor_descriptors = {{ + { mip::data_sensor::DATA_TIME_STAMP_GPS, sensor_decimation }, + { mip::data_sensor::DATA_ACCEL_SCALED, sensor_decimation }, + { mip::data_sensor::DATA_GYRO_SCALED, sensor_decimation }, + { mip::data_sensor::DATA_MAG_SCALED, sensor_decimation }, }}; - if(commands_3dm::writeImuMessageFormat(*device, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeImuMessageFormat(*device, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor message format!"); @@ -151,12 +149,12 @@ int main(int argc, const char* argv[]) //Setup GNSS data format to 4 Hz (decimation of 1) // - std::array gnss_descriptors = {{ - { data_gnss::DATA_FIX_INFO, 1 } + std::array gnss_descriptors = {{ + { mip::data_gnss::DATA_FIX_INFO, 1 } }}; //GNSS - if(commands_3dm::writeGpsMessageFormat(*device, static_cast(gnss_descriptors.size()), gnss_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeGpsMessageFormat(*device, static_cast(gnss_descriptors.size()), gnss_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GNSS1 message format!"); @@ -166,21 +164,21 @@ int main(int argc, const char* argv[]) uint16_t filter_base_rate; - if(commands_3dm::filterGetBaseRate(*device, &filter_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::filterGetBaseRate(*device, &filter_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get filter base rate format!"); const uint16_t filter_sample_rate = 100; // Hz const uint16_t filter_decimation = filter_base_rate / filter_sample_rate; - std::array filter_descriptors = {{ - { data_filter::DATA_FILTER_TIMESTAMP, filter_decimation }, - { data_filter::DATA_FILTER_STATUS, filter_decimation }, - { data_filter::DATA_POS_LLH, filter_decimation }, - { data_filter::DATA_VEL_NED, filter_decimation }, - { data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, + std::array filter_descriptors = {{ + { mip::data_filter::DATA_FILTER_TIMESTAMP, filter_decimation }, + { mip::data_filter::DATA_FILTER_STATUS, filter_decimation }, + { mip::data_filter::DATA_POS_LLH, filter_decimation }, + { mip::data_filter::DATA_VEL_NED, filter_decimation }, + { mip::data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, }}; - if(commands_3dm::writeFilterMessageFormat(*device, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeFilterMessageFormat(*device, static_cast(filter_descriptors.size()), filter_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); @@ -188,7 +186,7 @@ int main(int argc, const char* argv[]) //Setup the sensor to vehicle rotation // - if(commands_filter::writeSensorToVehicleRotationEuler(*device, sensor_to_vehicle_rotation_euler[0], sensor_to_vehicle_rotation_euler[1], sensor_to_vehicle_rotation_euler[2]) != CmdResult::ACK_OK) + if(mip::commands_filter::writeSensorToVehicleRotationEuler(*device, sensor_to_vehicle_rotation_euler[0], sensor_to_vehicle_rotation_euler[1], sensor_to_vehicle_rotation_euler[2]) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor-2-vehicle rotation!"); @@ -196,15 +194,15 @@ int main(int argc, const char* argv[]) //Setup the GNSS antenna offset // - if(commands_filter::writeAntennaOffset(*device, gnss_antenna_offset_meters) != CmdResult::ACK_OK) + if(mip::commands_filter::writeAntennaOffset(*device, gnss_antenna_offset_meters) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GNSS1 antenna offset!"); - + // //Setup heading update control // - if(commands_filter::writeHeadingSource(*device, commands_filter::HeadingSource::Source::GNSS_VEL_AND_MAG) != CmdResult::ACK_OK) + if(mip::commands_filter::writeHeadingSource(*device, mip::commands_filter::HeadingSource::Source::GNSS_VEL_AND_MAG) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter heading update control!"); @@ -212,7 +210,7 @@ int main(int argc, const char* argv[]) //Enable filter auto-initialization // - if(commands_filter::writeAutoInitControl(*device, 1) != CmdResult::ACK_OK) + if(mip::commands_filter::writeAutoInitControl(*device, 1) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter autoinit control!"); @@ -221,7 +219,7 @@ int main(int argc, const char* argv[]) //Reset the filter (note: this is good to do after filter setup is complete) // - if(commands_filter::reset(*device) != CmdResult::ACK_OK) + if(mip::commands_filter::reset(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not reset the filter!"); @@ -230,7 +228,7 @@ int main(int argc, const char* argv[]) // //Sensor Data - DispatchHandler sensor_data_handlers[4]; + mip::DispatchHandler sensor_data_handlers[4]; device->registerExtractor(sensor_data_handlers[0], &sensor_gps_time); device->registerExtractor(sensor_data_handlers[1], &sensor_accel); @@ -238,12 +236,12 @@ int main(int argc, const char* argv[]) device->registerExtractor(sensor_data_handlers[3], &sensor_mag); //GNSS Data - DispatchHandler gnss_data_handlers[1]; + mip::DispatchHandler gnss_data_handlers[1]; device->registerExtractor(gnss_data_handlers[0], &gnss_fix_info); - + //Filter Data - DispatchHandler filter_data_handlers[5]; + mip::DispatchHandler filter_data_handlers[5]; device->registerExtractor(filter_data_handlers[0], &filter_gps_time); device->registerExtractor(filter_data_handlers[1], &filter_status); @@ -255,7 +253,7 @@ int main(int argc, const char* argv[]) //Resume the device // - if(commands_base::resume(*device) != CmdResult::ACK_OK) + if(mip::commands_base::resume(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not resume the device!"); @@ -275,15 +273,15 @@ int main(int argc, const char* argv[]) displayFilterState(filter_status.filter_state, current_state, true); //Check GNSS fixes and alert the user when they become valid - if((gnss_fix_info_valid == false) && (gnss_fix_info.fix_type == data_gnss::FixInfo::FixType::FIX_3D) && - (gnss_fix_info.valid_flags & data_gnss::FixInfo::ValidFlags::FIX_TYPE)) + if((gnss_fix_info_valid == false) && (gnss_fix_info.fix_type == mip::data_gnss::FixInfo::FixType::FIX_3D) && + (gnss_fix_info.valid_flags & mip::data_gnss::FixInfo::ValidFlags::FIX_TYPE)) { printf("NOTE: GNSS fix info valid.\n"); gnss_fix_info_valid = true; } - + //Check Filter State - if((!filter_state_running) && ((filter_status.filter_state == data_filter::FilterMode::GX5_RUN_SOLUTION_ERROR) || (filter_status.filter_state == data_filter::FilterMode::GX5_RUN_SOLUTION_VALID))) + if((!filter_state_running) && ((filter_status.filter_state == mip::data_filter::FilterMode::GX5_RUN_SOLUTION_ERROR) || (filter_status.filter_state == mip::data_filter::FilterMode::GX5_RUN_SOLUTION_VALID))) { printf("NOTE: Filter has entered running mode.\n"); filter_state_running = true; @@ -350,4 +348,3 @@ bool should_exit() return false; } - diff --git a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp index b454be215..ba3f59c4a 100644 --- a/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp +++ b/examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp @@ -31,8 +31,6 @@ #include #include "../example_utils.hpp" -using namespace mip; - //////////////////////////////////////////////////////////////////////////////// // Global Variables @@ -43,15 +41,15 @@ using namespace mip; float sensor_to_vehicle_rotation_euler[3] = {0.0, 0.0, 0.0}; //Device data stores -data_sensor::GpsTimestamp sensor_gps_time; -data_sensor::ScaledAccel sensor_accel; -data_sensor::ScaledGyro sensor_gyro; +mip::data_sensor::GpsTimestamp sensor_gps_time; +mip::data_sensor::ScaledAccel sensor_accel; +mip::data_sensor::ScaledGyro sensor_gyro; -data_filter::Timestamp filter_gps_time; -data_filter::Status filter_status; -data_filter::EulerAngles filter_euler_angles; -data_filter::CompAngularRate filter_comp_angular_rate; -data_filter::CompAccel filter_comp_accel; +mip::data_filter::Timestamp filter_gps_time; +mip::data_filter::Status filter_status; +mip::data_filter::EulerAngles filter_euler_angles; +mip::data_filter::CompAngularRate filter_comp_angular_rate; +mip::data_filter::CompAccel filter_comp_accel; bool filter_state_running = false; @@ -83,7 +81,7 @@ int main(int argc, const char* argv[]) //Ping the device (note: this is good to do to make sure the device is present) // - if(commands_base::ping(*device) != CmdResult::ACK_OK) + if(mip::commands_base::ping(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not ping the device!"); @@ -91,7 +89,7 @@ int main(int argc, const char* argv[]) //Idle the device (note: this is good to do during setup) // - if(commands_base::setIdle(*device) != CmdResult::ACK_OK) + if(mip::commands_base::setIdle(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set the device to idle!"); @@ -99,26 +97,26 @@ int main(int argc, const char* argv[]) //Load the device default settings (so the device is in a known state) // - if(commands_3dm::defaultDeviceSettings(*device) != CmdResult::ACK_OK) + if(mip::commands_3dm::defaultDeviceSettings(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not load default device settings!"); float gyro_bias[3] = {0, 0, 0}; const uint32_t sampling_time = 2000; // The default is 15000 ms and longer sample times are recommended but shortened for convenience - const Timeout old_mip_sdk_timeout = device->baseReplyTimeout(); + const mip::Timeout old_mip_sdk_timeout = device->baseReplyTimeout(); printf("Capturing gyro bias. This will take %d seconds \n", sampling_time/1000); device->setBaseReplyTimeout(sampling_time * 2); - if(commands_3dm::captureGyroBias(*device, sampling_time, gyro_bias) != CmdResult::ACK_OK) + if(mip::commands_3dm::captureGyroBias(*device, sampling_time, gyro_bias) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not capture gyro bias!"); - if(commands_3dm::saveGyroBias(*device) != CmdResult::ACK_OK) + if(mip::commands_3dm::saveGyroBias(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not save gyro bias!"); const uint8_t device_selector = 3; const uint8_t enable_flag = 1; - if(commands_3dm::writeDatastreamControl(*device, device_selector, enable_flag) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeDatastreamControl(*device, device_selector, enable_flag) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not enable device data stream!"); // Reset the timeout @@ -136,19 +134,19 @@ int main(int argc, const char* argv[]) //Note: Querying the device base rate is only one way to calculate the descriptor decimation. //We could have also set it directly with information from the datasheet. - if(commands_3dm::imuGetBaseRate(*device, &sensor_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::imuGetBaseRate(*device, &sensor_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get sensor base rate format!"); const uint16_t sensor_sample_rate = 100; // Hz const uint16_t sensor_decimation = sensor_base_rate / sensor_sample_rate; - std::array sensor_descriptors = {{ - { data_sensor::DATA_TIME_STAMP_GPS, sensor_decimation }, - { data_sensor::DATA_ACCEL_SCALED, sensor_decimation }, - { data_sensor::DATA_GYRO_SCALED, sensor_decimation }, + std::array sensor_descriptors = {{ + { mip::data_sensor::DATA_TIME_STAMP_GPS, sensor_decimation }, + { mip::data_sensor::DATA_ACCEL_SCALED, sensor_decimation }, + { mip::data_sensor::DATA_GYRO_SCALED, sensor_decimation }, }}; - if(commands_3dm::writeImuMessageFormat(*device, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeImuMessageFormat(*device, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor message format!"); @@ -158,21 +156,21 @@ int main(int argc, const char* argv[]) uint16_t filter_base_rate; - if(commands_3dm::filterGetBaseRate(*device, &filter_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::filterGetBaseRate(*device, &filter_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get filter base rate format!"); const uint16_t filter_sample_rate = 100; // Hz const uint16_t filter_decimation = filter_base_rate / filter_sample_rate; - std::array filter_descriptors = {{ - { data_filter::DATA_FILTER_TIMESTAMP, filter_decimation }, - { data_filter::DATA_FILTER_STATUS, filter_decimation }, - { data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, - { data_filter::DATA_COMPENSATED_ANGULAR_RATE, filter_decimation }, - { data_filter::DATA_COMPENSATED_ACCELERATION, filter_decimation }, + std::array filter_descriptors = {{ + { mip::data_filter::DATA_FILTER_TIMESTAMP, filter_decimation }, + { mip::data_filter::DATA_FILTER_STATUS, filter_decimation }, + { mip::data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, + { mip::data_filter::DATA_COMPENSATED_ANGULAR_RATE, filter_decimation }, + { mip::data_filter::DATA_COMPENSATED_ACCELERATION, filter_decimation }, }}; - if(commands_3dm::writeFilterMessageFormat(*device, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeFilterMessageFormat(*device, static_cast(filter_descriptors.size()), filter_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); @@ -180,14 +178,14 @@ int main(int argc, const char* argv[]) //Setup the sensor to vehicle rotation // - if(commands_filter::writeSensorToVehicleRotationEuler(*device, sensor_to_vehicle_rotation_euler[0], sensor_to_vehicle_rotation_euler[1], sensor_to_vehicle_rotation_euler[2]) != CmdResult::ACK_OK) + if(mip::commands_filter::writeSensorToVehicleRotationEuler(*device, sensor_to_vehicle_rotation_euler[0], sensor_to_vehicle_rotation_euler[1], sensor_to_vehicle_rotation_euler[2]) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor-2-vehicle rotation!"); // //Enable filter auto-initialization // - if(commands_filter::writeAutoInitControl(*device, 1) != CmdResult::ACK_OK) + if(mip::commands_filter::writeAutoInitControl(*device, 1) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter autoinit control!"); @@ -196,7 +194,7 @@ int main(int argc, const char* argv[]) //Reset the filter (note: this is good to do after filter setup is complete) // - if(commands_filter::reset(*device) != CmdResult::ACK_OK) + if(mip::commands_filter::reset(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not reset the filter!"); @@ -205,27 +203,27 @@ int main(int argc, const char* argv[]) // //Sensor Data - DispatchHandler sensor_data_handlers[3]; + mip::DispatchHandler sensor_data_handlers[3]; device->registerExtractor(sensor_data_handlers[0], &sensor_gps_time); device->registerExtractor(sensor_data_handlers[1], &sensor_accel); device->registerExtractor(sensor_data_handlers[2], &sensor_gyro); - + //Filter Data - DispatchHandler filter_data_handlers[5]; + mip::DispatchHandler filter_data_handlers[5]; device->registerExtractor(filter_data_handlers[0], &filter_gps_time); device->registerExtractor(filter_data_handlers[1], &filter_status); device->registerExtractor(filter_data_handlers[2], &filter_euler_angles); device->registerExtractor(filter_data_handlers[3], &filter_comp_angular_rate); device->registerExtractor(filter_data_handlers[4], &filter_comp_accel); - + // //Resume the device // - if(commands_base::resume(*device) != CmdResult::ACK_OK) + if(mip::commands_base::resume(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not resume the device!"); @@ -241,9 +239,9 @@ int main(int argc, const char* argv[]) while(running) { device->update(); - + //Check Filter State - if((!filter_state_running) && ((filter_status.filter_state == data_filter::FilterMode::GX5_RUN_SOLUTION_ERROR) || (filter_status.filter_state == data_filter::FilterMode::GX5_RUN_SOLUTION_VALID))) + if((!filter_state_running) && ((filter_status.filter_state == mip::data_filter::FilterMode::GX5_RUN_SOLUTION_ERROR) || (filter_status.filter_state == mip::data_filter::FilterMode::GX5_RUN_SOLUTION_VALID))) { printf("NOTE: Filter has entered running mode.\n"); filter_state_running = true; @@ -257,7 +255,7 @@ int main(int argc, const char* argv[]) if(curr_timestamp - prev_print_timestamp >= 1000) { printf("TOW = %f: ATT_EULER = [%f %f %f]: COMP_ANG_RATE = [%f %f %f]: COMP_ACCEL = [%f %f %f]\n", - filter_gps_time.tow, filter_euler_angles.roll, filter_euler_angles.pitch, filter_euler_angles.yaw, + filter_gps_time.tow, filter_euler_angles.roll, filter_euler_angles.pitch, filter_euler_angles.yaw, filter_comp_angular_rate.gyro[0], filter_comp_angular_rate.gyro[1], filter_comp_angular_rate.gyro[2], filter_comp_accel.accel[0], filter_comp_accel.accel[1], filter_comp_accel.accel[2]); @@ -309,4 +307,3 @@ bool should_exit() return false; } - diff --git a/examples/GQ7/GQ7_example.cpp b/examples/GQ7/GQ7_example.cpp index a9bccf035..77c645e39 100644 --- a/examples/GQ7/GQ7_example.cpp +++ b/examples/GQ7/GQ7_example.cpp @@ -33,8 +33,6 @@ #include "example_utils.hpp" -using namespace mip; - //////////////////////////////////////////////////////////////////////////////// // Global Variables @@ -48,20 +46,20 @@ float gnss1_antenna_offset_meters[3] = {-0.25, 0.0, 0.0}; float gnss2_antenna_offset_meters[3] = {0.25, 0.0, 0.0}; //Device data stores -data_shared::GpsTimestamp sensor_gps_time; -data_sensor::ScaledAccel sensor_accel; -data_sensor::ScaledGyro sensor_gyro; -data_sensor::ScaledMag sensor_mag; +mip::data_shared::GpsTimestamp sensor_gps_time; +mip::data_sensor::ScaledAccel sensor_accel; +mip::data_sensor::ScaledGyro sensor_gyro; +mip::data_sensor::ScaledMag sensor_mag; -data_gnss::FixInfo gnss_fix_info[2]; +mip::data_gnss::FixInfo gnss_fix_info[2]; bool gnss_fix_info_valid[2] = {false}; -data_shared::GpsTimestamp filter_gps_time; -data_filter::Status filter_status; -data_filter::PositionLlh filter_position_llh; -data_filter::VelocityNed filter_velocity_ned; -data_filter::EulerAngles filter_euler_angles; +mip::data_shared::GpsTimestamp filter_gps_time; +mip::data_filter::Status filter_status; +mip::data_filter::PositionLlh filter_position_llh; +mip::data_filter::VelocityNed filter_velocity_ned; +mip::data_filter::EulerAngles filter_euler_angles; bool filter_state_full_nav = false; @@ -101,7 +99,7 @@ int main(int argc, const char* argv[]) //Ping the device (note: this is good to do to make sure the device is present) // - if(commands_base::ping(*device) != CmdResult::ACK_OK) + if(mip::commands_base::ping(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not ping the device!"); @@ -109,7 +107,7 @@ int main(int argc, const char* argv[]) //Idle the device (note: this is good to do during setup) // - if(commands_base::setIdle(*device) != CmdResult::ACK_OK) + if(mip::commands_base::setIdle(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set the device to idle!"); @@ -117,7 +115,7 @@ int main(int argc, const char* argv[]) //Load the device default settings (so the device is in a known state) // - if(commands_3dm::defaultDeviceSettings(*device) != CmdResult::ACK_OK) + if(mip::commands_3dm::defaultDeviceSettings(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not load default device settings!"); @@ -130,20 +128,20 @@ int main(int argc, const char* argv[]) //Note: Querying the device base rate is only one way to calculate the descriptor decimation. //We could have also set it directly with information from the datasheet (shown in GNSS setup). - if(commands_3dm::getBaseRate(*device, data_sensor::DESCRIPTOR_SET, &sensor_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::getBaseRate(*device, mip::data_sensor::DESCRIPTOR_SET, &sensor_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get sensor base rate format!"); const uint16_t sensor_sample_rate = 100; // Hz const uint16_t sensor_decimation = sensor_base_rate / sensor_sample_rate; - std::array sensor_descriptors = {{ - { data_shared::DATA_GPS_TIME, sensor_decimation }, - { data_sensor::DATA_ACCEL_SCALED, sensor_decimation }, - { data_sensor::DATA_GYRO_SCALED, sensor_decimation }, - { data_sensor::DATA_MAG_SCALED, sensor_decimation }, + std::array sensor_descriptors = {{ + { mip::data_shared::DATA_GPS_TIME, sensor_decimation }, + { mip::data_sensor::DATA_ACCEL_SCALED, sensor_decimation }, + { mip::data_sensor::DATA_GYRO_SCALED, sensor_decimation }, + { mip::data_sensor::DATA_MAG_SCALED, sensor_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_sensor::DESCRIPTOR_SET, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeMessageFormat(*device, mip::data_sensor::DESCRIPTOR_SET, static_cast(sensor_descriptors.size()), sensor_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor message format!"); @@ -151,16 +149,16 @@ int main(int argc, const char* argv[]) //Setup GNSS 1 and 2 data format to 2 Hz (decimation of 1) // - std::array gnss_descriptors = {{ - { data_gnss::DATA_FIX_INFO, 1 } + std::array gnss_descriptors = {{ + { mip::data_gnss::DATA_FIX_INFO, 1 } }}; //GNSS1 - if(commands_3dm::writeMessageFormat(*device, data_gnss::MIP_GNSS1_DATA_DESC_SET, static_cast(gnss_descriptors.size()), gnss_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeMessageFormat(*device, mip::data_gnss::MIP_GNSS1_DATA_DESC_SET, static_cast(gnss_descriptors.size()), gnss_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GNSS1 message format!"); //GNSS2 - if(commands_3dm::writeMessageFormat(*device, data_gnss::MIP_GNSS2_DATA_DESC_SET, static_cast(gnss_descriptors.size()), gnss_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeMessageFormat(*device, mip::data_gnss::MIP_GNSS2_DATA_DESC_SET, static_cast(gnss_descriptors.size()), gnss_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GNSS2 message format!"); @@ -170,21 +168,21 @@ int main(int argc, const char* argv[]) uint16_t filter_base_rate; - if(commands_3dm::getBaseRate(*device, data_filter::DESCRIPTOR_SET, &filter_base_rate) != CmdResult::ACK_OK) + if(mip::commands_3dm::getBaseRate(*device, mip::data_filter::DESCRIPTOR_SET, &filter_base_rate) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not get filter base rate format!"); const uint16_t filter_sample_rate = 100; // Hz const uint16_t filter_decimation = filter_base_rate / filter_sample_rate; - std::array filter_descriptors = {{ - { data_shared::DATA_GPS_TIME, filter_decimation }, - { data_filter::DATA_FILTER_STATUS, filter_decimation }, - { data_filter::DATA_POS_LLH, filter_decimation }, - { data_filter::DATA_VEL_NED, filter_decimation }, - { data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, + std::array filter_descriptors = {{ + { mip::data_shared::DATA_GPS_TIME, filter_decimation }, + { mip::data_filter::DATA_FILTER_STATUS, filter_decimation }, + { mip::data_filter::DATA_POS_LLH, filter_decimation }, + { mip::data_filter::DATA_VEL_NED, filter_decimation }, + { mip::data_filter::DATA_ATT_EULER_ANGLES, filter_decimation }, }}; - if(commands_3dm::writeMessageFormat(*device, data_filter::DESCRIPTOR_SET, static_cast(filter_descriptors.size()), filter_descriptors.data()) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeMessageFormat(*device, mip::data_filter::DESCRIPTOR_SET, static_cast(filter_descriptors.size()), filter_descriptors.data()) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter message format!"); @@ -192,7 +190,7 @@ int main(int argc, const char* argv[]) //Setup the sensor to vehicle transformation // - if(commands_3dm::writeSensor2VehicleTransformEuler(*device, sensor_to_vehicle_transformation_euler[0], sensor_to_vehicle_transformation_euler[1], sensor_to_vehicle_transformation_euler[2]) != CmdResult::ACK_OK) + if(mip::commands_3dm::writeSensor2VehicleTransformEuler(*device, sensor_to_vehicle_transformation_euler[0], sensor_to_vehicle_transformation_euler[1], sensor_to_vehicle_transformation_euler[2]) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set sensor-to-vehicle transformation!"); @@ -201,11 +199,11 @@ int main(int argc, const char* argv[]) // //GNSS1 - if(commands_filter::writeMultiAntennaOffset(*device, 1, gnss1_antenna_offset_meters) != CmdResult::ACK_OK) + if(mip::commands_filter::writeMultiAntennaOffset(*device, 1, gnss1_antenna_offset_meters) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GNSS1 antenna offset!"); //GNSS2 - if(commands_filter::writeMultiAntennaOffset(*device, 2, gnss2_antenna_offset_meters) != CmdResult::ACK_OK) + if(mip::commands_filter::writeMultiAntennaOffset(*device, 2, gnss2_antenna_offset_meters) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set GNSS2 antenna offset!"); @@ -213,10 +211,10 @@ int main(int argc, const char* argv[]) //Setup the filter aiding measurements (GNSS position/velocity and dual antenna [aka gnss heading]) // - if(commands_filter::writeAidingMeasurementEnable(*device, commands_filter::AidingMeasurementEnable::AidingSource::GNSS_POS_VEL, true) != CmdResult::ACK_OK) + if(mip::commands_filter::writeAidingMeasurementEnable(*device, mip::commands_filter::AidingMeasurementEnable::AidingSource::GNSS_POS_VEL, true) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter aiding measurement enable!"); - if(commands_filter::writeAidingMeasurementEnable(*device, commands_filter::AidingMeasurementEnable::AidingSource::GNSS_HEADING, true) != CmdResult::ACK_OK) + if(mip::commands_filter::writeAidingMeasurementEnable(*device, mip::commands_filter::AidingMeasurementEnable::AidingSource::GNSS_HEADING, true) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter aiding measurement enable!"); @@ -224,7 +222,7 @@ int main(int argc, const char* argv[]) //Enable the wheeled-vehicle constraint // - if(commands_filter::writeWheeledVehicleConstraintControl(*device, 1) != CmdResult::ACK_OK) + if(mip::commands_filter::writeWheeledVehicleConstraintControl(*device, 1) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter wheeled-vehicle constraint enable!"); @@ -235,11 +233,11 @@ int main(int argc, const char* argv[]) float filter_init_pos[3] = {0}; float filter_init_vel[3] = {0}; - commands_filter::InitializationConfiguration::AlignmentSelector alignment; + mip::commands_filter::InitializationConfiguration::AlignmentSelector alignment; alignment = alignment.DUAL_ANTENNA | alignment.KINEMATIC; - if(commands_filter::writeInitializationConfiguration(*device, 0, commands_filter::InitializationConfiguration::InitialConditionSource::AUTO_POS_VEL_ATT, - alignment, 0.0, 0.0, 0.0, filter_init_pos, filter_init_vel, commands_filter::FilterReferenceFrame::LLH) != CmdResult::ACK_OK) + if(mip::commands_filter::writeInitializationConfiguration(*device, 0, mip::commands_filter::InitializationConfiguration::InitialConditionSource::AUTO_POS_VEL_ATT, + alignment, 0.0, 0.0, 0.0, filter_init_pos, filter_init_vel, mip::commands_filter::FilterReferenceFrame::LLH) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not set filter initialization configuration!"); @@ -247,7 +245,7 @@ int main(int argc, const char* argv[]) //Reset the filter (note: this is good to do after filter setup is complete) // - if(commands_filter::reset(*device) != CmdResult::ACK_OK) + if(mip::commands_filter::reset(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not reset the filter!"); @@ -256,25 +254,25 @@ int main(int argc, const char* argv[]) // //Sensor Data - DispatchHandler sensor_data_handlers[4]; + mip::DispatchHandler sensor_data_handlers[4]; - device->registerExtractor(sensor_data_handlers[0], &sensor_gps_time, data_sensor::DESCRIPTOR_SET); + device->registerExtractor(sensor_data_handlers[0], &sensor_gps_time, mip::data_sensor::DESCRIPTOR_SET); device->registerExtractor(sensor_data_handlers[1], &sensor_accel); device->registerExtractor(sensor_data_handlers[2], &sensor_gyro); device->registerExtractor(sensor_data_handlers[3], &sensor_mag); //GNSS Data - DispatchHandler gnss_data_handlers[2]; + mip::DispatchHandler gnss_data_handlers[2]; - device->registerExtractor(gnss_data_handlers[0], &gnss_fix_info[0], data_gnss::MIP_GNSS1_DATA_DESC_SET); - device->registerExtractor(gnss_data_handlers[1], &gnss_fix_info[1], data_gnss::MIP_GNSS2_DATA_DESC_SET); + device->registerExtractor(gnss_data_handlers[0], &gnss_fix_info[0], mip::data_gnss::MIP_GNSS1_DATA_DESC_SET); + device->registerExtractor(gnss_data_handlers[1], &gnss_fix_info[1], mip::data_gnss::MIP_GNSS2_DATA_DESC_SET); //Filter Data - DispatchHandler filter_data_handlers[5]; + mip::DispatchHandler filter_data_handlers[5]; - device->registerExtractor(filter_data_handlers[0], &filter_gps_time, data_filter::DESCRIPTOR_SET); + device->registerExtractor(filter_data_handlers[0], &filter_gps_time, mip::data_filter::DESCRIPTOR_SET); device->registerExtractor(filter_data_handlers[1], &filter_status); device->registerExtractor(filter_data_handlers[2], &filter_position_llh); device->registerExtractor(filter_data_handlers[3], &filter_velocity_ned); @@ -285,7 +283,7 @@ int main(int argc, const char* argv[]) //Resume the device // - if(commands_base::resume(*device) != CmdResult::ACK_OK) + if(mip::commands_base::resume(*device) != mip::CmdResult::ACK_OK) exit_gracefully("ERROR: Could not resume the device!"); @@ -306,10 +304,10 @@ int main(int argc, const char* argv[]) //Check GNSS fixes and alert the user when they become valid for(int i=0; i<2; i++) { - if((gnss_fix_info_valid[i] == false) && ((gnss_fix_info[i].fix_type == data_gnss::FixInfo::FixType::FIX_3D) || - (gnss_fix_info[i].fix_type == data_gnss::FixInfo::FixType::FIX_RTK_FLOAT) || - (gnss_fix_info[i].fix_type == data_gnss::FixInfo::FixType::FIX_RTK_FIXED)) && - (gnss_fix_info[i].valid_flags & data_gnss::FixInfo::ValidFlags::FIX_TYPE)) + if((gnss_fix_info_valid[i] == false) && ((gnss_fix_info[i].fix_type == mip::data_gnss::FixInfo::FixType::FIX_3D) || + (gnss_fix_info[i].fix_type == mip::data_gnss::FixInfo::FixType::FIX_RTK_FLOAT) || + (gnss_fix_info[i].fix_type == mip::data_gnss::FixInfo::FixType::FIX_RTK_FIXED)) && + (gnss_fix_info[i].valid_flags & mip::data_gnss::FixInfo::ValidFlags::FIX_TYPE)) { printf("NOTE: GNSS%i fix info valid.\n", i+1); gnss_fix_info_valid[i] = true; @@ -317,7 +315,7 @@ int main(int argc, const char* argv[]) } //Check Filter State - if((!filter_state_full_nav) && (filter_status.filter_state == data_filter::FilterMode::FULL_NAV)) + if((!filter_state_full_nav) && (filter_status.filter_state == mip::data_filter::FilterMode::FULL_NAV)) { printf("NOTE: Filter has entered full navigation mode.\n"); filter_state_full_nav = true; @@ -384,4 +382,3 @@ bool should_exit() return false; } - From 748ace9f882b61165964a7351d375d7093307a98 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 20 Sep 2024 15:30:08 -0400 Subject: [PATCH 126/147] Fixed metadata constexpr check --- cmake/check_cxx_support.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/check_cxx_support.cmake b/cmake/check_cxx_support.cmake index abeb77296..c148cc507 100644 --- a/cmake/check_cxx_support.cmake +++ b/cmake/check_cxx_support.cmake @@ -9,7 +9,7 @@ include(CheckCXXSourceCompiles) check_cxx_source_compiles(" -#if __cpp_constexpr < 201907L +#if __cpp_constexpr < 201603L #error \"Metadata not supported\" #endif From 88f32ebb54a4942cebfa514fa08a79667b967747 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 20 Sep 2024 15:38:09 -0400 Subject: [PATCH 127/147] CentOS upgrade 7 --> 8 Attempting to upgrade CentOS for a newer gcc compiler version EOL for 7 was 6/30/2024 --- .devcontainer/Dockerfile.centos | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.devcontainer/Dockerfile.centos b/.devcontainer/Dockerfile.centos index 3e6d87d4e..7d0ab5512 100644 --- a/.devcontainer/Dockerfile.centos +++ b/.devcontainer/Dockerfile.centos @@ -1,5 +1,5 @@ ARG ARCH="amd64" -ARG CENTOS_VERSION="7" +ARG CENTOS_VERSION="8" FROM ${ARCH}/centos:${CENTOS_VERSION} # Add some CA certificates @@ -58,4 +58,4 @@ RUN set -ex \ && echo 'microstrain ALL=(ALL) NOPASSWD:ALL' >> /etc/sudoers # Append /usr/lib to LD_LIBRARY_PATH? Feels like we shouldn't need to do this -ENV LD_LIBRARY_PATH "${LD_LIBRARY_PATH}:/usr/lib" \ No newline at end of file +ENV LD_LIBRARY_PATH "${LD_LIBRARY_PATH}:/usr/lib" From 8cc9b9117ea0c200feba04601b384ece06ddf0fc Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 20 Sep 2024 15:46:57 -0400 Subject: [PATCH 128/147] Removing CentOS builds (EOL) --- .devcontainer/Dockerfile.centos | 61 --------------------------------- Jenkinsfile | 15 -------- 2 files changed, 76 deletions(-) delete mode 100644 .devcontainer/Dockerfile.centos diff --git a/.devcontainer/Dockerfile.centos b/.devcontainer/Dockerfile.centos deleted file mode 100644 index 7d0ab5512..000000000 --- a/.devcontainer/Dockerfile.centos +++ /dev/null @@ -1,61 +0,0 @@ -ARG ARCH="amd64" -ARG CENTOS_VERSION="8" -FROM ${ARCH}/centos:${CENTOS_VERSION} - -# Add some CA certificates -COPY .devcontainer/extra_cas /etc/pki/ca-trust/source/anchors -RUN set -ex && update-ca-trust - -# Install some build tools -RUN set -ex \ - && yum -y groupinstall "Development Tools" \ - && yum -y install \ - git \ - gdb \ - vim \ - curl \ - make \ - subversion \ - bash-completion - -# Add some python dependencies -RUN set -ex && yum -y install python2-devel || yum -y install python-devel - -# We need CMake 3 for MIP, so install that here -ARG CMAKE_VERSION="3.23.0" -RUN set -ex \ - && yum -y install epel-release \ - && export CMAKE_MAJOR_VERSION=$(echo ${CMAKE_VERSION} | cut -d"." -f-2) \ - && curl -fsSLo /tmp/cmake-${CMAKE_VERSION}.tar.gz https://cmake.org/files/v${CMAKE_MAJOR_VERSION}/cmake-${CMAKE_VERSION}.tar.gz \ - && tar -C /tmp/ -xzf /tmp/cmake-${CMAKE_VERSION}.tar.gz \ - && cd /tmp/cmake-${CMAKE_VERSION} \ - && ./bootstrap \ - --prefix="/usr" \ - --parallel=$(nproc) \ - -- \ - -DCMAKE_INSTALL_PREFIX="/usr" \ - -DCMAKE_BUILD_TYPE="RELEASE" \ - -DCMAKE_USE_OPENSSL=OFF \ - && make -j$(nproc) \ - && make install \ - && rm -rf /tmp/cmake-* - -# Add a user that will be used when shelling into this container and allow them to use devices -ARG USER_ID=1000 -ARG GROUP_ID=1000 -RUN set -ex \ - && yum install -y \ - sudo \ - && groupadd -g ${USER_ID} microstrain \ - && useradd \ - -N \ - -m \ - -u ${USER_ID} \ - -g ${GROUP_ID} \ - -G "dialout" \ - -s "/bin/bash" \ - microstrain \ - && echo 'microstrain ALL=(ALL) NOPASSWD:ALL' >> /etc/sudoers - -# Append /usr/lib to LD_LIBRARY_PATH? Feels like we shouldn't need to do this -ENV LD_LIBRARY_PATH "${LD_LIBRARY_PATH}:/usr/lib" diff --git a/Jenkinsfile b/Jenkinsfile index 2bd14a899..47128af12 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -115,21 +115,6 @@ pipeline { } } } - stage('Centos amd64') { - agent { label 'linux-amd64' } - options { - skipDefaultCheckout() - timeout(time: 5, activity: true, unit: 'MINUTES') - } - steps { - script { - checkoutRepo() - env.setProperty('BRANCH_NAME', branchName()) - sh "./.devcontainer/docker_build.sh --os centos --arch amd64" - archiveArtifacts artifacts: 'build_centos_amd64/mipsdk_*' - } - } - } stage('Ubuntu arm64') { agent { label 'linux-arm64' } options { From ef2d82b132e1a6ec63fdebce8005c7149e77829b Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Fri, 20 Sep 2024 16:30:54 -0400 Subject: [PATCH 129/147] Moved documentation builder to Linux --- .devcontainer/Dockerfile.ubuntu | 3 ++- .devcontainer/docker_build.sh | 33 ++++++++++++++++++++++++++------- Jenkinsfile | 9 ++------- 3 files changed, 30 insertions(+), 15 deletions(-) diff --git a/.devcontainer/Dockerfile.ubuntu b/.devcontainer/Dockerfile.ubuntu index f783f26e0..5b060aba9 100644 --- a/.devcontainer/Dockerfile.ubuntu +++ b/.devcontainer/Dockerfile.ubuntu @@ -22,7 +22,8 @@ RUN set -ex \ zlib1g-dev \ subversion \ build-essential \ - bash-completion + bash-completion \ + doxygen # Add a user that will be used when shelling into this container and allow them to use devices ARG USER_ID=1000 diff --git a/.devcontainer/docker_build.sh b/.devcontainer/docker_build.sh index 424afa992..a2d94caad 100755 --- a/.devcontainer/docker_build.sh +++ b/.devcontainer/docker_build.sh @@ -8,6 +8,7 @@ set -e # Get some arguments from the user os="ubuntu" arch="amd64" +build_docs=false while [[ $# -gt 0 ]]; do case $1 in --os) @@ -20,6 +21,10 @@ while [[ $# -gt 0 ]]; do shift # past argument shift # past value ;; + --docs) + build_docs=true + shift # past argument + ;; *) shift # past argument ;; @@ -31,9 +36,15 @@ script_dir="$(cd "$(dirname "${BASH_SOURCE[0]}")" &> /dev/null && pwd)" project_dir="${script_dir}/.." docker_project_dir="/home/microstrain/mipsdk" dockerfile="${script_dir}/Dockerfile.${os}" -build_dir_name="build_${os}_${arch}" -image_name="microstrain/mipsdk_${os}_builder:${arch}" +if [ ${build_docs} = true ]; then + build_dir_name="build_docs" + image_name="microstrain/mipsdk_docs_builder:${arch}" +else + build_dir_name="build_${os}_${arch}" + image_name="microstrain/mipsdk_${os}_builder:${arch}" +fi + # Build the docker image docker build \ @@ -49,6 +60,17 @@ if [ "${ISHUDSONBUILD}" != "True" ]; then docker_it_flags="-it" fi +if [ ${build_docs} = true ]; then + configure_flags="-DMICROSTRAIN_BUILD_DOCUMENTATION=ON" + build_target="package_docs" +else + configure_flags="\ + -DMICROSTRAIN_BUILD_EXAMPLES=ON \ + -DMICROSTRAIN_BUILD_PACKAGE=ON \ + -DCMAKE_BUILD_TYPE=RELEASE" + build_target="package" +fi + # Run the build in the docker image docker run \ --rm \ @@ -61,10 +83,7 @@ docker run \ rm -rf ${docker_project_dir}/${build_dir_name}; \ mkdir ${docker_project_dir}/${build_dir_name}; \ cd ${docker_project_dir}/${build_dir_name}; \ - cmake ${docker_project_dir} \ - -DMICROSTRAIN_BUILD_EXAMPLES=ON \ - -DMICROSTRAIN_BUILD_PACKAGE=ON \ - -DCMAKE_BUILD_TYPE=RELEASE; \ + cmake ${docker_project_dir} ${configure_flags}; \ cmake --build . -j$(nproc); \ - cmake --build . --target package; \ + cmake --build . --target ${build_target}; \ " diff --git a/Jenkinsfile b/Jenkinsfile index 47128af12..495092cf9 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -39,7 +39,7 @@ pipeline { // Run all the builds in parallel parallel { stage('Documentation') { - agent { label 'windows10' } + agent { label 'linux-amd64' } options { skipDefaultCheckout() timeout(time: 5, activity: true, unit: 'MINUTES') @@ -48,12 +48,7 @@ pipeline { script { checkoutRepo() env.setProperty('BRANCH_NAME', branchName()) - powershell """ - mkdir build_docs - cd build_docs - cmake .. -DMICROSTRAIN_BUILD_DOCUMENTATION=ON - cmake --build . --target package_docs - """ + sh "./.devcontainer/docker_build.sh --docs" archiveArtifacts artifacts: 'build_docs/mipsdk_*' } } From e38bbec5f32b47786720d130c731ca79362bd76c Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 23 Sep 2024 18:50:07 -0400 Subject: [PATCH 130/147] Fix a few serialization bugs and begin adding associated documentation. --- docs/serialization_docs.c | 118 ++++ .../common/serialization/serializer.hpp | 598 ++++++++++++++++-- 2 files changed, 652 insertions(+), 64 deletions(-) create mode 100644 docs/serialization_docs.c diff --git a/docs/serialization_docs.c b/docs/serialization_docs.c new file mode 100644 index 000000000..4d74346bd --- /dev/null +++ b/docs/serialization_docs.c @@ -0,0 +1,118 @@ +using namespace microstrain::C; +//////////////////////////////////////////////////////////////////////////////// +///@page Serialization +/// +//////////////////////////////////////////////////////////////////////////////// +///@section serialization_C Serialization in C +/// +///@see microstrain::C::microstrain_serializer +///@see microstrain_serializer +/// +/// Serialization infrastructure in C is very basic and is currently limited to +/// built-in types and big-endian protocols. +/// +/// To (de)serialize a buffer, follow these steps: +/// 1. Create a serializer and initialize it via microstrain_serializer_init_insertion +/// or microstrain_serializer_init_extraction, depending on whether you're +/// writing or reading data. +/// 2. Call microstrain_insert_* or microstrain_extract_* for each parameter. +/// 3. Call microstrain_serializer_is_ok to check if all the data was +/// written/read successfully (i.e. fit in the buffer). Alternatively, to +/// verify if exactly buffer_size bytes were read/written, use microstrain_serializer_is_complete. +/// 4. Transmit the written buffer or use the deserialized parameters. +/// +/// When reading an array length from a buffer, it is recommended to use +/// microstrain_extract_count to specify a maximum length. This helps avoid +/// buffer overrun bugs and associated security vulnerabilities. +/// +//////////////////////////////////////////////////////////////////////////////// +///@section serialization_CPP Serialization in C++ +/// +/// The MIP SDK includes a complete serialization system in C++. It supports +/// both big- and little-endian buffers and user-defined types. +/// +///@subsection basic_usage Basic usage +/// +/// To (de)serialize a buffer, follow these steps: +/// 1. Create a microstrain::Serializer, passing in a pointer to your buffer +/// and the size. A starting offset may also be specified for convenience. +/// 2. Call serializer.insert or serializer.extract with the values to be +/// (de)serialized. Multiple calls may be made to these functions if needed. +/// When reading an array length from a buffer, it is recommended to use +/// Serializer::extract_count to specify a maximum count. This helps avoid +/// buffer overrun bugs and associated security vulnerabilities. +/// 3. Check if the data was written/read successfully (i.e. fit in the buffer) +/// by calling Serializer::isOk or Serializer::isFinished (use the latter if +/// the entire buffer should have been used). +/// 4. Transmit the written buffer or use the deserialized parameters. +/// +///@subsection user_types User-defined types +/// +/// All serialization goes through microstrain::insert / microstrain::extract. +/// These are non-member functions and are overloaded for various data types. +/// This makes it possible to extend serialization to new types. +/// +///@par Classes and structs +/// +/// Classes and structs may include one or more of the following member +/// functions to enable serialization support: +/// +///@li `void insert(microstrain::BigEndianSerializer& serializer) const` +///@li `void insert(microstrain::LittleEndianSerializer& serializer) const` +///@li `template void insert(microstrain::Serializer& serializer) const` +/// +///@li `void extract(microstrain::BigEndianSerializer& serializer)` +///@li `void extract(microstrain::LittleEndianSerializer& serializer)` +///@li `template void extract(microstrain::Serializer& serializer)` +/// +/// In addition, the serialization non-member functions may be overloaded as +/// described next. +/// +///@par Other user-defined types +/// +/// Serialization for any custom type may be implemented by overloading +/// the microstrain::insert / microstrain::extract functions. For example: +///@code{.cpp} +/// namespace custom { +/// // An enum which is not typed and thus cannot use the regular enum methods. +/// enum Foo { A=0, B, C, MAX_FOO }; +/// +/// template +/// size_t insert(microstrain::Serializer& serializer, Foo foo) +/// { +/// return microstrain::insert(serializer, uint8_t(foo)); +/// } +/// +/// template +/// size_t extract(microstrain::Serializer& serializer, Foo& foo) +/// { +/// uint8_t value; +/// size_t size = microstrain::extract(serializer, value); +/// if(serializer.isOk()) // Optional check +/// { +/// if(value < MAX_FOO) // Another optional check +/// foo = value; +/// else +/// serializer.invalidate(); +/// } +/// return size; +/// } +/// } // namespace custom +/// +/// // Test function +/// void read_write_foo(custom::Foo foo) +/// { +/// uint8_t buffer[8]; +/// microstrain::BigEndianSerializer serializer(buffer, sizeof(buffer)); +/// serializer.insert(foo); +/// +/// custom::Foo foo2; +/// serializer.setOffset(0); // Jump back to start of buffer +/// serializer.extract(foo2); +/// assert(foo2 == foo); +/// } +/// +///@endcode +/// +///@image html serialization.svg +/// diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index 3468503e6..5d859bf70 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -20,6 +20,33 @@ namespace microstrain { +//////////////////////////////////////////////////////////////////////////////// +///@brief Represents a view of a buffer of bytes of known capacity. +/// +/// The class maintains 3 attributes: +///@li A pointer to the first byte of the buffer. +///@li A capacity indicating the total size of the buffer. +///@li An offset, representing the number of bytes read or written. +/// +/// This class works for either reading or writing data. As data is written/ +/// read, the offset is incremented. Through functions such as pointer() and +/// getPtrAndAdvance(), the next readable/writable location can be accessed. +/// Both of these take a 'required_size' parameter indicating the amount of +/// data intending to be read/written. If sufficient data/space remains, +/// a valid pointer is returned. Otherwise, NULL is returned. The offset is +/// incremented in getPtrAndAdvance() regardless. This means the offset can +/// exceed the size/capacity of the buffer. This is an "overrun" condition, +/// and it can be checked with the isOk(), isFinished(), or hasRemaining() +/// functions. This behavior prevents bugs where an object is partially +/// read/written in the case where a larger parameter (say u32) fails but +/// then a smaller one (say u8) succeeds. With this class an overflowing +/// access will cause every following access to fail. Note that "overrun" +/// here does NOT mean that an out-of-bounds access has occurred. +/// +///@note This class can be constructed with a const buffer, however constness +/// is not enforced. It is up to the user to ensure const buffers are +/// not written. +/// class SerializerBase { public: @@ -28,27 +55,47 @@ class SerializerBase SerializerBase(const uint8_t* ptr, size_t size, size_t offset=0) : m_ptr(const_cast(ptr)), m_size(size), m_offset(offset) {} SerializerBase(microstrain::Span buffer, size_t offset=0) : m_ptr(const_cast(buffer.data())), m_size(buffer.size()), m_offset(offset) {} - size_t capacity() const { return m_size; } - size_t offset() const { return m_offset; } - size_t usedLength() const { return offset(); } - int remaining() const { return int(m_size - m_offset); } - - bool isOverrun() const { return m_offset > m_size; } - bool isOk() const { return !isOverrun(); } - bool isFinished() const { return m_offset == m_size; } - bool hasRemaining(size_t count=0) const { return m_offset+count <= m_size; } - - const uint8_t* basePointer() const { return m_ptr; } - uint8_t* basePointer() { return m_ptr; } - - const uint8_t* pointer(size_t required_size) const { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } - uint8_t* pointer(size_t required_size) { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } - + size_t capacity() const { return m_size; } ///< Returns the total size of the buffer. + size_t offset() const { return m_offset; } ///< Returns the current read or write offset. + size_t usedLength() const { return offset(); } ///< Returns the number of bytes read/written. + int remaining() const { return int(m_size - m_offset); } ///< Returns the number of byte remaining (negative if overflowed). + + bool isOverrun() const { return m_offset > m_size; } ///< Returns true if offset has exceeded the size/capacity. + bool isOk() const { return !isOverrun(); } ///< Returns true if not overrun, i.e. !isOverrun(). + bool isFinished() const { return m_offset == m_size; } ///< Returns true if the entire buffer (and no more) has been read/written. + bool hasRemaining(size_t count=0) const { return m_offset+count <= m_size; } ///< Returns true if at least 'count' bytes remain unread/unwritten. + + uint8_t* basePointer() { return m_ptr; } ///< Returns a pointer to the start of the buffer. + const uint8_t* basePointer() const { return m_ptr; } ///< Returns a pointer to the start of the buffer. + + ///@brief Obtains a pointer to the current offset for reading/writing a value of the specified size. + /// This function does NOT advance the offset value. Generally, you should use getPtrAndAdvance() instead. + ///@param required_size How many bytes will be read/written to the pointer. + ///@returns A valid pointer if required_size bytes are available. NULL otherwise. + uint8_t* pointer(size_t required_size) { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } + const uint8_t* pointer(size_t required_size) const { return hasRemaining(required_size) ? (m_ptr+m_offset) : nullptr; } ///<@copydoc pointer(size_t required_size) + + ///@brief Obtains a pointer to the current offset for reading/writing a value of specified size, and post-increments the offset by that size. + /// Use this function just like pointer(). + ///@param size How many bytes will be read/written to the pointer. The offset is increased by this amount. + ///@returns A valid pointer if size bytes are available. NULL otherwise. + ///Example usage: + ///@code{.cpp} + /// uint32_t value = 5; + /// if(uint8_t* ptr = serializer.getPointerAndAdvance(sizeof(value))) + /// std::memcpy(ptr, &value, sizeof(value)); + ///@endcode uint8_t* getPtrAndAdvance(size_t size) { uint8_t* ptr = hasRemaining(size) ? (m_ptr+m_offset) : nullptr; m_offset += size; return ptr; } - void invalidate() { m_offset = size_t(-1); } + ///@brief Marks the buffer as invalid, i.e. overrun/error state. + /// All further accesses via pointer(), getPtrAndAdvance(), etc. will fail. (basePointer() and capacity() remain valid) + void invalidate() { m_offset = m_size+1; } - // Sets a new offset and returns the old value. + ///@brief Sets a new offset and returns the old value. + /// This can be used to save/restore the current offset. + /// Calling setOffset() after an overrun with an in-range (i.e. non-overrun) value restores the non-overrun status. + ///@param offset New offset. Allowed to exceed the size, i.e. an overrun state. + ///@returns The old offset value. size_t setOffset(size_t offset) { std::swap(m_offset, offset); return offset; } private: @@ -58,7 +105,22 @@ class SerializerBase }; -// Serializer that has the endianness built-in +//////////////////////////////////////////////////////////////////////////////// +///@brief Serializes or deserializes data to/from a byte buffer. +/// +/// Create one of these to handle serialization or deserialization of one or +/// more values to/from a buffer of bytes. +/// +/// You can use `this->insert`/`extract` or directly call the `insert`/`extract` non- +///member functions taking a serializer reference. +/// +/// The endianness is included as part of the %Serializer's type so that it +/// doesn't have to be repeatedly re-specified. It is not included as a +/// runtime parameter for performance reasons (most of the time only a buffer +/// of a known, specific endianness is required). +/// +///@tparam E Endianness of the target buffer. +/// template class Serializer : public SerializerBase { @@ -70,8 +132,8 @@ class Serializer : public SerializerBase template bool insert (const Ts&... values); template bool extract(Ts&... values); - template bool extract_count(T& value, S max_value); - template bool extract_count(T* value, S max_value) { return extract_count(*value, max_value); } + template bool extract_count(T& count, S max_count); + template bool extract_count(T* count, S max_count) { return extract_count(*count, max_count); } }; using BigEndianSerializer = Serializer; @@ -84,10 +146,27 @@ using LittleEndianSerializer = Serializer; // // +//////////////////////////////////////////////////////////////////////////////// +// +// LEVEL 1 SERIALIZATION +// +//////////////////////////////////////////////////////////////////////////////// + // // Built-in types (bool, int, float, ...) // +//////////////////////////////////////////////////////////////////////////////// +///@brief Inserts a numeric value to a Serializer. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of the value to write. Automatically deduced from the value parameter. +/// +///@param buffer Serializer object pointing to the destination buffer. +///@param value A number to write to the buffer. Can be bool, int, uint32_t, float, etc. +/// +///@returns The size of T, for consistency. +/// template typename std::enable_if::value, size_t>::type /*size_t*/ insert(Serializer& buffer, T value) @@ -98,6 +177,17 @@ typename std::enable_if::value, size_t>::type return sizeof(T); } +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads a numeric value from a Serializer. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of the value to read. Automatically deduced from the value parameter. +/// +///@param buffer Serializer object pointing to the source buffer. +///@param[out] value The read value is stored in this variable. Can be a reference to bool, int, uint32_t, float, etc. +/// +///@returns The size of T, for consistency. +/// template typename std::enable_if::value, size_t>::type /*size_t*/ extract(Serializer& buffer, T& value) @@ -113,6 +203,19 @@ typename std::enable_if::value, size_t>::type // Enums // +//////////////////////////////////////////////////////////////////////////////// +///@brief Writes an enum to a Serializer. +/// For this to work properly, the enum must have its underlying type specified, i.e., +/// like `enum Foo : uint32_t { /*...*/ };` +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of the enum. Automatically deduced from the underlying type of the enum. +/// +///@param buffer Serializer object pointing to the destination buffer. +///@param value The enum value to write to the buffer. +/// +///@returns The size of T, for consistency. +/// template typename std::enable_if::value, size_t>::type /*size_t*/ insert(Serializer& buffer, T value) @@ -125,6 +228,19 @@ typename std::enable_if::value, size_t>::type return sizeof(BaseType); } +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads an enum from a Serializer. +/// For this to work properly, the enum must have its underlying type specified, i.e., +/// like `enum Foo : uint32_t { /*...*/ };` +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of the enum. Automatically deduced from the underlying type of the enum. +/// +///@param buffer Serializer object pointing to the source buffer. +///@param[out] value The value will be stored in this variable. +/// +///@returns The size of T, for consistency. +/// template typename std::enable_if::value, size_t>::type /*size_t*/ extract(Serializer& buffer, T& value) @@ -142,11 +258,117 @@ typename std::enable_if::value, size_t>::type } +// +// Classes - if they have member functions "insert" and "extract" +// + +//////////////////////////////////////////////////////////////////////////////// +///@brief Writes a class object to a Serializer. +/// This overload is available to any class which defines a method +/// `insert`. It shall take a Serializer reference as the sole parameter. +/// +/// Example: +///@code{.cpp} +/// class Foo +/// { +/// int x, y; +/// float z; +/// +/// // E.g. for big endian serialization: +/// void insert(microstrain::BigEndianSerializer& serializer) const { +/// insert(serializer, x, y, z); // Write x, y, and z parameters. +/// } +/// // OR, if both big and little serialization are desired: +/// template +/// void insert(microstrain::Serializer& serializer) const { +/// insert(serializer, x, y, z); // Write x, y, and z parameters. +/// } +/// }; +///@endcode +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of the class. Automatically deduced from the object parameter. +/// +///@param serializer Serializer object pointing to the destination buffer. +///@param object The class to write to the buffer. +/// +///@returns The number of bytes written. +/// +template +typename std::enable_if::value , size_t>::type +/*size_t*/ insert(microstrain::Serializer& serializer, const T& object) +{ + size_t offset = serializer.offset(); + object.insert(serializer); + return serializer.offset() - offset; +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads a class object from a Serializer. +/// This overload is available to any class which defines a method +/// `extract`. It shall take a Serializer reference as the sole parameter. +/// +/// Example: +///@code{.cpp} +/// class Foo +/// { +/// int x, y; +/// float z; +/// +/// // E.g. for big endian serialization: +/// void extract(microstrain::BigEndianSerializer& serializer) { +/// extract(serializer, x, y, z); // Read x, y, and z parameters. +/// } +/// // OR, if both big and little serialization are desired: +/// template +/// void insert(microstrain::Serializer& serializer) { +/// extract(serializer, x, y, z); // Read x, y, and z parameters. +/// } +/// }; +///@endcode +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of the class. Automatically deduced from the object parameter. +/// +///@param serializer Serializer object pointing to the source buffer. +///@param object The class to read from the buffer. +/// +///@returns The number of bytes read. +/// +template +typename std::enable_if::value , size_t>::type +/*size_t*/ extract(microstrain::Serializer& serializer, T& object) +{ + size_t offset = serializer.offset(); + object.extract(serializer); + return serializer.offset() - offset; +} + + +//////////////////////////////////////////////////////////////////////////////// +// +// LEVEL 2 SERIALIZATION +// +//////////////////////////////////////////////////////////////////////////////// + // // std::tuple - only supported if std::apply can be used // #if __cpp_lib_apply >= 201603L +//////////////////////////////////////////////////////////////////////////////// +///@brief Writes all values from a std::tuple to a Serializer. +/// +/// This overload is only enabled if std::apply from c++17 is available. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam Ts Types contained in the tuple. Deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the destination buffer. +///@param values Tuple to serialize. +/// +///@returns The total sizes of each type in the enum (i.e. Ts). +/// template size_t insert(Serializer& serializer, const std::tuple& values) { @@ -157,7 +379,19 @@ size_t insert(Serializer& serializer, const std::tuple& values) return std::apply(lambda, values); } -// std::tuple of references +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads values from a Serializer to a series of references wrapped in a std::tuple. +/// +/// This overload is only enabled if std::apply from c++17 is available. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam Ts Types contained in the tuple. Deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the source buffer. +///@param values Tuple of references (i.e. via std::ref or std::reference_wrapper) to the destination variables. +/// +///@returns The total sizes of each type in the enum (i.e. Ts). +/// template size_t extract(Serializer& serializer, const std::tuple...>& values) { @@ -171,35 +405,23 @@ size_t extract(Serializer& serializer, const std::tuple -typename std::enable_if::value , size_t>::type -/*size_t*/ insert(microstrain::Serializer& serializer, const T& object) -{ - size_t offset = serializer.offset(); - object.insert(serializer); - return serializer.offset() - offset; -} - -// Generic classes which have an "extract" method. -template -typename std::enable_if::value , size_t>::type -/*size_t*/ extract(microstrain::Serializer& serializer, T& object) -{ - size_t offset = serializer.offset(); - object.extract(serializer); - return serializer.offset() - offset; -} - // // Arrays of runtime length // +//////////////////////////////////////////////////////////////////////////////// +///@brief Writes an array to a Serializer. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of array elements. Automatically deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the destination buffer. +///@param values Pointer to the first value in the array. +///@param count Number of elements in the array to write. +/// +///@returns The total number of bytes written. +/// template size_t insert(Serializer& serializer, const T* values, size_t count) { @@ -223,6 +445,18 @@ size_t insert(Serializer& serializer, const T* values, size_t count) } } +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads an array from a Serializer. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of array elements. Automatically deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the source buffer. +///@param values Pointer to the first value in the array. +///@param count Number of elements in the array to read. +/// +///@returns The total number of bytes read. +/// template size_t extract(Serializer& serializer, T* values, size_t count) { @@ -246,11 +480,34 @@ size_t extract(Serializer& serializer, T* values, size_t count) } } +//////////////////////////////////////////////////////////////////////////////// +///@brief Writes an array to a Serializer via a Span. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of array elements. Automatically deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the destination buffer. +///@param values Span containing pointer and count. +/// +///@returns The total number of bytes written. +/// template size_t insert(Serializer& serializer, microstrain::Span values) { return insert(serializer, values.data(), values.size()); } + +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads an array from a Serializer via a Span. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of array elements. Automatically deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the source buffer. +///@param values Span containing pointer and count. +/// +///@returns The total number of bytes read. +/// template size_t extract(Serializer& serializer, microstrain::Span values) { @@ -262,22 +519,70 @@ size_t extract(Serializer& serializer, microstrain::Span values) // Arrays of fixed size // +//////////////////////////////////////////////////////////////////////////////// +///@brief Writes a fixed-size array to a Serializer. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of array elements. Automatically deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the destination buffer. +///@param values C-style array of values +/// +///@returns The total number of bytes written. +/// template size_t insert(Serializer& serializer, const T(&values)[N]) { return insert(serializer, values, N); } + +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads a fixed-size array from a Serializer. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of array elements. Automatically deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the source buffer. +///@param values C-style array of values +/// +///@returns The total number of bytes read. +/// template size_t extract(Serializer& serializer, T(&values)[N]) { return extract(serializer, values, N); } + + +//////////////////////////////////////////////////////////////////////////////// +///@brief Writes a std::array to a Serializer. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of array elements. Automatically deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the destination buffer. +///@param values std::array of values +/// +///@returns The total number of bytes written. +/// template size_t insert(Serializer& serializer, const std::array& values) { return insert(serializer, values.data(), values.size()); } + +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads a std::array from a Serializer. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of array elements. Automatically deduced from the values parameter. +/// +///@param serializer Serializer object pointing to the source buffer. +///@param values std::array of values +/// +///@returns The total number of bytes read. +/// template size_t extract(Serializer& serializer, const std::array& values) { @@ -288,16 +593,32 @@ size_t extract(Serializer& serializer, const std::array& values) // Multiple values at once - more efficient since it avoids multiple size checks // +//////////////////////////////////////////////////////////////////////////////// +///@brief Writes multiple values to a Serializer. +/// +/// This function is equivalent to calling insert on each parameter in sequence. +/// +/// This function can make use of C++17 fold expressions to improve performance +/// by combining the buffer bounds checks when all types are of known size (i.e. numeric types). +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam Ts Types of values. Automatically deduced from the values parameters. +/// +///@param serializer Serializer object pointing to the destination buffer. +///@param values One or more parameters to be written. +/// +///@returns The total number of bytes written. +/// #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type -/*size_t*/ insert(Serializer& buffer, Ts... values) +/*size_t*/ insert(Serializer& serializer, Ts... values) { if constexpr( (std::is_arithmetic::value && ...) ) { const size_t size = ( ... + sizeof(Ts) ); - if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) + if(uint8_t* ptr = serializer.getPtrAndAdvance(size)) { size_t offset = 0; ( ..., (offset += serialization::write(ptr+offset, values)) ); @@ -307,7 +628,7 @@ typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type return size; } else // Class types may not have fixed sizes, can't optimize them - return ( ... + insert(buffer, values) ); + return ( ... + insert(serializer, values) ); } #else template @@ -318,16 +639,32 @@ size_t insert(Serializer& serializer, const T0& value0, const T1& value1, Ts. #endif +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads multiple values from a Serializer. +/// +/// This function is equivalent to calling extract on each parameter in sequence. +/// +/// This function can make use of C++17 fold expressions to improve performance +/// by combining the buffer bounds checks when all types are of known size (i.e. numeric types). +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam Ts Types of values. Automatically deduced from the values parameters. +/// +///@param serializer Serializer object pointing to the destination buffer. +///@param values One or more parameters to be read. +/// +///@returns The total number of bytes read. +/// #if __cpp_fold_expressions >= 201603L && __cpp_if_constexpr >= 201606L template typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type -/*size_t*/ extract(Serializer& buffer, Ts&... values) +/*size_t*/ extract(Serializer& serializer, Ts&... values) { if constexpr( (std::is_arithmetic::value && ...) ) { const size_t size = ( ... + sizeof(Ts) ); - if(uint8_t* ptr = buffer.getPtrAndAdvance(size)) + if(uint8_t* ptr = serializer.getPtrAndAdvance(size)) { size_t offset = 0; ( ..., (offset += serialization::read(ptr+offset, values)) ); @@ -337,7 +674,7 @@ typename std::enable_if<(sizeof...(Ts) > 1), size_t>::type return size; } else // Class types may not have fixed sizes, can't optimize them - return ( ... + extract(buffer, values) ); + return ( ... + extract(serializer, values) ); } #else template @@ -352,14 +689,73 @@ size_t extract(Serializer& serializer, T0& value0, T1& value1, Ts&... values) // Raw buffer - avoids the need to create a serializer yourself. // +//////////////////////////////////////////////////////////////////////////////// +///@brief Serializes a value to a raw byte buffer. +/// +/// Use this overload to write a single value without needing to +/// manually construct a Serializer object. +/// +/// Example: +///@code{.cpp} +/// uint8_t buffer[256]; +/// uint32_t value = 16909060; // 0x01020304 +/// insert(value, buffer, sizeof(buffer), 0, false); +/// // Buffer = [0x01, 0x02, 0x03, 0x04] +/// insert(value, buffer, sizeof(buffer), 0, false); +/// // Buffer = [0x04, 0x03, 0x02, 0x01] +///@endcode +/// +///@tparam E Endianness of buffer. Must be manually specified. +///@tparam T Type of value. Automatically deduced from the value parameter. +/// +///@param value Parameter to serialize. This can be any serializable type. +///@param buffer Pointer to first element of the byte buffer. +///@param buffer_length Length/size of buffer. +///@param offset Starting offset. Default 0. +///@param exact_size Returns true only if exactly buffer_length plus offset bytes are written. Default false. +/// +///@returns False if the buffer isn't large enough. +///@returns False if exact_size is true and the number of bytes written didn't equal buffer_length. +///@returns True otherwise. +/// template -bool insert(const T& value, uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=true) +bool insert(const T& value, uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=false) { Serializer serializer(buffer, buffer_length, offset); serializer.insert(value); return exact_size ? serializer.isFinished() : serializer.isOk(); } +//////////////////////////////////////////////////////////////////////////////// +///@brief Deserializes a value from a raw byte buffer. +/// +/// Use this overload to read a single value without needing to +/// manually construct a Serializer object. +/// +/// Example: +///@code{.cpp} +/// uint8_t buffer[4] = {0x01, 0x02, 0x03, 0x04}; +/// uint32_t value_BE; +/// uint32_t value_LE; +/// extract(value_BE, buffer, sizeof(buffer), 0, true); +/// extract(value_LE, buffer, sizeof(buffer), 0, true); +/// // value_BE == 0x01020304 +/// // value_LE == 0x04030201 +///@endcode +/// +///@tparam E Endianness of buffer. Must be manually specified. +///@tparam T Type of value. Automatically deduced from the value parameter. +/// +///@param value Parameter to deserialize. This can be any serializable type. +///@param buffer Pointer to first element of the byte buffer. +///@param buffer_length Length/size of buffer. +///@param offset Starting offset (default 0). +///@param exact_size Returns true only if exactly buffer_length-offset bytes are written. Default false. +/// +///@returns False if the buffer doesn't have enough data. +///@returns False if exact_size is true and the number of bytes read plus offset didn't equal buffer_length. +///@returns True otherwise. +/// template bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=false) { @@ -373,9 +769,19 @@ bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offse // Special Deserialization // -// Deserialize and return by value - #ifdef MICROSTRAIN_HAS_OPTIONAL +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads a value from a serializer and returns it via std::optional. +/// +/// This overload is only enabled if std::optional is supported. +/// +///@tparam E Endianness of buffer. Automatically deduced from the serializer parameter. +///@tparam T Type of value. Must be manually specified. +/// +///@param buffer Serializer object pointing to the buffer. +/// +///@returns The value read from the buffer, or std::nullopt if it couldn't be read. +/// template std::optional extract(Serializer& serializer) { @@ -386,6 +792,23 @@ std::optional extract(Serializer& serializer) return std::nullopt; } +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads a value from a raw byte buffer and returns it via std::optional. +/// +/// This overload is only enabled if std::optional is supported. +/// +///@see bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offset=0, bool exact_size=false) +/// +///@tparam E Endianness of buffer. Must be manually specified. +///@tparam T Type of value. Must be manually specified. +/// +///@param buffer Pointer to first element of the byte buffer. +///@param buffer_length Length/size of buffer. +///@param offset Starting offset (default 0). +///@param exact_size Returns a value only if exactly buffer_length-offset bytes are read. Default false. +/// +///@returns The value read from the buffer, or std::nullopt if it couldn't be read. +/// template std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bool exact_size=false) { @@ -398,12 +821,25 @@ std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bo #endif -// +//////////////////////////////////////////////////////////////////////////////// // // Serializer member functions which depend on the above overloads. // -// - +//////////////////////////////////////////////////////////////////////////////// + +//////////////////////////////////////////////////////////////////////////////// +///@brief Serializes one or more values. +/// +/// This function defers to the non-member function microstrain::insert. By +/// doing so, it allows the user to provide custom overloads for their own +/// types. Any type supported by the non-member functions may be used here. +/// +///@tparam Ts Types of values to serialize. +/// +///@param values One or more parameters to serialize. +/// +///@returns True if all values were successfully written. +/// template template bool Serializer::insert(const Ts&... values) @@ -412,9 +848,24 @@ bool Serializer::insert(const Ts&... values) // https://stackoverflow.com/questions/13407205/calling-nonmember-instead-of-member-function using microstrain::insert; - return insert(*this, values...); + insert(*this, values...); + + return isOk(); } +//////////////////////////////////////////////////////////////////////////////// +///@brief Deserializes one or more values. +/// +/// This function defers to the non-member function microstrain::extract. By +/// doing so, it allows the user to provide custom overloads for their own +/// types. Any type supported by the non-member functions may be used here. +/// +///@tparam Ts Types of values to deserialize. +/// +///@param[out] values One or more parameters to deserialize. +/// +///@returns True if all values were successfully read. +/// template template bool Serializer::extract(Ts&... values) @@ -426,18 +877,37 @@ bool Serializer::extract(Ts&... values) return extract(*this, values...); } -// Extract a counter with maximum value. +//////////////////////////////////////////////////////////////////////////////// +///@brief Deserializes an integer with maximum permissible value. +/// +/// This function is intended to be used with protocols which have embedded +/// length fields. This function returns false and invalidates the serializer +/// if the count is too large. +/// +///@tparam T Type of value to read. Expected to be integer-like and must +/// support `bool operator<=(S)`. +///@tparam S Type of the maximum value. Usually the same integral type as T, +/// but the only requirement is that it can be compared with T. +/// +///@param[out] count Value read from the buffer. Set to 0 on failure. +///@param max_count Maximum permissible value for count (inclusive). +/// +///@returns True if the count was successfully read and is less than +/// or equal to max_count. +/// template template bool Serializer::extract_count(T& count, S max_count) { - this->extract(count); + if( this->extract(count) ) + { + if( count <= max_count ) + return true; - if(count <= max_count) - return true; + invalidate(); + } count = 0; - invalidate(); return false; } From 9b2c778f51009dbac5fe9855917bb7442e7fa550 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 24 Sep 2024 17:32:47 -0400 Subject: [PATCH 131/147] Add documentation and split out docs.c into several markdown files. --- docs/cpp.md | 46 ++++ docs/docs.c | 543 -------------------------------------- docs/main.md | 46 ++++ docs/metadata.md | 66 +++++ docs/mip_cmd_result.md | 40 +++ docs/mip_interface.md | 242 +++++++++++++++++ docs/mip_parser.md | 127 +++++++++ docs/miscellaneous.md | 47 ++++ docs/serialization.md | 279 ++++++++++++++++++++ docs/serialization_docs.c | 118 --------- docs/time.md | 32 +++ 11 files changed, 925 insertions(+), 661 deletions(-) create mode 100644 docs/cpp.md delete mode 100644 docs/docs.c create mode 100644 docs/main.md create mode 100644 docs/metadata.md create mode 100644 docs/mip_cmd_result.md create mode 100644 docs/mip_interface.md create mode 100644 docs/mip_parser.md create mode 100644 docs/miscellaneous.md create mode 100644 docs/serialization.md delete mode 100644 docs/serialization_docs.c create mode 100644 docs/time.md diff --git a/docs/cpp.md b/docs/cpp.md new file mode 100644 index 000000000..9bb123c0f --- /dev/null +++ b/docs/cpp.md @@ -0,0 +1,46 @@ +C++ Standard Support {#cpp_standards} +==================== + +The MIP SDK requires at least C++14 support, but some parts of the MIP SDK can make use of newer C++ features. +These parts are guarded by `#ifdefs` for the `__cplusplus` version or [feature test macros](https://en.cppreference.com/w/cpp/feature_test) +and they will be safely ignored if your compiler lacks support. + +In a few cases however, this can be dangerous when the MIP SDK is built as a library (e.g., MicroStrain +pre-built versions from github) and then gets used in a project with a different C++ standard version. If the `#ifdef` +guards cause a different implementation to be selected, then there is a mismatch and a violation of the one-definition +rule. This can cause linker errors or mysterious crashes and odd behavior. To avoid this, the MIP SDK requires that the +user explicitly opt-in to certain C++ features. This "opt-in" choice must be made identically when the library is +compiled and then in the project where it is used (this includes anywhere the MIP SDK headers are included). + +std::span +--------- + +A "span" in C++ parlance is the combination of a pointer and length, typically representing a view of an array. The +MIP SDK provides an implementation called `microstrain::Span`, which tries to be compatible with `std::span` from C++20. +It includes most, but not all, features from the standard version. If your compiler supports it, you may use `std::span` +instead by defining `MICROSTRAIN_USE_STD_SPAN`. This will replace the microstrain span implementation with a +typedef to `std::span`. + +https://en.cppreference.com/w/cpp/container/span + +std::endian +----------- + +The serialization system requires a notion of endianness. By default, an enum called `microstrain::Endian` is defined +which provides integer constants representing big and little endianness. If your compiler supports `std::endian` from +C++20, you may define `MICROSTRAIN_USE_STD_ENDIAN` in your project. This will replace the microstrain enum with a +typedef to `std::endian`. + +https://en.cppreference.com/w/cpp/types/endian + +Other Optional C++ Features +--------------------------- + +These features can be used with the MIP SDK if your compiler supports them. No special `#defines` are necessary as +compiled library code is not affected by the choice. They are used by header-only features and no alternative +implementations are supplied with which they could conflict. + +* [std::apply](https://en.cppreference.com/w/cpp/utility/apply) +* [fold expressions](https://en.cppreference.com/w/cpp/language/fold) +* [constexpr if](https://en.cppreference.com/w/cpp/language/if) +* [std::optional](https://en.cppreference.com/w/cpp/utility/optional) diff --git a/docs/docs.c b/docs/docs.c deleted file mode 100644 index 537940e6a..000000000 --- a/docs/docs.c +++ /dev/null @@ -1,543 +0,0 @@ -//////////////////////////////////////////////////////////////////////////////// -///@mainpage MIP SDK -/// -/// Welcome to the official MIP Software Development Kit. This software package -/// provides everything you need to communicate with any MIP-compatible -/// MicroStrain inertial sensor. -/// See @ref mip_interface for details on how to get started. -/// -///@par Main Features -/// -///@li MIP packet creation -///@li Send commands using a single function -///@li Packet parsing and field iteration -///@li Data field deserialization -///@li Simple interface requires only two functions to be defined -///@li Can be used to parse offline binary files -///@li Dual C and C++ API for maximum usability, safety, flexibility, and convenience. -///@li Suitable for bare-metal microcontrollers (Minimal code size and memory footprint, No dynamic memory allocation, No dependence on any RTOS or threading) -/// -///@section quickref_cpp Quick Reference [C++] -/// -/// All C++ functions and classes reside within the mip namespace. -/// The C functions can be accessed via the mip::C namespace. -/// -///@li @ref mip::Interface Top-level MIP interface class. -///@li @ref mip::PacketView An interface to a MIP packet for either transmission or reception. -///@li @ref mip::PacketBuf Similar to PacketRef but includes the data buffer. -///@li @ref mip::FieldView An interface to a MIP field within a packet. -///@li @ref mip::Parser MIP parser class for converting received bytes into packets. -///@li @ref mip::CmdResult Stores the status or result of a MIP command. -/// -///@section quickref_c Quick Reference [C] -/// -/// C does not support the equivalent of C++ namespaces, so all definitions are -/// global. Most names start with `mip_` to avoid conflicts. -/// In these documentation pages, objects are referred to by their fully- -/// qualified C++ names for clarity. -/// -///@li @ref mip_interface_c -///@li @ref mip_packet_c -///@li @ref mip_field_c -///@li @ref mip_parser_c -///@li @ref mip::C::mip_cmd_result "mip_cmd_result [C]" -/// -/// -//////////////////////////////////////////////////////////////////////////////// -///@page mip_interface Mip Interface -//////////////////////////////////////////////////////////////////////////////// -/// -//////////////////////////////////////////////////////////////////////////////// -///@section mip_interface_interface Application Interface -/// -/// The MIP interface is a high-level abstraction of a physical device which -/// communicates using the MIP protocol. It provides both data callbacks and -/// command functions for controlling and configuring the device: -/// -///@image html mip_interface.svg -/// -/// When an application calls one of the command functions, the MIP interface -/// creates a packet, sends it to the device, and waits for a reply. When the -/// reply is received, the command function returns the reply code to the -/// application. If no reply is received, or if an error occurs, the function -/// will return a status code. -/// -/// Sending and receiving to or from the device occurs via two functions: -///@li mip::Interface::sendToDevice() or -/// mip_interface_send_to_device() for transmission and -///@li mip::Interface::recvFromDevice() or -/// mip_interface_recv_from_device() for reception. -/// -/// Each of these has a corresponding callback to the application. The -/// application is expected to implement the required behavior for each as -/// described below. Additionally, there is an @ref update "update function", -/// which handles periodic tasks such as command timeouts and streaming data -/// collection. An application may optionally override the update callback. -/// -///@li @ref mip::C::mip_send_callback "mip_send_callback" -///@li @ref mip::C::mip_recv_callback "mip_recv_callback" -///@li @ref mip::C::mip_update_callback "mip_update_callback" -/// -/// An application obtains sensor data via the -/// @ref mip_dispatch "dispatch subsystem". There are 3 ways to do so: -///@li Packet callbacks, which call a function when a packet matching the -/// MIP descriptor set is received, -///@li Field callbacks, which call a function when a MIP field matching the -/// descriptor set and field descriptor is called, and -///@li Data pointers, which point to a data structure in memory and update it -/// when the associated data is received. -/// -/// -//////////////////////////////////////////////////////////////////////////////// -///@section mip_commands Sending Commands -/// -/// Typically an application will configure the device, initialize some -/// settings, and start streaming. To do so, it must send commands. In many -/// cases, applications will call a single function for each needed command -/// (e.g. @ref MipCommands_c / @ref MipCommands_cpp). -/// These functions take the command parameters as arguments, send the packet, -/// wait for the reply, and return a result code. Additionally some commands can -/// report back responses from the device. -/// -/// The command functions are blocking, that is, they halt execution until the -/// device responds or the command times out. -/// -/// Note that since MIP data is received serially and is not buffered, data may -/// be received and processed while waiting for command responses. It is -/// recommended (but not required) to set the device to idle during configuration. -/// -//////////////////////////////////////////////////////////////////////////////// -///@section mip_dispatch The Dispatch System -/// -/// Because of the limited resources on embedded platforms, the MIP SDK will not -/// buffer received data, and instead requires the application to process data -/// as it arrives. The MIP interface will dispatch callbacks to the application -/// when the requested data is received. -/// -/// The MIP interface can dispatch data in 3 ways: -///@li Packet callbacks, which call a function with a mip packet, -///@li Field callbacks, which call a function with a single mip field, and -///@li Data pointers, which are updated with data from a single mip field. -/// -/// With the first two options, the callback function will receive a handle to -/// the MIP interface, the associated MIP packet or field, and the reception -/// timestamp. -/// -/// An application must register callbacks with the system during -/// initialization. Each method requires a pointer and the MIP descriptor -/// associated with the data of interest. There is no limit on the number -/// of registered dispatchers, though performance may be affected by using -/// too many. Multiple dispatchers may be registered to the same data. -/// -///@par Packet callbacks -/// -///@code{.cpp} -/// void packet_callback(void* userdata, const mip::PacketView& packet, Timestamp parseTime) -///@endcode -/// -/// Packet callbacks are invoked when a packet is received which matches the -/// registered descriptor set. The descriptor set may also be a wildcard, -/// allowing the application to process any type of packet. -/// -/// An application can register a packet callback to occur either before or -/// after the field callbacks for the data in the same packet. For example, -/// to print a summary of the packet before displaying information about each -/// field, an application would set the callback to occur first. Usually -/// applications will set a packet callback to occur last, so that they can -/// determine if all of the fields have been processed. -/// -///@par Field callbacks -/// -///@code{.cpp} -/// void field_callback(void* userdata, const mip::FieldView& field, Timestamp parseTime) -///@endcode -/// -/// Similar to packet callbacks, field callbacks are invoked when a MIP -/// field is received which matches the specified descriptor set and -/// field descriptor. Either descriptor may be a wildcard. -/// -///@par Data pointers -/// -/// Data pointer dispatchers can alleviate a lot of boilerplate code having to -/// do with deserializing a MIP field and storing it somewhere. An application -/// can register a pointer one of the MIP data structures, along with the -/// associated descriptors, and have it automatically updated. The descriptors -/// cannot be wildcards because the type of the data structure is fixed. -/// -///@par Data callbacks -/// -///@code{.cpp} -/// void data_callback(void* userdata, const mip::data_sensor::ScaledAccel& packet, Timestamp parseTime) -///@endcode -/// -/// Thanks to the power of templates, one additional dispatch mechanism is -/// available for C++ applications. A data callback is similar to a field -/// callback except that instead of getting the raw MIP field data, the function -/// is passed the fully-deserialized data structure. -/// -/// -/// Typically an application will register a series of data or field callbacks -/// and write the data to some kind of data structure. Because the order of -/// these callbacks depends on the device configuration, it can be difficult -/// to know which fields belong together in one sample. The solution is to use -/// a packet callback after all of the fields are received. In the case of -/// wraparound "overflow" MIP packets (see the MIP documentation), packets -/// containing a shared timestamp or event source field at the beginning can -/// be used to group data together. -/// -/// -//////////////////////////////////////////////////////////////////////////////// -///@section update The Update Function -/// -/// The application should call mip_interface_update() periodically to process -/// data sent by the device. This update function will call -/// mip_interface_recv_from_device() to parse packets. When a data packet is -/// received, the list of packet and data callbacks is checked, and any -/// matching callbacks are invoked. The update function should be called at -/// a high enough rate to avoid overflowing the connection buffers. The -/// precision of the reception timestamp is dependent on the update rate. -/// -/// The command functions in @ref MipCommands_c / @ref MipCommands_cpp (e.g. mip::C::mip_write_message_format() / mip::writeMessageFormat()) -/// will block execution until the command completes. Either the device will -/// respond with an ack/nack code, or the command will time out. During this -/// time, the system must be able to receive data from the device in order for -/// command replies to be detected. This occurs via the mip_interface_update() -/// function as well. -/// -///@par Single-threaded applications -/// -/// For single-threaded applications, data can be read from the port directly -/// from within the command function. While the command is waiting (status code -/// MIP_STATUS_WAITING / CmdResult::STATUS_WAITING), repeated calls to the -/// update function will be made. By default, the update function calls -/// mip_interface_recv_from_device(). Because the function is called from -/// within a loop, it should sleep for a short time to wait for data if none -/// has been received yet. Doing so prevents excessive CPU usage and lowers -/// power consumption. -/// -/// The following diagram shows the typical control flow for a single-threaded -/// application. First, the device is configured by setting the message format. -/// Execution flows down into the command processing functions until -/// mip_interface_wait_for_reply() is called. This will repeatedly call -/// mip_interface_update() to pump packets from the device through the system, -/// until either an ack/nack is received or the command times out. -/// Once the device acknowledges the command, control is returned to the -/// application which then registers some data or packet callbacks. It finally -/// goes into a loop in collect_data(). Inside this loop, the update function -/// is called to process data packets. -/// -/// Notice that the same update function is called from both the command -/// function and the data collection loop. If any data packets are received -/// while waiting for a command reply, associated callbacks may be executed. -/// This is why this example application registers its callbacks after the -/// format is configured properly. -/// -///@image html device_update.svg -/// -///@par Multi-threaded applications -/// -/// For some applications, it may be desirable to run all of the data collection -/// from a separate thread. In this case, the command functions must not -/// call the update function as that would cause a race condition between the -/// command thread and the data thread. Instead, the command thread should -/// simply sleep or yield and let the data thread process the ack/nack packet. -/// -/// To allow this behavior, the update function takes a boolean parameter which -/// is true when waiting on a command and false when processing data. The -/// default update function, mip_interface_default_update(), ignores this flag, -/// but applications may override it via mip_interface_set_update_function(). In -/// this case, a wrapper function can be created which implements the above -/// behavior: -///@code{.c} -/// bool user_update_function(struct mip_device* device, bool blocking) -/// { -/// // If called from the data thread, do the normal processing. -/// if( !blocking ) -/// return mip_interface_default_update(device, blocking); -/// -/// // Otherwise, sleep and let the data thread process the reply. -/// std::this_thread::sleep_for(std::chrono::milliseconds(10)); -/// return true; -/// } -/// -/// mip_interface_set_update_function(device, &user_update_function); -///@endcode -/// -///@image html device_update_threaded.svg -/// -/// See the threading demo for an example application. -/// -///@par Other thread-safety concerns -/// -///@li Data transmission to the device (but not sending commands) is thread-safe -/// within the MIP SDK. If multiple threads will send to the device, the -/// application should ensure that the device interface is properly protected. -/// -///@li It is up to the application to ensure that sending and receiving from -/// separate threads is safe. This is true for the built-in serial and TCP -/// connections on most operating systems. -/// -///@par Using a custom update function for other purposes -/// -/// An alternate update function may be used for single-threaded -/// applications, too: -///@li To update a progress bar while waiting for commands to complete -///@li To process data from other devices -///@li To avoid blocking inside mip_interface_recv_from_device() when -/// called from a data processing loop. -///@li To push data through the system in a different way (e.g. without using -/// mip_interface_recv_from_device()) -/// -/// Data may be pushed into the system by calling any of these functions: -///@li mip_interface_default_update() - this is the default behavior. -///@li mip_interface_receive_bytes() - process bytes, given a buffer. -///@li mip_interface_receive_packet() - process pre-parsed packets. -///@li mip_interface_process_unparsed_packets() - continue parsing buffered data. -/// -/// -//////////////////////////////////////////////////////////////////////////////// -///@page parsing_packets Mip Parser -//////////////////////////////////////////////////////////////////////////////// -/// -/// The MIP Parser takes in bytes from the device connection or recorded binary -/// file and extracts the packet data. Data is input to the ring buffer and -/// packets are parsed out one at a time and sent to a callback function. -/// -/// The parser uses a ring buffer to store data temporarily between reception -/// and parsing. This helps even out processor workload on embedded systems -/// when data arrives in large bursts. -/// -///@image html mip_parser.svg -/// -//////////////////////////////////////////////////////////////////////////////// -///@section parsing_data Parsing Data -/// -/// Data is supplied by calling mip_parser_parse() / mip::Parser::parse() with -/// a buffer and length. Along with the data, the user must provide a timestamp. -/// The timestamp serves two purposes: to provide a time of reception indicator -/// and to allow the parser to time out waiting for more data. -/// -/// The parse function takes an additional parameter, `max_packets`, which -/// limits the number of packets parsed. This can be used to prevent a large -/// quantity of packets from consuming too much CPU time and denying service -/// to other subsystems. If the limit is reached, parsing stops and the -/// unparsed portion of the data remains in the ring buffer. The constant value -///@ref MIPPARSER_UNLIMITED_PACKETS disables this limit. -/// -/// To continue parsing, call the parse function again. You may choose to -/// not supply any new data by passing NULL and a length of 0. The timestamp -/// should be unchanged from the previous call for highest accuracy, but it's -/// permissible to use the current time as well. If new data is supplied, the -/// new data is appended to the ring buffer and parsing resumes. The timestamp -/// should be the time of the new data. Previously received but unparsed packets -/// will be assigned the new timestamp. -/// -/// The application must parse enough packets to keep up with the incoming -/// data stream. Failure to do so will result in the ring buffer becoming -/// full. If this happens, the parse function will return a negative number, -/// indicating the number of bytes that couldn't be copied. This will never -/// happen if max_packets is `MIPPARSER_UNLIMITED_PACKETS` because all -/// of the data will be processed as soon as it is received. -/// -//////////////////////////////////////////////////////////////////////////////// -///@section ring_buffer The Ring Buffer -/// -/// The ring buffer's backing buffer is a byte array that is allocated by -/// the application during initialization. It must be large enough to store -/// the biggest burst of data seen at any one time. For example, applications -/// expecting to deal with lots of GNSS-related data will need a bigger buffer -/// because there may be a large number of satellite messages. These messages -/// are sent relatively infrequently but contain a lot of data. If max_packets -/// is `MIPPARSER_UNLIMITED_PACKETS`, then it needs only 512 bytes (enough for -/// one packet, rounded up to a power of 2). -/// -/// In addition to passing data to the parse function, data can be written -/// directly to the ring buffer by obtaining a writable pointer and length -/// from mip_parser_get_write_ptr(). This may be more efficient by skipping a -/// copy operation. Call mip_parser_process_written() to tell the parser how -/// many bytes were written to the pointer. Note that the length returned by -/// `mip_parser_get_write_ptr` can frequently be less than the total -/// available space. An application should call it in a loop as long as there -/// is more data to process and the returned size is greater than 0. -/// -//////////////////////////////////////////////////////////////////////////////// -///@section packet_timeouts Packet Timeouts -/// -/// In some cases it's possible for a packet to be corrupted during -/// transmission or reception (e.g. EMI while in transit on the wire, serial -/// baud rate too low, etc). If the payload length byte is corrupted, it may -/// falsely indicate that the packet is longer than what was sent. Without a -/// timeout, the parser would wait until this extra data (potentially up to 255 -/// bytes) was received before checking and realizing that the checksum failed. -/// Any following packets would be delayed, possibly causing additional commands -/// to time out and make the device appear temporarily unresponsive. Setting a -/// reasonable timeout ensures that the bad packet is rejected more quickly. -/// The timeout should be set so that a MIP packet of the largest possible -/// size (261 bytes) can be transferred well within the transmission time plus -/// any additional processing delays in the application or operating system. -/// As an example, for a 115200 baud serial link a timeout of 30 ms would be -/// about right. You can use the mip_timeout_from_baudrate() function to -/// compute an appropriate timeout. -/// -///@see mip_timestamp -///@see mip::Timestamp -/// -//////////////////////////////////////////////////////////////////////////////// -///@section parsing_process The Packet Parsing Process -/// -/// Packets are parsed from the internal ring buffer one at a time in the parse -/// function. -/// -/// If a packet was previously started but not completed previously (due to -/// requiring more data) then the timeout is checked. If too much time has -/// passed, the packet is discarded and the parsing state reset. This check is -/// only performed once per parse call because that is the only point where the -/// timestamp changes. -/// -///@image html parse_function.svg -/// -/// The current status is held by the `expected_length` variable, which tracks -/// how many bytes are expected to be in the current packet. The parse function -/// enters a loop, checking if there is enough data to complete the next parsing -/// step. -/// -///@image html parse_one_packet.svg -/// -/// `expected_length` starts out as 1 when the parser is searching for the start -/// of a packet. Once a potential start byte (`SYNC1`) is found, the packet's -/// start time is initialized to the current timestamp and `expected_length` is -/// bumped up to the size of a mip packet header (4 bytes). -/// -/// When the expected length is 4 bytes, the header's SYNC2 byte is checked for -/// validity and the payload length field is read. `expected_length` is set to -/// the full packet size (computed as the packet header and checksum size plus -/// the payload size). -/// -/// Finally, when `expected_length` is neither of the above two conditions, it -/// means that the entire packet has been received. Note that other values less -/// than 6 (the size of an empty packet) are not possible. At this point, the -/// data is copied out from the ring buffer to a linear buffer for processing. -/// The checksum is verified, and if it passes, the entire packet is dropped -/// from the ring buffer and the callback function is invoked. -/// -/// If any of the checks in the above steps fails, such as a wrong SYNC2 byte, -/// a single byte is dropped from the ring buffer and the loop is continued. -/// Only a single byte can be dropped, because rogue SYNC1 bytes or truncated -/// packets may hide real mip packets in what would have been their payload. -/// -//////////////////////////////////////////////////////////////////////////////// -///@page command_results Command Result -//////////////////////////////////////////////////////////////////////////////// -/// -///@li @ref mip::C::mip_cmd_result "mip_command_result [C]" -///@li @ref mip::CmdResult "CmdResult [C++]" -/// -/// Command results are divided into two categories, reply codes and status -/// codes. Reply codes are returned by the device, e.g.: -///@li ACK_OK -///@li Unknown command (NACK_COMMAND_UNKNOWN) -///@li Invalid parameter (NACK_INVALID_PARAM) -///@li Command failed (NACK_COMMAND_FAILED) -/// The values of these enums match the corresponding values returned by the -/// device. They are non-negative integers. -/// -/// Status codes are set by this library, e.g.: -///@li General error (STATUS_ERROR) -///@li Timeout (STATUS_TIMEDOUT) -///@li Other statuses are used to track commands in progress -///@li User status codes can also be set (STATUS_USER). -/// -/// All of these are negative integers. -/// -/// You can use `mip_cmd_result_is_reply_code()` / `CmdResult::isReplyCode()` and -/// `mip_cmd_result_is_status_code()` / `CmdResult::isStatusCode()` to distinguish -/// between them. -/// -/// In C++, CmdResult is implicitly convertible to bool. ACK_OK converts to true -/// while everything else converts to false. This allows compact code like -///@code{.cpp} -/// if( !resume(device) ) // resume returns a CmdResult -/// fprintf(stderr, "Failed to resume the sensor\n"); -///@endcode -/// -/// For debugging, the name of command results is available via -/// mip_cmd_result_to_string() / CmdResult::name() -/// -/// In C++, CmdResult defaults to the initial state CmdResult::STATUS_NONE. -/// -//////////////////////////////////////////////////////////////////////////////// -///@page timestamps Timestamps and Timeouts -//////////////////////////////////////////////////////////////////////////////// -/// -///@section timestamp_type Timestamp Type -/// Timestamps (`mip_timestamp` / `Timestamp`) represent the local time when data was received or a packet was parsed. These timestamps -/// are used to implement command timeouts and provide the user with an approximate timestamp of received data. It is not intended to be -/// a precise timestamp or used for synchronization, and it generally cannot be used instead of the timestamps from the connected MIP device. -/// In particular, if you limit the maximum number of packets processed per `update` call, the timestamp of some packets may be delayed. -/// -/// Because different applications may keep track of time differently (especially on embedded platforms), it is up to the user to provide -/// the current time whenever data is received from the device. On a PC, this might come from the posix `clock()` function or from the -/// `std::chrono` library. On ARM systems, it is often derived from the Systick timer. It should be a monotonically increasing value; -/// jumps backwards in time (other than due to wraparound) will cause problems. -/// -/// By default, timestamps are `typedef`'d to `uint64_t`. Typically timestamps are in milliseconds. Embedded systems may wish to use -/// `uint32_t` or even `uint16_t` instead. The value is allowed to wrap around as long as the time between wraparounds is longer than -/// twice the longest timeout needed. If higher precision is needed or wraparound can't be tolerated by your application, define it to -/// `uint64_t`. It must be a standard unsigned integer type. -/// -///@section Command Timeouts -/// -/// Timeouts for commands are broken down into two parts. -/// * A "base reply timeout" applies to all commands. This is useful to compensate for communication latency, such as over a TCP socket. -/// * "Additional time" which applies per command, because some commands may take longer to complete. -/// -/// Currently, only the C++ api offers a way to set the additional time parameter, and only when using the `runCommand` function taking -/// the command structure and the `additionalTime` parameter. -/// -/// The `mip_timeout` / `mip::Timeout` typedef is an alias to the timestamp type. -/// -//////////////////////////////////////////////////////////////////////////////// -///@page other Other Considerations -//////////////////////////////////////////////////////////////////////////////// -/// -///@section known_issues Known Issues and Workarounds -/// -///@par suppress_ack parameters are not supported -/// -/// Some commands accept a parameter named `suppress_ack` which acts to prevent -/// the standard ack/nack reply from being returned by the device, e.g. the -/// 3DM Poll Data command. Use of this parameter is not supported in the MIP SDK -/// and will cause the command to appear to time out after a short delay. -/// -/// If you do not wish to wait for a reply (i.e. just send the command and continue) -/// you can build and send the command yourself: -///@code{.cpp} -/// // Create the command with required parameters. -/// mip::commands_3dm::PollData cmd; -/// cmd.desc_set = mip::data_sensor::DESCRIPTOR_SET; -/// cmd.suppress_ack = true; -/// cmd.num_descriptors = 2; -/// cmd.descriptors[0] = mip::data_sensor::ScaledAccel::FIELD_DESCRIPTOR; -/// cmd.descriptors[1] = mip::data_sensor::ScaledGyro::FIELD_DESCRIPTOR; -/// // Build a packet. -/// mip::PacketBuf packet(cmd); -/// // Send it to the device. -/// device.sendCommand(packet); -///@endcode -/// -///@par Some commands take longer and may time out -/// -/// This applies to the following commands: -///@li Save All Settings (`mip::commands_3dm::DeviceSettings` with `mip::FunctionSelector::SAVE`) -///@li Commanded Built-In Test (`mip::commands_base::BuiltInTest`) -///@li Capture Gyro Bias (`mip::commands_3dm::CaptureGyroBias`) -/// -/// The device timeout must be sufficiently long when sending these commands. -/// There are 3 potential ways to avoid erroneous timeouts: -///@li Set a high overall device timeout. This is the easiest solution but may cause excess -/// delays in your application if the device is unplugged, not powered, etc. -///@li Temporarily set the timeout higher, and restore it after running the long command. -///@li If using C++, use the `mip::Interface::runCommand` function and pass a large enough -/// value for the `additionalTime` parameter. This raises the timeout specifically for that -/// one command instance and is the recommended option. -/// diff --git a/docs/main.md b/docs/main.md new file mode 100644 index 000000000..49fe279a7 --- /dev/null +++ b/docs/main.md @@ -0,0 +1,46 @@ +MIP SDK {#mainpage} +================= + +Welcome to the official MIP Software Development Kit. This software package +provides everything you need to communicate with any MIP-compatible +MicroStrain inertial sensor. +See @ref mip_interface for details on how to get started. + +### Main Features + +* MIP packet creation +* Send commands using a single function +* Packet parsing and field iteration +* Data field deserialization +* Simple interface requires only two functions to be defined +* Can be used to parse offline binary files +* Dual C and C++ API for maximum usability, safety, flexibility, and convenience. +* Suitable for bare-metal microcontrollers (Minimal code size and memory footprint, No dynamic memory allocation, No dependence on any RTOS or threading) + +Quick Reference [C++] {#quickref_cpp} +--------------------- + +All C++ functions and classes reside within the mip namespace. +The C functions can be accessed via the mip::C namespace. + +* mip::Interface Top-level MIP interface class. +* mip::PacketView An interface to a MIP packet for either transmission or reception. +* mip::PacketBuf Similar to PacketRef but includes the data buffer. +* mip::FieldView An interface to a MIP field within a packet. +* mip::Parser MIP parser class for converting received bytes into packets. +* mip::CmdResult Stores the status or result of a MIP command. + +Quick Reference [C] {#quickref_c} +------------------- + +C does not support the equivalent of C++ namespaces, so all definitions are +global. Most names start with `mip_` to avoid conflicts. +In these documentation pages, objects are referred to by their fully- +qualified C++ names for clarity. + +* [mip_interface (C)](mip_interface_c) +* [mip_packet (C)](mip_packet_c) +* [mip_field (C)](mip_field_c) +* [mip_parser (C)](mip_parser_c) +* [mip_cmd_result (C)](mip::C::mip_cmd_result) + diff --git a/docs/metadata.md b/docs/metadata.md new file mode 100644 index 000000000..713228b8b --- /dev/null +++ b/docs/metadata.md @@ -0,0 +1,66 @@ +Metadata {#metadata} +======== + +The MIP SDK includes an additional set of definitions for each MIP field which contain additional information beyond +that needed for the core functionality of sending commands and receiving data. It includes human-readable field names +and information on each parameter, such as name, type, size, etc. This information is accessible at compile time and +can be used for things like pretty-printing, CSV generation, and more. + +Metadata is currently an experimental feature and is subject to changes. It requires C++17 or later. + +Usage: +1. Include the metadata definition header for the corresponding descriptor set. +2. Get a reference or pointer to the metadata for your field. +3. Access members of the reference. + +~~~~~~~~{.cpp} +#include + +template +void print_parameters() +{ + // Obtain a reference for easier access. + constexpr const mip::metadata::FieldInfo& field = mip::metadata::MetadataFor::value; + + // Print field name and descriptor. + std::printf("Field (0x%02X,%02X) %s:\n", field.descriptor.descriptorSet, field.descriptor.fieldDescriptor, field.title); + + // Iterate each parameter. + unsigned int p=0; + for(const mip::metadata::ParameterInfo& param : field.parameters) + { + // Single element (most parameters)? + if(param.count.count == 1) + std::printf(" Parameter %u: %s\n", p, param.name); + + // Fixed-size array? + else if(param.count.isFixed()) + std::printf(" Parameter %u: %s[%u]\n", p, param.name, param.count.count); + + // Variable-sized array with another parameter holding the count? + else if(param.count.hasCounter()) + std::printf(" Parameter %u: %s[%s]\n", p, param.name, field.parameters[param.count.counter.index()].name); + + // Variable-length array which is determined by the payload length. + else + std::printf(" Parameter %u: %s[]\n", p, param.name); + + p++; + } + + std::printf("\n"); +} + +#include +#include + +int main() +{ + print_parameters(); + print_parameters(); + print_parameters(); + + return 0; +} + +~~~~~~~~ diff --git a/docs/mip_cmd_result.md b/docs/mip_cmd_result.md new file mode 100644 index 000000000..99149f5b5 --- /dev/null +++ b/docs/mip_cmd_result.md @@ -0,0 +1,40 @@ +Mip Command Results {#command_results} +=================== + +All of the command functions in the MIP SDK return a Command Result. Command results are represented by an 8-bit enum +type in both C and C++: + +* [mip_command_result (C)](@ref mip::C::mip_cmd_result) +* [CmdResult (C++)](@ref mip::CmdResult) + +Command results are divided into two categories, reply codes and status +codes. Reply codes are returned by the device directly: +* `ACK_OK` - Ok; The command was successful. +* `NACK_COMMAND_UNKNOWN` - Unknown command; the descriptor was not recognized or isn't supported. +* `NACK_INVALID_PARAM` - Invalid parameter; One or more parameters are missing, invalid, or not supported. +* `NACK_COMMAND_FAILED` - Command failed; The device was unable to perform the requested function. + +The values of these enums match the corresponding values returned by the device in the MIP protocol. They are +non-negative 8-bit integers. Please see the documentation for your device for more details. + +Status codes are set by this library and are _negative_ 8-bit integers: +* `STATUS_ERROR` - General error, such as failure to send/receive on the connection. +* `STATUS_TIMEDOUT` - Timeout; No response was heard from the device within the specified time period. +* Other statuses are used to track commands in progress +* `STATUS_USER` - Application-specific codes can also be set. They must be this value or lower (more negative). + +You can use [mip_cmd_result_is_reply()](@ref mip::C::mip_cmd_result_is_reply) / mip::CmdResult::isReplyCode() and +[mip_cmd_result_is_status()](@ref mip::C::mip_cmd_result_is_status) / mip::CmdResult::isStatusCode() to distinguish +between the two categories. + +In C++, CmdResult is implicitly convertible to bool. `ACK_OK` converts to true while everything else converts to false. +This allows compact code like +~~~~~~~~{.cpp} +if( !mip::commands_base::resume(device) ) // resume returns a CmdResult + std::fprintf(stderr, "Failed to resume the sensor\n"); +~~~~~~~~ + +For debugging, the name of command results is available via +[mip_cmd_result_to_string()](@ref mip::C::mip_cmd_result_to_string) / mip::CmdResult::name + +In C++, CmdResult defaults to the initial state `CmdResult::STATUS_NONE`. diff --git a/docs/mip_interface.md b/docs/mip_interface.md new file mode 100644 index 000000000..d4ef8cb1f --- /dev/null +++ b/docs/mip_interface.md @@ -0,0 +1,242 @@ + +Mip Interface {#mip_interface_interface} +============= + +Application Interface +--------------------- + +The MIP interface is a high-level abstraction of a physical device which +communicates using the MIP protocol. It provides both data callbacks and +command functions for controlling and configuring the device: + +![](mip_interface.svg) + +When an application calls one of the command functions, the MIP interface +creates a packet, sends it to the device, and waits for a reply. When the +reply is received, the command function returns the reply code to the +application. If no reply is received, or if an error occurs, the function +will return a status code. + +Sending and receiving to or from the device occurs via two functions: +* mip::Interface::sendToDevice() or mip_interface_send_to_device() for transmission and +* mip::Interface::recvFromDevice() or mip_interface_recv_from_device() for reception. + +Each of these has a corresponding callback to the application. The +application is expected to implement the required behavior for each as +described below. Additionally, there is an @ref update "update function", +which handles periodic tasks such as command timeouts and streaming data +collection. An application may optionally override the update callback. + +* [mip_send_callback](@ref mip::C::mip_send_callback) +* [mip_recv_callback](@ref mip::C::mip_recv_callback) +* [mip_update_callback](@ref mip::C::mip_update_callback) + +An application obtains sensor data via the [dispatch subsystem](@ref mip_dispatch). There are 3 ways to do so: +* Packet callbacks, which call a function when a packet matching the MIP descriptor set is received, +* Field callbacks, which call a function when a MIP field matching the descriptor set and field descriptor is called, + and +* Data pointers, which point to a data structure in memory and update it when the associated data is received. + + +Sending Commands {#mip_commands} +---------------- + +Typically an application will configure the device, initialize some +settings, and start streaming. To do so, it must send commands. In many +cases, applications will call a single function for each needed command +(e.g. @ref MipCommands_c / @ref MipCommands_cpp). +These functions take the command parameters as arguments, send the packet, +wait for the reply, and return a result code. Additionally some commands can +report back responses from the device. + +The command functions are blocking, that is, they halt execution until the +device responds or the command times out. + +Note that since MIP data is received serially and is not buffered, data may +be received and processed while waiting for command responses. It is +recommended (but not required) to set the device to idle during configuration. + +The Dispatch System {#mip_dispatch} +------------------- + +Because of the limited resources on embedded platforms, the MIP SDK will not +buffer received data, and instead requires the application to process data +as it arrives. The MIP interface will dispatch callbacks to the application +when the requested data is received. + +The MIP interface can dispatch data in 3 ways: +* Packet callbacks, which call a function with a mip packet, +* Field callbacks, which call a function with a single mip field, and +* Data pointers, which are updated with data from a single mip field. + +With the first two options, the callback function will receive a handle to +the MIP interface, the associated MIP packet or field, and the reception +timestamp. + +An application must register callbacks with the system during +initialization. Each method requires a pointer and the MIP descriptor +associated with the data of interest. There is no limit on the number +of registered dispatchers, though performance may be affected by using +too many. Multiple dispatchers may be registered to the same data. + +### Packet callbacks + +~~~~~~~~{.cpp} + void packet_callback(void* userdata, const mip::PacketView& packet, Timestamp parseTime) +~~~~~~~~ + +Packet callbacks are invoked when a packet is received which matches the +registered descriptor set. The descriptor set may also be a wildcard, +allowing the application to process any type of packet. + +An application can register a packet callback to occur either before or +after the field callbacks for the data in the same packet. For example, +to print a summary of the packet before displaying information about each +field, an application would set the callback to occur first. Usually +applications will set a packet callback to occur last, so that they can +determine if all of the fields have been processed. + +### Field callbacks + +~~~~~~~~{.cpp} + void field_callback(void* userdata, const mip::FieldView& field, Timestamp parseTime) +~~~~~~~~ + +Similar to packet callbacks, field callbacks are invoked when a MIP +field is received which matches the specified descriptor set and +field descriptor. Either descriptor may be a wildcard. + +### Data pointers + +Data pointer dispatchers can alleviate a lot of boilerplate code having to +do with deserializing a MIP field and storing it somewhere. An application +can register a pointer one of the MIP data structures, along with the +associated descriptors, and have it automatically updated. The descriptors +cannot be wildcards because the type of the data structure is fixed. + +### Data callbacks + +~~~~~~~~{.cpp} + void data_callback(void* userdata, const mip::data_sensor::ScaledAccel& packet, Timestamp parseTime) +~~~~~~~~ + +Thanks to the power of templates, one additional dispatch mechanism is +available for C++ applications. A data callback is similar to a field +callback except that instead of getting the raw MIP field data, the function +is passed the fully-deserialized data structure. + + +Typically an application will register a series of data or field callbacks +and write the data to some kind of data structure. Because the order of +these callbacks depends on the device configuration, it can be difficult +to know which fields belong together in one sample. The solution is to use +a packet callback after all of the fields are received. In the case of +wraparound "overflow" MIP packets (see the MIP documentation), packets +containing a shared timestamp or event source field at the beginning can +be used to group data together. + + +The Update Function {#update} +------------------- + +The application should call mip_interface_update() periodically to process +data sent by the device. This update function will call +mip_interface_recv_from_device() to parse packets. When a data packet is +received, the list of packet and data callbacks is checked, and any +matching callbacks are invoked. The update function should be called at +a high enough rate to avoid overflowing the connection buffers. The +precision of the reception timestamp is dependent on the update rate. + +The command functions in @ref MipCommands_c / @ref MipCommands_cpp (e.g. mip::C::mip_write_message_format() / mip::writeMessageFormat()) +will block execution until the command completes. Either the device will +respond with an ack/nack code, or the command will time out. During this +time, the system must be able to receive data from the device in order for +command replies to be detected. This occurs via the mip_interface_update() +function as well. + +### Single-threaded applications + +For single-threaded applications, data can be read from the port directly +from within the command function. While the command is waiting (status code +MIP_STATUS_WAITING / CmdResult::STATUS_WAITING), repeated calls to the +update function will be made. By default, the update function calls +mip_interface_recv_from_device(). Because the function is called from +within a loop, it should sleep for a short time to wait for data if none +has been received yet. Doing so prevents excessive CPU usage and lowers +power consumption. + +The following diagram shows the typical control flow for a single-threaded +application. First, the device is configured by setting the message format. +Execution flows down into the command processing functions until +mip_interface_wait_for_reply() is called. This will repeatedly call +mip_interface_update() to pump packets from the device through the system, +until either an ack/nack is received or the command times out. +Once the device acknowledges the command, control is returned to the +application which then registers some data or packet callbacks. It finally +goes into a loop in collect_data(). Inside this loop, the update function +is called to process data packets. + +Notice that the same update function is called from both the command +function and the data collection loop. If any data packets are received +while waiting for a command reply, associated callbacks may be executed. +This is why this example application registers its callbacks after the +format is configured properly. + +![](device_update.svg) + +### Multi-threaded applications + +For some applications, it may be desirable to run all of the data collection +from a separate thread. In this case, the command functions must not +call the update function as that would cause a race condition between the +command thread and the data thread. Instead, the command thread should +simply sleep or yield and let the data thread process the ack/nack packet. + +To allow this behavior, the update function takes a boolean parameter which +is true when waiting on a command and false when processing data. The +default update function, mip_interface_default_update(), ignores this flag, +but applications may override it via mip_interface_set_update_function(). In +this case, a wrapper function can be created which implements the above +behavior: +~~~~~~~~{.c} + bool user_update_function(struct mip_device* device, bool blocking) + { + // If called from the data thread, do the normal processing. + if( !blocking ) + return mip_interface_default_update(device, blocking); + + // Otherwise, sleep and let the data thread process the reply. + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + return true; + } + + mip_interface_set_update_function(device, &user_update_function); +~~~~~~~~ + +![](device_update_threaded.svg) + +See the threading demo for an example application. + +### Other thread-safety concerns + +* Data transmission to the device (but not sending commands) is thread-safe + within the MIP SDK. If multiple threads will send to the device, the + application should ensure that the device interface is properly protected. + +* It is up to the application to ensure that sending and receiving from + separate threads is safe. This is true for the built-in serial and TCP + connections on most operating systems. + +### Using a custom update function for other purposes + +An alternate update function may be used for single-threaded applications, too: +* To update a progress bar while waiting for commands to complete +* To process data from other devices +* To avoid blocking inside mip_interface_recv_from_device() when called from a data processing loop. +* To push data through the system in a different way (e.g. without using mip_interface_recv_from_device()) + +Data may be pushed into the system by calling any of these functions: +* mip_interface_default_update() - this is the default behavior. +* mip_interface_receive_bytes() - process bytes, given a buffer. +* mip_interface_receive_packet() - process pre-parsed packets. +* mip_interface_process_unparsed_packets() - continue parsing buffered data. diff --git a/docs/mip_parser.md b/docs/mip_parser.md new file mode 100644 index 000000000..8f96025cf --- /dev/null +++ b/docs/mip_parser.md @@ -0,0 +1,127 @@ +Mip Parser {#parsing_packets} +========== + +The MIP Parser takes in bytes from the device connection or recorded binary +file and extracts the packet data. Data is input to the ring buffer and +packets are parsed out one at a time and sent to a callback function. + +The parser uses a ring buffer to store data temporarily between reception +and parsing. This helps even out processor workload on embedded systems +when data arrives in large bursts. + +![](mip_parser.svg) + +Parsing Data {#parsing_data} +------------ + +Data is supplied by calling mip_parser_parse() / mip::Parser::parse() with +a buffer and length. Along with the data, the user must provide a timestamp. +The timestamp serves two purposes: to provide a time of reception indicator +and to allow the parser to time out waiting for more data. + +The parse function takes an additional parameter, `max_packets`, which +limits the number of packets parsed. This can be used to prevent a large +quantity of packets from consuming too much CPU time and denying service +to other subsystems. If the limit is reached, parsing stops and the +unparsed portion of the data remains in the ring buffer. The constant value +MIPPARSER_UNLIMITED_PACKETS disables this limit. + +To continue parsing, call the parse function again. You may choose to +not supply any new data by passing NULL and a length of 0. The timestamp +should be unchanged from the previous call for highest accuracy, but it's +permissible to use the current time as well. If new data is supplied, the +new data is appended to the ring buffer and parsing resumes. The timestamp +should be the time of the new data. Previously received but unparsed packets +will be assigned the new timestamp. + +The application must parse enough packets to keep up with the incoming +data stream. Failure to do so will result in the ring buffer becoming +full. If this happens, the parse function will return a negative number, +indicating the number of bytes that couldn't be copied. This will never +happen if max_packets is `MIPPARSER_UNLIMITED_PACKETS` because all +of the data will be processed as soon as it is received. + +The Ring Buffer {#ring_buffer} +--------------- + +The ring buffer's backing buffer is a byte array that is allocated by +the application during initialization. It must be large enough to store +the biggest burst of data seen at any one time. For example, applications +expecting to deal with lots of GNSS-related data will need a bigger buffer +because there may be a large number of satellite messages. These messages +are sent relatively infrequently but contain a lot of data. If max_packets +is `MIPPARSER_UNLIMITED_PACKETS`, then it needs only 512 bytes (enough for +one packet, rounded up to a power of 2). + +In addition to passing data to the parse function, data can be written +directly to the ring buffer by obtaining a writable pointer and length +from mip_parser_get_write_ptr(). This may be more efficient by skipping a +copy operation. Call mip_parser_process_written() to tell the parser how +many bytes were written to the pointer. Note that the length returned by +`mip_parser_get_write_ptr` can frequently be less than the total +available space. An application should call it in a loop as long as there +is more data to process and the returned size is greater than 0. + +Packet Timeouts {#packet_timeouts} +--------------- + +In some cases it's possible for a packet to be corrupted during +transmission or reception (e.g. EMI while in transit on the wire, serial +baud rate too low, etc). If the payload length byte is corrupted, it may +falsely indicate that the packet is longer than what was sent. Without a +timeout, the parser would wait until this extra data (potentially up to 255 +bytes) was received before checking and realizing that the checksum failed. +Any following packets would be delayed, possibly causing additional commands +to time out and make the device appear temporarily unresponsive. Setting a +reasonable timeout ensures that the bad packet is rejected more quickly. +The timeout should be set so that a MIP packet of the largest possible +size (261 bytes) can be transferred well within the transmission time plus +any additional processing delays in the application or operating system. +As an example, for a 115200 baud serial link a timeout of 30 ms would be +about right. You can use the mip_timeout_from_baudrate() function to +compute an appropriate timeout. + +See ["mip_timestamp (C)"](@ref mip_timestamp) or [mip::Timestamp (C++)](@ref mip::Timestamp) + +The Packet Parsing Process {#parsing_process} +-------------------------- + +Packets are parsed from the internal ring buffer one at a time in the parse +function. + +If a packet was previously started but not completed previously (due to +requiring more data) then the timeout is checked. If too much time has +passed, the packet is discarded and the parsing state reset. This check is +only performed once per parse call because that is the only point where the +timestamp changes. + +![](parse_function.svg) + +The current status is held by the `expected_length` variable, which tracks +how many bytes are expected to be in the current packet. The parse function +enters a loop, checking if there is enough data to complete the next parsing +step. + +![](parse_one_packet.svg) + +`expected_length` starts out as 1 when the parser is searching for the start +of a packet. Once a potential start byte (`SYNC1`) is found, the packet's +start time is initialized to the current timestamp and `expected_length` is +bumped up to the size of a mip packet header (4 bytes). + +When the expected length is 4 bytes, the header's SYNC2 byte is checked for +validity and the payload length field is read. `expected_length` is set to +the full packet size (computed as the packet header and checksum size plus +the payload size). + +Finally, when `expected_length` is neither of the above two conditions, it +means that the entire packet has been received. Note that other values less +than 6 (the size of an empty packet) are not possible. At this point, the +data is copied out from the ring buffer to a linear buffer for processing. +The checksum is verified, and if it passes, the entire packet is dropped +from the ring buffer and the callback function is invoked. + +If any of the checks in the above steps fails, such as a wrong SYNC2 byte, +a single byte is dropped from the ring buffer and the loop is continued. +Only a single byte can be dropped, because rogue SYNC1 bytes or truncated +packets may hide real mip packets in what would have been their payload. diff --git a/docs/miscellaneous.md b/docs/miscellaneous.md new file mode 100644 index 000000000..8d683afe1 --- /dev/null +++ b/docs/miscellaneous.md @@ -0,0 +1,47 @@ +Other Considerations {#other} +==================== + +Known Issues and Workarounds {#known_issues} +---------------------------- + +### `suppress_ack` parameters are not supported + +Some commands accept a parameter named `suppress_ack` which acts to prevent +the standard ack/nack reply from being returned by the device, e.g. the +3DM Poll Data command. Use of this parameter is not supported in the MIP SDK +and will cause the command to appear to time out after a short delay. + +If you do not wish to wait for a reply (i.e. just send the command and continue) +you can build and send the command yourself: +~~~~~~~~{.cpp} +// Create the command with required parameters. +mip::commands_3dm::PollData cmd; + +cmd.desc_set = mip::data_sensor::DESCRIPTOR_SET; +cmd.suppress_ack = true; +cmd.num_descriptors = 2; +cmd.descriptors[0] = mip::data_sensor::ScaledAccel::FIELD_DESCRIPTOR; +cmd.descriptors[1] = mip::data_sensor::ScaledGyro::FIELD_DESCRIPTOR; + +// Build a packet. +mip::PacketBuf packet(cmd); + +// Send it to the device. +device.sendCommand(packet); +~~~~~~~~ + +### Some commands take longer and may time out + +This applies to the following commands: +* Device Settings (mip::commands_3dm::DeviceSettings), in particular saving settings. +* Commanded Built-In Test (mip::commands_base::BuiltInTest) +* Capture Gyro Bias (mip::commands_3dm::CaptureGyroBias) + +The device timeout must be sufficiently long when sending these commands. +There are 3 potential ways to avoid erroneous timeouts: +* Set a high overall device timeout. This is the easiest solution but may cause excess + delays in your application if the device is unplugged, not powered, etc. +* Temporarily set the timeout higher, and restore it after running the long command. +* If using C++, use the mip::Interface::runCommand function and pass a large enough + value for the `additionalTime` parameter. This raises the timeout specifically for that + one command instance and is the recommended option. diff --git a/docs/serialization.md b/docs/serialization.md new file mode 100644 index 000000000..fbd6c7293 --- /dev/null +++ b/docs/serialization.md @@ -0,0 +1,279 @@ +Serialization {#serialization} +============= + +Serialization in C {#serialization_c} +------------------ + +Serialization infrastructure in C is very basic and is currently limited to built-in types and big-endian protocols. + +To (de)serialize a buffer, follow these steps: +1. Create a serializer and initialize it via `microstrain_serializer_init_insertion` or `microstrain_serializer_init_extraction`, depending on whether you're + writing or reading data. +2. Call `microstrain_insert_*` or `microstrain_extract_*` for each parameter. +3. Call `microstrain_serializer_is_ok` to check if all the data was written/read successfully (i.e. fit in the buffer). + Alternatively, to verify if exactly buffer_size bytes were read/written, use `microstrain_serializer_is_complete`. +4. Transmit the written buffer or use the deserialized parameters. + +When reading an array length from a buffer, it is recommended to use `microstrain_extract_count` to specify a maximum +length. This helps avoid buffer overrun bugs and associated security vulnerabilities. + +Serialization in C++ {#serialization_cpp} +-------------------- + +The MIP SDK includes a complete serialization system in C++. It supports both big- and little-endian buffers and user- +defined types. + +### Basic usage + +To (de)serialize a buffer, follow these steps: +1. Create a microstrain::Serializer, passing in a pointer to your buffer and the size. A starting offset may also be + specified for convenience. +2. Call `serializer.insert` or `serializer.extract` with the values to be (de)serialized. Multiple calls may be made to + these functions if needed. When reading an array length from a buffer, it is recommended to use + `Serializer::extract_count` to specify a maximum count. This helps avoid buffer overrun bugs and associated security + vulnerabilities. +3. Check if the data was written/read successfully (i.e. fit in the buffer) by calling `Serializer::isOk` or + `Serializer::isFinished` (use the latter if the entire buffer should have been used). +4. Transmit the written buffer or use the deserialized parameters. + +Example: + +~~~~~~~~{.cpp} +int main() +{ + // Byte buffers + uint8_t buffer_le[128]; + uint8_t buffer_be[128]; + + // Create serializers + microstrain::BigEndianSerializer bes(buffer_be, sizeof(buffer_be)); + microstrain::LittleEndianSerializer les(buffer_le, sizeof(buffer_le)); + + // Alternatively, specify the endianness via template argument. + //microstrain::Serializer bes2(buffer_be, sizeof(buffer_be)); + //microstrain::Serializer les2(buffer_le, sizeof(buffer_le)); + + // Some variables to serialize + uint8_t a = 22; + int8_t b = -33; + uint16_t c = 1024; + int32_t d = -1000000; + uint64_t e = 0x81726354AABBCCDD; + float f = 1.25f; + double g = -1.1; + + // Serialize all the basic variables. + bes.insert(a,b,c,d,e,f,g); + les.insert(a,b,c,d,e,f,g); + + // buffer_be = [0x16, 0xDF, 0x04,0x00, 0xFF,0xF0,0xBD,0xC0, 0x81,0x72,0x63,0x54,0xAA,0xBB,0xCC,0xDD, 0x3F,0xA0,0x00,0x00, 0xBF,0xF1,0x99,0x99,0x99,0x99,0x99,0x9a] + // buffer_le = [0x16, 0xDF, 0x00,0x04, 0xC0,0xBD,0xF0,0xFF, 0xDD,0xCC,0xBB,0xAA,0x54,0x63,0x72,0x81, 0x00,0x00,0xA0,0x3F, 0x9a,0x99,0x99,0x99,0x99,0x99,0xF1,0xBF] + + // Serialize 20 u64s using C-style array or pointer and size. + uint64_t too_much[20] = {0}; + bes.insert(too_much); // Size is deduced from C-style array. + les.insert(&too_much[0], 20); // 20 items, not 20 bytes. + + // Too much data! Note: no actual overrun / invalid access of the buffer has occurred. + // (20*sizeof(uint64_t) = 160) > (sizeof(buffer) = 128) + assert(!bes.isOk() && !les.isOk()); + + // Jump back to the start of the buffer for deserialization. + // Note: this clears the overrun condition. + bes.setOffset(0); + les.setOffset(0); + assert(bes.isOk() && les.isOk()); + + // Deserialize the values. + bes.extract(a,b,c,d,e,f,g); + les.extract(a,b,c,d,e,f,g); + + // Check if everything was deserialized successfully. + if(!bes.isOk() || !les.isOk()) + return 1; + + // Jump to specific offset. + bes.setOffset(4); + les.setOffset(4); + + // Try to read a value using std::optional (subject to compiler support for C++17). + std::optional vg = microstrain::extract(bes); + assert( vg.has_value() && *vg == d ); + + // Reset again + bes.setOffset(0); + les.setOffset(0); + + // See following examples + + return 0; +} +~~~~~~~~ + +### Supported Types + +The serialization library has support for the following basic types: +* Booleans (as a u8; false->[0x00], true->[0x01]; 0x00 reads as false, anything else as true) +* Signed and unsigned integers of various sizes (u8, s8, u16, ..., u64, s64) +* Floating point values (float and double) +* Enums, provided they have an underlying type specified + +Additionally, the following compound types are supported: +* Arrays, both fixed-size and runtime size + * `std::array` + * `microstrain::Span` / `std::span` + * C-style arrays of fixed, known size + * Pointer and size +* std::tuple (with c++17 support) +* User-defined types (see below) + + Adding to the example above, we have: +~~~~~~~~{.cpp} + // A strongly-typed enum + enum class MyEnum : uint8_t { ZERO=0, ONE=1, TWO=2, THREE, FOUR }; + MyEnum me = MyEnum::TWO; + + auto basics = std::make_tuple(a,b,c,d,e,f,g); + std::array vector4 = {1.0f, 2.0f, 3.0f, 4.0f}; + microstrain::Span vector3(vector4[0], 3); + + /// Serialize a custom enum and the contents of a std::tuple. + bes.insert(me, basics); + les.insert(me, basics); + + /// Serialize an array and Span using the non-member functions. + /// This is equivalent to `s.insert(vector4, vector3)`. + microstrain::insert(bes, vector4, vector3); + microstrain::insert(les, vector4, vector3); +~~~~~~~~ + +### Serialization "One-liners" + +For convenience, a few additional methods are provided for serialization in a single line. +* insert to raw buffer +* extract from raw buffer +* extract to std::optional + +~~~~~~~~{.cpp} +void one_liners() +{ + uint8_t buffer[4]; + microstrain::Span span(buffer, sizeof(buffer)); + + int32_t x = -501; + + // Write a single value to a buffer. + bool ok1 = microstrain::insert(x, span); + bool ok2 = microstrain::insert(x, buffer, sizeof(buffer)); + bool ok3 = microstrain::insert(x, buffer, sizeof(buffer), 0, true); // Enforces all bytes used + + assert(ok1 && ok2 && ok3); + + // Read a single value from the buffer + int32_t y1,y2,y3; + ok1 = microstrain::extract(y1, span); + ok2 = microstrain::extract(y2, span, 0, true); // Enforces all bytes read + ok3 = microstrain::extract(y3, buffer, sizeof(buffer)); + + assert(ok1 && ok2 && ok3 && y1 == x && y2 == x && y3 == x); + + // Read a value of the specified type from the buffer. + // Note: only available with std::optional support from C++17. + std::optional value1 = microstrain::extract(span); + std::optional value2 = microstrain::extract(buffer, sizeof(buffer)); + + assert(value1.has_value() && value2.has_value()); + assert(*value1 == x && *value2 == x); +} +~~~~~~~~ + +### User-defined types + +#### Classes and structs + +Classes and structs may include one or more of the following member functions to enable serialization support: +* `void insert(microstrain::BigEndianSerializer& serializer) const` +* `void insert(microstrain::LittleEndianSerializer& serializer) const` +* `template void insert(microstrain::Serializer& serializer) const` +* `void extract(microstrain::BigEndianSerializer& serializer)` +* `void extract(microstrain::LittleEndianSerializer& serializer)` +* `template void extract(microstrain::Serializer& serializer)` + +In addition, the serialization non-member functions may be overloaded as described next. + +#### Other user-defined types + +All serialization goes through `microstrain::insert` / `microstrain::extract`. These are non-member functions and are +overloaded for various data types. This makes it possible to extend serialization to new types. +Serialization for any custom type may be implemented by overloading the `insert` or `extract` +functions. For example: + +~~~~~~~~{.cpp} +namespace custom +{ + // An enum which is not typed and thus cannot use the regular enum methods. + enum Foo { A=0, B, C, MAX_FOO }; + + // Insert Foo function which just converts to u8. + template + size_t insert(microstrain::Serializer& serializer, Foo foo) + { + return microstrain::insert(serializer, uint8_t(foo)); + } + + // Extract Foo function which range-checks and converts a u8. + template + size_t extract(microstrain::Serializer& serializer, Foo& foo) + { + uint8_t value; + size_t size = microstrain::extract(serializer, value); + if(serializer.isOk()) // Optional check + { + if(value < MAX_FOO) // Another optional check + foo = value; + else + serializer.invalidate(); + } + return size; + } + +} // end namespace custom + +// Test function +void write_read_foo(custom::Foo foo) +{ + // A byte buffer of 8 bytes. + uint8_t buffer[8]; + + // Create the serializer, passing in the buffer. + microstrain::BigEndianSerializer serializer(buffer, sizeof(buffer)); + + // Write foo to the buffer. + // This calls Serializer::insert, which calls the non-member function 'insert'. + // Despite being in the 'custom' namespace, the 'insert(Serializer&, Foo)' + // function will be found via argument-dependent lookup because + // 'Foo' is also in that namespace. + serializer.insert(foo); + + // Jump back to start of buffer for reading. + serializer.setOffset(0); + + // Read foo back out and compare to original. + custom::Foo foo2; + serializer.extract(foo2); + + assert(foo2 == foo); +} +~~~~~~~~ + +### Serialization System Architecture + +The MIP library implements many custom types and heavily leverages the serialization system. It uses `insert`/`extract` +overloads, class methods, strongly-typed enums, and arrays. + +The Serializer uses read/write functions from the microstrain::serialization namespace to handle endianness / +byteswapping and packing at the lowest level. + +This diagram describes the architecture of the serialization system: + +![Serialization Diagram](serialization.svg) diff --git a/docs/serialization_docs.c b/docs/serialization_docs.c deleted file mode 100644 index 4d74346bd..000000000 --- a/docs/serialization_docs.c +++ /dev/null @@ -1,118 +0,0 @@ -using namespace microstrain::C; -//////////////////////////////////////////////////////////////////////////////// -///@page Serialization -/// -//////////////////////////////////////////////////////////////////////////////// -///@section serialization_C Serialization in C -/// -///@see microstrain::C::microstrain_serializer -///@see microstrain_serializer -/// -/// Serialization infrastructure in C is very basic and is currently limited to -/// built-in types and big-endian protocols. -/// -/// To (de)serialize a buffer, follow these steps: -/// 1. Create a serializer and initialize it via microstrain_serializer_init_insertion -/// or microstrain_serializer_init_extraction, depending on whether you're -/// writing or reading data. -/// 2. Call microstrain_insert_* or microstrain_extract_* for each parameter. -/// 3. Call microstrain_serializer_is_ok to check if all the data was -/// written/read successfully (i.e. fit in the buffer). Alternatively, to -/// verify if exactly buffer_size bytes were read/written, use microstrain_serializer_is_complete. -/// 4. Transmit the written buffer or use the deserialized parameters. -/// -/// When reading an array length from a buffer, it is recommended to use -/// microstrain_extract_count to specify a maximum length. This helps avoid -/// buffer overrun bugs and associated security vulnerabilities. -/// -//////////////////////////////////////////////////////////////////////////////// -///@section serialization_CPP Serialization in C++ -/// -/// The MIP SDK includes a complete serialization system in C++. It supports -/// both big- and little-endian buffers and user-defined types. -/// -///@subsection basic_usage Basic usage -/// -/// To (de)serialize a buffer, follow these steps: -/// 1. Create a microstrain::Serializer, passing in a pointer to your buffer -/// and the size. A starting offset may also be specified for convenience. -/// 2. Call serializer.insert or serializer.extract with the values to be -/// (de)serialized. Multiple calls may be made to these functions if needed. -/// When reading an array length from a buffer, it is recommended to use -/// Serializer::extract_count to specify a maximum count. This helps avoid -/// buffer overrun bugs and associated security vulnerabilities. -/// 3. Check if the data was written/read successfully (i.e. fit in the buffer) -/// by calling Serializer::isOk or Serializer::isFinished (use the latter if -/// the entire buffer should have been used). -/// 4. Transmit the written buffer or use the deserialized parameters. -/// -///@subsection user_types User-defined types -/// -/// All serialization goes through microstrain::insert / microstrain::extract. -/// These are non-member functions and are overloaded for various data types. -/// This makes it possible to extend serialization to new types. -/// -///@par Classes and structs -/// -/// Classes and structs may include one or more of the following member -/// functions to enable serialization support: -/// -///@li `void insert(microstrain::BigEndianSerializer& serializer) const` -///@li `void insert(microstrain::LittleEndianSerializer& serializer) const` -///@li `template void insert(microstrain::Serializer& serializer) const` -/// -///@li `void extract(microstrain::BigEndianSerializer& serializer)` -///@li `void extract(microstrain::LittleEndianSerializer& serializer)` -///@li `template void extract(microstrain::Serializer& serializer)` -/// -/// In addition, the serialization non-member functions may be overloaded as -/// described next. -/// -///@par Other user-defined types -/// -/// Serialization for any custom type may be implemented by overloading -/// the microstrain::insert / microstrain::extract functions. For example: -///@code{.cpp} -/// namespace custom { -/// // An enum which is not typed and thus cannot use the regular enum methods. -/// enum Foo { A=0, B, C, MAX_FOO }; -/// -/// template -/// size_t insert(microstrain::Serializer& serializer, Foo foo) -/// { -/// return microstrain::insert(serializer, uint8_t(foo)); -/// } -/// -/// template -/// size_t extract(microstrain::Serializer& serializer, Foo& foo) -/// { -/// uint8_t value; -/// size_t size = microstrain::extract(serializer, value); -/// if(serializer.isOk()) // Optional check -/// { -/// if(value < MAX_FOO) // Another optional check -/// foo = value; -/// else -/// serializer.invalidate(); -/// } -/// return size; -/// } -/// } // namespace custom -/// -/// // Test function -/// void read_write_foo(custom::Foo foo) -/// { -/// uint8_t buffer[8]; -/// microstrain::BigEndianSerializer serializer(buffer, sizeof(buffer)); -/// serializer.insert(foo); -/// -/// custom::Foo foo2; -/// serializer.setOffset(0); // Jump back to start of buffer -/// serializer.extract(foo2); -/// assert(foo2 == foo); -/// } -/// -///@endcode -/// -///@image html serialization.svg -/// diff --git a/docs/time.md b/docs/time.md new file mode 100644 index 000000000..658523b4d --- /dev/null +++ b/docs/time.md @@ -0,0 +1,32 @@ +Timestamps and Timeouts {#timestamps} +======================= + +Timestamp Type {#timestamp_type} +-------------- + +Timestamps ([mip_timestamp](@ref mip::C::mip_timestamp) / mip::Timestamp) represent the local time when data was received or a packet was parsed. These timestamps +are used to implement command timeouts and provide the user with an approximate timestamp of received data. It is not intended to be +a precise timestamp or used for synchronization, and it generally cannot be used instead of the timestamps from the connected MIP device. +In particular, if you limit the maximum number of packets processed per `update` call, the timestamp of some packets may be delayed. + +Because different applications may keep track of time differently (especially on embedded platforms), it is up to the user to provide +the current time whenever data is received from the device. On a PC, this might come from the posix `clock()` function or from the +`std::chrono` library. On ARM Cortex-M systems, it is often derived from the Systick timer. It should be a monotonically increasing value; +jumps backwards in time (other than due to wraparound) will cause problems. + +By default, timestamps are `typedef`'d to `uint64_t`. Typically timestamps are in milliseconds. Embedded systems may wish to use +`uint32_t` or even `uint16_t` instead. The value is allowed to wrap around as long as the time between wraparounds is longer than +twice the longest timeout needed. If higher precision is needed or wraparound can't be tolerated by your application, define it to +`uint64_t`. It must be a standard unsigned integer type. + +Command Timeouts +---------------- + +Timeouts for commands are broken down into two parts. +* A "base reply timeout" applies to all commands. This is useful to compensate for communication latency, such as over a TCP socket. +* "Additional time" which applies per command, because some commands may take longer to complete. + +Currently, only the C++ api offers a way to set the additional time parameter, and only when using the `runCommand` function taking +the command structure and the `additionalTime` parameter. + +The `mip_timeout` / `mip::Timeout` typedef is an alias to the timestamp type. From ef6326c84f93478d8489aadead90576c988893ac Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 24 Sep 2024 17:33:11 -0400 Subject: [PATCH 132/147] Add insert/extract overloads taking Spans. --- .../common/serialization/serializer.hpp | 80 ++++++++++++++++++- 1 file changed, 79 insertions(+), 1 deletion(-) diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index 5d859bf70..4dbcb7cd9 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -750,7 +750,7 @@ bool insert(const T& value, uint8_t* buffer, size_t buffer_length, size_t offset ///@param buffer Pointer to first element of the byte buffer. ///@param buffer_length Length/size of buffer. ///@param offset Starting offset (default 0). -///@param exact_size Returns true only if exactly buffer_length-offset bytes are written. Default false. +///@param exact_size Returns true only if exactly buffer_length-offset bytes are read. Default false. /// ///@returns False if the buffer doesn't have enough data. ///@returns False if exact_size is true and the number of bytes read plus offset didn't equal buffer_length. @@ -765,6 +765,58 @@ bool extract(T& value, const uint8_t* buffer, size_t buffer_length, size_t offse } +// +// Raw buffer - Span version +// + +//////////////////////////////////////////////////////////////////////////////// +///@brief Serializes a value to a raw byte buffer (span version). +/// +/// Use this overload to write a single value without needing to +/// manually construct a Serializer object. +/// +///@tparam E Endianness of buffer. Must be manually specified. +///@tparam T Type of value. Automatically deduced from the value parameter. +/// +///@param value Parameter to serialize. This can be any serializable type. +///@param buffer Source buffer span. +///@param offset Starting offset. Default 0. +///@param exact_size Returns true only if exactly buffer.size()-offset bytes are written. Default false. +/// +///@returns False if the buffer isn't large enough. +///@returns False if exact_size is true and the number of bytes written didn't equal buffer_length. +///@returns True otherwise. +/// +template +bool insert(T value, microstrain::Span buffer, size_t offset=0, bool exact_size=false) +{ + return insert(value, buffer.data(), buffer.size(), offset, exact_size); +} + +//////////////////////////////////////////////////////////////////////////////// +///@brief Deserializes a value from a raw byte buffer (span version). +/// +/// Use this overload to read a single value without needing to +/// manually construct a Serializer object. +/// +///@tparam E Endianness of buffer. Must be manually specified. +///@tparam T Type of value. Automatically deduced from the value parameter. +/// +///@param value Parameter to deserialize. This can be any serializable type. +///@param buffer Source buffer span. +///@param offset Starting offset (default 0). +///@param exact_size Returns true only if exactly buffer.size()-offset bytes are read. Default false. +/// +///@returns False if the buffer doesn't have enough data. +///@returns False if exact_size is true and the number of bytes read plus offset didn't equal buffer_length. +///@returns True otherwise. +/// +template +bool extract(T& value, microstrain::Span buffer, size_t offset=0, bool exact_size=false) +{ + return extract(value, buffer.data(), buffer.size(), offset, exact_size); +} + // // Special Deserialization // @@ -818,6 +870,32 @@ std::optional extract(const uint8_t* buffer, size_t length, size_t offset, bo else return std::nullopt; } + +//////////////////////////////////////////////////////////////////////////////// +///@brief Reads a value from a raw byte span and returns it via std::optional. +/// +/// This overload is only enabled if std::optional is supported. +/// +///@see bool extract(T& value, microstrain::Span buffer, size_t offset=0, bool exact_size=false) +/// +///@tparam E Endianness of buffer. Must be manually specified. +///@tparam T Type of value. Must be manually specified. +/// +///@param buffer Source buffer span. +///@param offset Starting offset (default 0). +///@param exact_size Returns a value only if exactly buffer.size()-offset bytes are read. Default false. +/// +///@returns The value read from the buffer, or std::nullopt if it couldn't be read. +/// +template +std::optional extract(microstrain::Span buffer, size_t offset, bool exact_size=false) +{ + T value; + if(extract(value, buffer.data(), buffer.size(), offset, exact_size)) + return value; + else + return std::nullopt; +} #endif From 7a72ec3f08116a50458d1e0d8b656fc05d5ea600 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Thu, 26 Sep 2024 09:33:32 -0400 Subject: [PATCH 133/147] Update README.md. --- README.md | 86 +++++++++++++++++++++++++++++++------------------------ 1 file changed, 48 insertions(+), 38 deletions(-) diff --git a/README.md b/README.md index c243fc3db..b18cb80c1 100644 --- a/README.md +++ b/README.md @@ -26,20 +26,20 @@ Features Examples -------- - -* Get device information [[C++](./examples/device_info.cpp)] -* Watch IMU [[C](./examples/watch_imu.c) | [C++](./examples/watch_imu.cpp)] -* Threading [[C++](./examples/threading.cpp)] -* Ping [[C++](./examples/ping.cpp)] -* Product-specific examples: - * GQ7 setup [[C](./examples/GQ7/GQ7_example.c) | [C++](./examples/GQ7/GQ7_example.cpp)] - * CV7 setup [[C](./examples/CV7/CV7_example.c) | [C++](./examples/CV7/CV7_example.cpp)] - * GX5-45 setup [[C](./examples/GX5_45/GX5_45_example.c) | [C++](./examples/GX5_45/GX5_45_example.cpp)] - * CV7_INS setup [[C++](./examples/CV7_INS/CV7_INS_simple_example.cpp)] - * CV7_INS with UBlox setup [[C++](./examples/CV7_INS/CV7_INS_simple_ublox_example.cpp)] +| Example | | | Description | +|----------------------------------|-------------------------------------------------------------------|--------------------------------------------------------------|----------------------------------------------------------------------------------------------| +| Generic Examples | | | | +| Get device information | [C++](./examples/device_info.cpp) | | Queries the device strings and prints them to stdout. | +| Watch IMU | [C++](./examples/watch_imu.cpp) | [C](./examples/watch_imu.c) | Configures the IMU for streaming and prints the data to stdout. | +| Threading | [C++](./examples/threading.cpp) | | | +| Ping | [C++](./examples/ping.cpp) | | | +| Product-specific examples | | | | +| CV7 setup | [C++](./examples/CV7/CV7_example.cpp) | [C](./examples/CV7/CV7_example.c) | Configures a CV7 device for typical usage and includes an example of using the event system. | +| CV7_INS setup | [C++](./examples/CV7_INS/CV7_INS_simple_example.cpp) | | Configures a CV7_INS device for typical usage. | +| CV7_INS with UBlox setup | [C++](./examples/CV7_INS/CV7_INS_simple_ublox_example.cpp) | | Configures a CV7_INS device for typical usage with aiding data from a UBlox GNSS receiver. | +| GQ7 setup | [C++](./examples/GQ7/GQ7_example.cpp) | [C](./examples/GQ7/GQ7_example.c) | Configures a GQ7 device for typical usage in a wheeled-vehicle application. | +| GX5-45 setup | [C++](./examples/GX5_45/GX5_45_example.cpp) | [C](./examples/GX5_45/GX5_45_example.c) | Configures a GX5-45 device for typical usage in a wheeled-vehicle application. | +| GX5/CX5/CV5 -15 or -25 setup | [C++](./examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp) | [C](./examples/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.c) | Configures a GX5-45 device for typical usage in a wheeled-vehicle application. | You'll need to enable at least one of the [communications interfaces](#communications-interfaces) in the CMake configuration to use the examples. @@ -114,10 +114,9 @@ How to Build * A working C compiler * C11 or later required -* A working C++ compiler, if using any C++ features * Define `MICROSTRAIN_ENABLE_CPP=OFF` if you don't want to use any C++. Note that some features are only available in C++. - * C++11 or later required for the mip library - * C++14 or later for the examples +* A working C++ compiler, if using any C++ features + * C++14 or later is required. * C++20 or later for metadata and associated examples * CMake version 3.10 or later (technically this is optional, see below) * Doxygen, if building documentation @@ -125,22 +124,25 @@ How to Build ### CMake Build Configuration The following options may be specified when configuring the build with CMake (e.g. `cmake .. -DOPTION=VALUE`): -* MICROSTRAIN_ENABLE_LOGGING - Builds logging functionality into the library. The user is responsible for configuring a logging callback (default enabled) -* MICROSTRAIN_LOGGING_MAX_LEVEL - Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration. Useful if you want some logs, but do not want the overhead compiled into the code. -* MICROSTRAIN_TIMESTAMP_TYPE - Overrides the default timestamp type. See [Timestamps](https://lord-microstrain.github.io/mip_sdk_documentation/latest/timestamps.html) in the documentation. -* MICROSTRAIN_ENABLE_CPP - Causes the src/cpp directory to be included in the build (default enabled). Disable to turn off the C++ api. -* MICROSTRAIN_ENABLE_EXTRAS - Builds some higher level utility classes and functions that may use dynamic memory. -* MICROSTRAIN_ENABLE_SERIAL - Builds the included serial port library (default enabled). -* MICROSTRAIN_ENABLE_TCP - Builds the included socket library (default enabled). -* MICROSTRAIN_BUILD_PACKAGE - Adds a `package` target to the project that will build a `.deb`, `.rpm`, or `.zip` file containing the library -* MICROSTRAIN_BUILD_EXAMPLES - If enabled (`-DMICROSTRAIN_BUILD_EXAMPLES=ON`), the example projects will be built (default disabled). -* MICROSTRAIN_BUILD_TESTING - If enabled (`-DMICROSTRAIN_BUILD_TESTING=ON`), the test programs in the /test directory will be compiled and linked. Run the tests with `ctest`. -* MICROSTRAIN_BUILD_DOCUMENTATION - If enabled, the documentation will be built with doxygen. You must have doxygen installed. -* MICROSTRAIN_BUILD_DOCUMENTATION_FULL - Builds internal documentation (default disabled). -* MICROSTRAIN_BUILD_DOCUMENTATION_QUIET - Suppress standard doxygen output (default enabled). -* MIP_ENABLE_DIAGNOSTICS - Adds some counters to various entities which can serve as a debugging aid. -* MIP_ENABLE_METADATA - Builds metadata for MIP commands. If not set, the system will try to determine if C++20 is available to enable it. C++20 is required for the metadata module. -* MIP_ENABLE_EXTRAS - Builds some higher level utility classes and functions that may use dynamic memory. (default MICROSTRAIN_ENABLE_EXTRAS) + +| CMake Option | Default | Description | +| ------------------------------------- |----------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| MICROSTRAIN_ENABLE_LOGGING | ON | Builds logging functionality into the library. The user is responsible for configuring a logging callback. | +| MICROSTRAIN_LOGGING_MAX_LEVEL | MICROSTRAIN_LOG_LEVEL_WARN | Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration. Useful if you want some logs, but do not want the overhead compiled into the code. | +| MICROSTRAIN_TIMESTAMP_TYPE | uint64_t | Overrides the default timestamp type. See [Timestamps](https://lord-microstrain.github.io/mip_sdk_documentation/latest/timestamps.html) in the documentation. | +| MICROSTRAIN_ENABLE_CPP | ON | Causes the src/cpp directory to be included in the build. Disable to turn off the C++ api. | +| MICROSTRAIN_ENABLE_EXTRAS | ON | Builds some higher level utility classes and functions that may use dynamic memory. | +| MICROSTRAIN_ENABLE_SERIAL | ON | Builds the included serial port library. | +| MICROSTRAIN_ENABLE_TCP | ON | Builds the included socket library (default enabled). | +| MICROSTRAIN_BUILD_PACKAGE | OFF | Adds a `package` target to the project that will build a `.deb`, `.rpm`, or `.zip` file containing the library | +| MICROSTRAIN_BUILD_EXAMPLES | OFF | If enabled, the example projects will be built. | +| MICROSTRAIN_BUILD_TESTING | OFF | If enabled, the test programs in the /test directory will be compiled and linked. Run the tests with `ctest`. | +| MICROSTRAIN_BUILD_DOCUMENTATION | OFF | If enabled, the documentation will be built with doxygen. You must have doxygen installed. | +| MICROSTRAIN_BUILD_DOCUMENTATION_FULL | OFF | Builds internal documentation. | +| MICROSTRAIN_BUILD_DOCUMENTATION_QUIET | ON | Suppress standard doxygen output. | +| MIP_ENABLE_DIAGNOSTICS | ON | Adds some counters to various entities which can serve as a debugging aid. | +| MIP_ENABLE_METADATA | ON if supported | Builds metadata for MIP commands. If not set, the system will try to determine if C++20 is available to enable it. C++20 is required for the metadata module. | +| MIP_ENABLE_EXTRAS | MICROSTRAIN_ENABLE_EXTRAS | Builds some higher level utility classes and functions that may use dynamic memory. (default MICROSTRAIN_ENABLE_EXTRAS) | ### Compilation @@ -175,9 +177,17 @@ include all the necessary files and define a few options. Pass these to your compiler as appropriate, e.g. `arm-none-eabi-gcc -DMICROSTRAIN_TIMESTAMP_TYPE=uint32_t -DMICROSTRAIN_ENABLE_LOGGING=0` -* MICROSTRAIN_ENABLE_LOGGING (and MICROSTRAIN_LOGGING_MAX_LEVEL) - default is enabled -* MICROSTRAIN_TIMESTAMP_TYPE - defaults to uint64_t if not specified -* MIP_ENABLE_DIAGNOSTICS - Supported on embedded platforms to aid debugging +These defines must be set when building the MIP SDK sources and for any code that includes +MIP SDK headers. + +| Name | Description | +|-------------------------------|--------------------------------------------------------------------------------------| +| MICROSTRAIN_ENABLE_LOGGING | Enables logging facilities (e.g. via printf). | +| MICROSTRAIN_LOGGING_MAX_LEVEL | Disables logging more detailed messages (e.g. debug tracing) to improve performance. | +| MICROSTRAIN_TIMESTAMP_TYPE | Type to use for mip::Timestamp / mip::Timeout. Defaults to uint64_t if not defined. | +| MICROSTRAIN_USE_STD_ENDIAN | Define to 1 to enable the use of std::span from C++20. | +| MICROSTRAIN_USE_STD_SPAN | Define to 1 to enable the use of std::endian from C++20. | +| MIP_ENABLE_DIAGNOSTICS | Enables diagnostic counters. | These options affect the compiled code interface and sizes of various structs. They MUST be consistent between compiling the MIP SDK and any other code which includes @@ -187,7 +197,7 @@ rebuilt properly. Normally CMake takes care of this for you). Known Issues ------------ -* `suppress_ack=true` is not supported -* The commanded BIT, device settings, and capture gyro bias commands can time out unless the timeout is increased +* `suppress_ack=true` is not supported. +* The commanded BIT, device settings, and capture gyro bias commands can time out unless the timeout is increased. See the documentation page for [Known Issues](https://lord-microstrain.github.io/mip_sdk_documentation/latest/other.html#known_issues). From 77a9317c99d8fc2622d64415074e932a505957ca Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 2 Oct 2024 12:44:01 -0400 Subject: [PATCH 134/147] - Rename some packet-related functions. - Fix constness issue in PacketView creation. - Add Span overloads for PacketView ctor. - Fix serializer::extract return value. - Rename microstrain_serializer_*_new_field to mip_serializer_*_new_field. - Add packet building/processing examples. --- examples/CMakeLists.txt | 53 ++- examples/mip_packet_example.c | 405 ++++++++++++++++++ examples/mip_packet_example.cpp | 359 ++++++++++++++++ src/c/mip/mip_packet.c | 14 +- src/c/mip/mip_packet.h | 14 +- src/c/mip/mip_serialization.c | 16 +- src/c/mip/mip_serialization.h | 8 +- .../common/serialization/serializer.hpp | 4 +- src/cpp/mip/mip_packet.hpp | 25 +- test/mip/test_mip_fields.c | 2 +- test/mip/test_mip_packet_builder.c | 12 +- test/mip/test_mip_random.c | 2 +- 12 files changed, 848 insertions(+), 66 deletions(-) create mode 100644 examples/mip_packet_example.c create mode 100644 examples/mip_packet_example.cpp diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 04d02fa87..62e60efc2 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -58,32 +58,39 @@ macro(add_mip_example name sources) endmacro() -# C++ examples need either serial or TCP support -if(MICROSTRAIN_ENABLE_CPP AND (MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP)) - - # Generic examples - add_mip_example(DeviceInfo "${EXAMPLE_DIR}/device_info.cpp") - add_mip_example(WatchImu "${EXAMPLE_DIR}/watch_imu.cpp") - add_mip_example(Threads "${EXAMPLE_DIR}/threading.cpp") - if(UNIX) - target_link_libraries(Threads PUBLIC pthread) - endif() - if(MIP_ENABLE_METADATA) - add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") - target_link_libraries(CsvExample PRIVATE ${MIP_METADATA_LIBRARY}) - endif() - - # Product-specific examples - add_mip_example(GQ7_Example "${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") - add_mip_example(CV7_Example "${EXAMPLE_DIR}/CV7/CV7_example.cpp") - add_mip_example(CV7_INS_Simple_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_example.cpp") - add_mip_example(CV7_INS_Simple_Ublox_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_ublox_example.cpp") - add_mip_example(CX5_GX5_45_Example "${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.cpp") - add_mip_example(CX5_GX5_CV5_15_25_Example "${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp") +add_mip_example(MipPacketC "${EXAMPLE_DIR}/mip_packet_example.c") + +if(MICROSTRAIN_ENABLE_CPP) + + add_mip_example(MipPacket "${EXAMPLE_DIR}/mip_packet_example.cpp") + + # C++ examples that need either serial or TCP support + if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) + + # Generic examples + add_mip_example(DeviceInfo "${EXAMPLE_DIR}/device_info.cpp") + add_mip_example(WatchImu "${EXAMPLE_DIR}/watch_imu.cpp") + add_mip_example(Threads "${EXAMPLE_DIR}/threading.cpp") + if(UNIX) + target_link_libraries(Threads PUBLIC pthread) + endif() + if(MIP_ENABLE_METADATA) + add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") + target_link_libraries(CsvExample PRIVATE ${MIP_METADATA_LIBRARY}) + endif() + + # Product-specific examples + add_mip_example(GQ7_Example "${EXAMPLE_DIR}/GQ7/GQ7_example.cpp") + add_mip_example(CV7_Example "${EXAMPLE_DIR}/CV7/CV7_example.cpp") + add_mip_example(CV7_INS_Simple_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_example.cpp") + add_mip_example(CV7_INS_Simple_Ublox_Example "${EXAMPLE_DIR}/CV7_INS/CV7_INS_simple_ublox_example.cpp") + add_mip_example(CX5_GX5_45_Example "${EXAMPLE_DIR}/CX5_GX5_45/CX5_GX5_45_example.cpp") + add_mip_example(CX5_GX5_CV5_15_25_Example "${EXAMPLE_DIR}/CX5_GX5_CV5_15_25/CX5_GX5_CV5_15_25_example.cpp") + endif() endif() -# C examples need serial support +# C examples that need serial support if(MICROSTRAIN_ENABLE_SERIAL) add_mip_example(WatchImuC "${EXAMPLE_DIR}/watch_imu.c") diff --git a/examples/mip_packet_example.c b/examples/mip_packet_example.c new file mode 100644 index 000000000..416db23fd --- /dev/null +++ b/examples/mip_packet_example.c @@ -0,0 +1,405 @@ + +#include "mip/mip_packet.h" +#include "mip/mip_serialization.h" + +#include "mip/definitions/commands_base.h" +#include "mip/definitions/commands_3dm.h" +#include "mip/definitions/data_sensor.h" +#include "mip/definitions/data_shared.h" + +#include +#include + + +// This function demonstrates how to inspect and iterate fields in +// a MIP packet. These functions do not modify the packet and can +// be used on any packet as long as it has valid structure. +void print_packet(const mip_packet_view* packet, const char* name) +{ + // Ensure the packet structure is correct, otherwise a crash may result. + // This checks the following: + // 1. The packet buffer is not NULL. + // 2. The buffer size is at least MIP_PACKET_LENGTH_MIN. + // 3. The payload length does not exceed the buffer size. + // There's generally no need to check this if you're getting packets + // directly from mip_packet_create (with sufficient buffer space) or + // from the mip parser. If you're reading packets from a file, etc., + // without parsing, use this as a cheap validation step. + // In this example, it should always pass. + assert(mip_packet_is_sane(packet)); + + // Roughly equivalent to mip_packet_checksum_value(packet) == mip_packet_compute_checksum(packet). + const char* checksum_str = mip_packet_is_valid(packet) ? "valid" : "invalid"; + + // Print descriptor set, total length, and payload length. + printf( + "%s: desc_set=0x%02X tot_len=%u pay_len=%u chk=%s [", + name, mip_packet_descriptor_set(packet), mip_packet_total_length(packet), mip_packet_payload_length(packet), checksum_str + ); + + // Print each byte in the packet, including header and checksum. + for(size_t i = 0; i < mip_packet_total_length(packet); i++) + { + printf("%02X", mip_packet_pointer(packet)[i]); + } + + puts("]"); + + // Iterate each field in the packet and print it. + mip_field_view field; + mip_field_init_empty(&field); + while(mip_field_next_in_packet(&field, packet)) + { + // Print descriptors (descriptor set always matches the packet). + printf(" (%02X,%02X): payload=[", mip_field_descriptor_set(&field), mip_field_field_descriptor(&field)); + + // Print field payload bytes. + for(size_t i = 0; i < mip_field_payload_length(&field); i++) + { + printf("%02X", mip_field_payload(&field)[i]); + } + + puts("]"); + } +} + +// This function demonstrates how to build mip packets from scratch. +// It starts with simple cases and moves to more complex ones. It +// also shows some of the low-level details to help you understand +// what's happening "under the hood". +void create_packet_from_scratch() +{ + puts("\nCreate packet from scratch"); + + // Create a mip packet and storage buffer. + mip_packet_view packet; + uint8_t buffer[MIP_PACKET_LENGTH_MAX]; + mip_serializer serializer; + + // If the descriptor set is specified (even if it's invalid, i.e. 0x00) + // the constructor initializes a new MIP packet in the buffer. + // Otherwise, it assumes the buffer already contains a valid MIP packet. + mip_packet_create(&packet, buffer, sizeof(buffer), MIP_BASE_CMD_DESC_SET); + + // The packet isn't ready yet, but print it to demonstrate what the raw bytes look like after each step. + print_packet(&packet, "Empty, un-finalized packet"); + + // Write the checksum. + mip_packet_finalize(&packet); + print_packet(&packet, "Empty packet with checksum"); + + // + // FIELD #1 + // + // A Ping command, with no payload data. + // + + mip_packet_add_field(&packet, MIP_CMD_DESC_BASE_PING, NULL, 0); + + // + // FIELD #2 + // + // A Base Comm Speed command using a fixed/pre-serialized payload. + // + // If you already have the payload data in a buffer, this is the + // most efficient way to add a field. + // + + const uint8_t payload2[] = { 0x01, 0x01, 0x00, 0x01, 0xC2, 0x00 }; + mip_packet_add_field(&packet, MIP_CMD_DESC_BASE_COMM_SPEED, payload2, sizeof(payload2)); + + print_packet(&packet, "Unfinished packet with 2 fields"); + + // + // FIELD #3 + // + // A Base Comm Speed command, using the C struct definition. + // + // Generally, the C struct definitions are the easiest and most readable way to + // create a field in a packet from its parameter values. It's also the most efficient + // method offered by the MIP SDK because the data is not copied through any intermediate + // buffers; it's serialized directly from the command struct to the packet. + // + + mip_base_comm_speed_command cmd3; + cmd3.function = MIP_FUNCTION_WRITE; + cmd3.port = 0x01; + cmd3.baud = 115200; + + // Create a new field with a serializer. + mip_serializer_init_new_field(&serializer, &packet, MIP_CMD_DESC_BASE_COMM_SPEED); + // Serialize the command directly into the field's payload. + insert_mip_base_comm_speed_command(&serializer, &cmd3); + // Update the field length byte. + mip_serializer_finish_new_field(&serializer, &packet); + + print_packet(&packet, "Unfinished packet with 3 fields"); + + // + // FIELD #4 + // + // A Base Comm Speed command, by manually serializing the parameters. + // + // This is exactly the same as field #3, but without the mip_serializer_*_field helper + // functions. This is intended to show what happens "behind the scenes". + // + + // This part is analogous to mip_serializer_init_new_field from field #3. + // -------- + uint8_t* payload4 = NULL; + // Create a field and obtain the payload pointer. + // The return value is the number of bytes remaining after allocating this field. + // Note that in this particular case, we know the field length will be 6 bytes. + // This allows us to save going back and updating the field length after serialization (see field #6). + int leftover3 = mip_packet_create_field(&packet, MIP_CMD_DESC_BASE_COMM_SPEED, 6, &payload4); + + // If less than 0 bytes are left over, then allocation failed by this many bytes. + assert(leftover3 >= 0 && payload4 != NULL); + + // Show what the packet looks like after allocating a field. + // The header will exist but the payload will not be valid yet. + print_packet(&packet, "Field #4 allocated, not written"); + + // Initialize the serializer for the payload. + microstrain_serializer_init_insertion(&serializer, payload4, 6); + // -------- + + // This part is analogous to insert_mip_base_comm_speed_command + // -------- + // Write parameters to the payload. + microstrain_insert_u8(&serializer, 0x01); + microstrain_insert_u8(&serializer, 0x01); + microstrain_insert_u32(&serializer, 115200); + // Make sure serialization was successful (not out of space). + assert(microstrain_serializer_is_ok(&serializer)); + // -------- + + // The equivalent to mip_serializer_finish_new_field isn't required in this case + // because we specified an exact payload length to mip_packet_create_field. + + + // + // Complete packet #1 + // + + // Update the checksum. + mip_packet_finalize(&packet); + + // "Send" the packet + print_packet(&packet, "Finished packet with 4 fields"); + + // + // Packet #2 + // + + // Start over with a new descriptor set. + mip_packet_reset(&packet, MIP_3DM_CMD_DESC_SET); + + // Payload length has been zeroed out. Checksum is garbage. + print_packet(&packet, "Empty packet after reset"); + + // + // FIELD #5 (second packet) + // + // A 3DM Message Format command field using the C struct definition. + // + // Similar to #3 except that we have a variable-length payload. + // Again, this is the recommended method for field creation. + // + + mip_3dm_message_format_command cmd5; + cmd5.function = MIP_FUNCTION_WRITE; + cmd5.desc_set = MIP_SENSOR_DATA_DESC_SET; + cmd5.num_descriptors = 3; // This determines how many descriptors follow. + cmd5.descriptors[0].descriptor = MIP_DATA_DESC_SHARED_REFERENCE_TIME; + cmd5.descriptors[1].descriptor = MIP_DATA_DESC_SENSOR_ACCEL_SCALED; + cmd5.descriptors[2].descriptor = MIP_DATA_DESC_SENSOR_GYRO_SCALED; + cmd5.descriptors[0].decimation = 10; + cmd5.descriptors[1].decimation = 10; + cmd5.descriptors[2].decimation = 10; + + // Create the field and init the serializer in one step. + mip_serializer_init_new_field(&serializer, &packet, MIP_CMD_DESC_3DM_MESSAGE_FORMAT); + // Serialize the command. + insert_mip_3dm_message_format_command(&serializer, &cmd5); + // Update the field length. + mip_serializer_finish_new_field(&serializer, &packet); + + mip_packet_finalize(&packet); + print_packet(&packet, "3DM Message Format command"); + mip_packet_reset(&packet, MIP_3DM_CMD_DESC_SET); + + // + // Packet #3 + // + // FIELD #6 (third packet) + // + + // A 3DM Message Format command field, by manually serializing parameters + // + // Similar to #4 except that with a variable-length payload. + // Similar to #5, but with lower level function calls and slightly different command. + // + + // This part is analogous to mip_serializer_init_new_field from field #3. + // It's almost the same as in field #4, except we use a zero-length field. + // -------- + // Get a pointer to the payload buffer and the maximum number of bytes that can fit. + // + // Start by creating a zero-payload-length field and determining the remaining space. + uint8_t* payload5 = NULL; + int available5 = mip_packet_create_field(&packet, MIP_CMD_DESC_3DM_POLL_DATA, 0, &payload5); + // If less than 0 bytes are available, then there wasn't even space for the field header. + assert(available5 > 0 && payload5 != NULL); + // Initialize the serializer, giving it all available space. + microstrain_serializer_init_insertion(&serializer, payload5, available5); + // -------- + + // This part is analogous to insert_mip_3dm_poll_command + // -------- + // Build a 3DM Poll Data command: + // 1. Suppress_ack + microstrain_insert_bool(&serializer, false); + // 2. Descriptor set + microstrain_insert_u8(&serializer, MIP_SENSOR_DATA_DESC_SET); + // 3. Number of data quantities. + unsigned int num_data = 3; // Configure two descriptors + microstrain_insert_u8(&serializer, num_data); + // 4. Array of uint8_t descriptors. + // Descriptor 1 - Reference timestamp + microstrain_insert_u8(&serializer, MIP_DATA_DESC_SHARED_REFERENCE_TIME); + // Descriptor 2 - Scaled Accel + microstrain_insert_u8(&serializer, MIP_DATA_DESC_SENSOR_ACCEL_SCALED); + // Descriptor 3 - Scaled Gyro + microstrain_insert_u8(&serializer, MIP_DATA_DESC_SENSOR_GYRO_SCALED); + // -------- + + // This part is analogous to mip_serializer_finish_new_field + // -------- + // Check that everything fit in the field payload. + if(microstrain_serializer_is_ok(&serializer)) + { + // Now we know how many bytes were written, so update the field length in the packet. + mip_packet_update_last_field_length(&packet, payload5, microstrain_serializer_length(&serializer)); + } + else // Not enough space + { + assert(false); // This shouldn't happen in this example (note, there's no assertion in mip_serializer_finish_new_field). + // Cancel the field to ensure the packet is still valid. + mip_packet_cancel_last_field(&packet, payload5); + } + // -------- + + // + // Complete packet #3 + // + + mip_packet_finalize(&packet); + print_packet(&packet, "3DM Poll Data command"); +} + +// This function demonstrates how to construct a packet view from a buffer with existing data. +// For simplicity, the packet is hardcoded. +void create_packet_from_buffer() +{ + puts("\nCreate packet from buffer"); + + const uint8_t buffer[] = { + 0x75, 0x65, 0x80, 0x4c, 0x0a, 0xd5, 0x00, 0x00, 0x00, 0x05, 0x5e, 0xe6, 0x7c, 0xc0, 0x0a, 0xd6, + 0x00, 0x00, 0x00, 0x01, 0x4e, 0x43, 0x4a, 0x00, 0x0e, 0x04, 0x3d, 0x9e, 0xe8, 0x8d, 0x38, 0x7f, + 0xdb, 0x00, 0xbf, 0x7a, 0xaf, 0x03, 0x0e, 0x05, 0xbb, 0x0c, 0x1e, 0x30, 0xbb, 0x57, 0x2e, 0x68, + 0xbb, 0xaa, 0x24, 0xae, 0x0e, 0x07, 0xbc, 0x8a, 0xac, 0x80, 0xbc, 0x72, 0xc5, 0x0e, 0xbc, 0xc4, + 0xe2, 0xc1, 0x0e, 0x08, 0x3e, 0xee, 0x3d, 0x9f, 0xbd, 0x66, 0xda, 0xdd, 0xc0, 0xaf, 0xde, 0xf5, + 0x91, 0x96 + }; + + // Create a view of the packet in the buffer. + // Note: The buffer must not be modified, so do not call functions that manipulate the packet. + // E.g. finalize(), addField, createField, reset, etc. + mip_packet_view packet1; + mip_packet_from_buffer(&packet1, buffer, sizeof(buffer)); + + // Ensure the packet is valid before inspecting it. + // This is the combination of checking: + // 1. mip_packet_is_sane (buffer size and payload length checks) + // 2. The packet has a non-zero descriptor set. + // 3. The checksum is valid. + if(!mip_packet_is_valid(&packet1)) + { + assert(false); // The packet should be valid in this example. + return; + } + + // Print the packet. + print_packet(&packet1, "Packet from buffer"); + + // Example of what an application might do to parse specific data. + // This example is for demonstration of the techniques used with the MIP SDK; + // consider using the "dispatch" system (see the documentation) instead. + + // Is this a sensor data packet? + if(mip_packet_descriptor_set(&packet1) == MIP_SENSOR_DATA_DESC_SET) + { + puts("Sensor Data packet:"); + + // Iterate all fields in the packet. + mip_field_view field; + mip_field_init_empty(&field); + while(mip_field_next_in_packet(&field, &packet1)) + { + // Create a deserializer for the field. + mip_serializer serializer; + microstrain_serializer_init_extraction(&serializer, mip_field_payload(&field), mip_field_payload_length(&field)); + + // Check what data the field contains. + switch(mip_field_field_descriptor(&field)) + { + case MIP_DATA_DESC_SHARED_REFERENCE_TIME: + { + uint64_t nanoseconds; + microstrain_extract_u64(&serializer, &nanoseconds); + + if(microstrain_serializer_is_complete(&serializer)) + printf(" Ref Time = %lu\n", nanoseconds); + + break; + } + case MIP_DATA_DESC_SENSOR_ACCEL_SCALED: + { + // Extract the 3-vector. + float x,y,z; + microstrain_extract_float(&serializer, &x); + microstrain_extract_float(&serializer, &y); + microstrain_extract_float(&serializer, &z); + + // Check if the entire field was deserialized (validity check). + if(microstrain_serializer_is_complete(&serializer)) + printf(" Scaled Accel = (%f, %f, %f)\n", x, y, z); + + break; + } + case MIP_DATA_DESC_SENSOR_GYRO_SCALED: + { + // Same as scaled accel except using the C data structure. + // This is the recommended method. + mip_sensor_scaled_gyro_data data; + extract_mip_sensor_scaled_gyro_data(&serializer, &data); + + if(microstrain_serializer_is_complete(&serializer)) + printf(" Scaled Gyro = (%f, %f, %f)\n", data.scaled_gyro[0], data.scaled_gyro[1], data.scaled_gyro[2]); + + break; + } + } + } + puts(""); + } +} + +int main() +{ + create_packet_from_scratch(); + create_packet_from_buffer(); + + return 0; +} diff --git a/examples/mip_packet_example.cpp b/examples/mip_packet_example.cpp new file mode 100644 index 000000000..7f8db90ee --- /dev/null +++ b/examples/mip_packet_example.cpp @@ -0,0 +1,359 @@ + +#include + +#include +#include +#include +#include + +#include + +// This function demonstrates how to inspect and iterate fields in +// a MIP packet. These functions do not modify the packet and can +// be used on any packet as long as it has valid structure. +void print_packet(const mip::PacketView& packet, const char* name) +{ + // Ensure the packet structure is correct, otherwise a crash may result. + // This checks the following: + // 1. The packet buffer is not NULL. + // 2. The buffer size is at least MIP_PACKET_LENGTH_MIN. + // 3. The payload length does not exceed the buffer size. + // There's generally no need to check this if you're getting packets + // directly from mip_packet_create (with sufficient buffer space) or + // from the mip parser. If you're reading packets from a file, etc., + // without parsing, use this as a cheap validation step. + // In this example, it should always pass. + assert(packet.isSane()); + + // Roughly equivalent to packet.checksumValue() == packet.computeChecksum() + const char* checksum_str = packet.isValid() ? "valid" : "invalid"; + + // Print descriptor set, total length, and payload length. + std::printf( + "%s: desc_set=0x%02X tot_len=%u pay_len=%u chk=%s [", + name, packet.descriptorSet(), packet.totalLength(), packet.payloadLength(), checksum_str + ); + + // Print each byte in the packet, including header and checksum. + for(size_t i=0; i(0x01); + serialize4.insert(0x01); + serialize4.insert(115200); +#endif + + // + // Complete packet #1 + // + + // Update the checksum. + packet.finalize(); + + // "Send" the packet + print_packet(packet, "Finished packet with 4 fields"); + + // + // Packet #2 + // + + // Start over with a new descriptor set. + packet.reset(mip::commands_3dm::DESCRIPTOR_SET); + + // Payload length has been zeroed out. Checksum is garbage. + print_packet(packet, "Empty packet after reset"); + + // + // FIELD #5 (second packet) + // + // A 3DM Message Format command field using the C struct definition. + // + // Similar to #3 except that we have a variable-length payload. + // Again, this is the recommended method for field creation. + // + + mip::commands_3dm::MessageFormat cmd5; + cmd5.function = mip::FunctionSelector::WRITE; + cmd5.desc_set = mip::data_sensor::DESCRIPTOR_SET; + cmd5.num_descriptors = 3; // This determines how many descriptors follow. + cmd5.descriptors[0].descriptor = mip::data_shared::ReferenceTimestamp::FIELD_DESCRIPTOR; + cmd5.descriptors[1].descriptor = mip::data_sensor::ScaledAccel::FIELD_DESCRIPTOR; + cmd5.descriptors[2].descriptor = mip::data_sensor::DATA_GYRO_SCALED; + cmd5.descriptors[0].decimation = 10; + cmd5.descriptors[1].decimation = 10; + cmd5.descriptors[2].decimation = 10; + + packet.addField(cmd5); + + packet.finalize(); + print_packet(packet, "3DM Message Format command"); + mip_packet_reset(&packet, mip::commands_3dm::DESCRIPTOR_SET); + + // + // Packet #3 + // + + // FIELD #6 (third packet) + // + // A 3DM Message Format command field, by manually serializing parameters + // + // Similar to #4 except that with a variable-length payload. + // Similar to #5, but with lower level function calls and slightly different command. + // + + // Create a field of unknown length. + // This is equivalent to creating a field with length 0 and a serializer covering + // all of the remaining space. After the field is serialized, the field length is + // updated based on how many bytes were used. + mip::PacketView::AllocatedField field6 = packet.createField(mip::commands_3dm::PollData::FIELD_DESCRIPTOR); + + field6.insert( + false, // suppress_ack + uint8_t(mip::data_sensor::DESCRIPTOR_SET), + uint8_t(3) + ); + + // Arrays can also be directly serialized if their size is known. +#if 1 + std::array descriptors6 = {{ + mip::data_shared::ReferenceTimestamp::FIELD_DESCRIPTOR, + mip::data_sensor::ScaledAccel::FIELD_DESCRIPTOR, + mip::data_sensor::DATA_GYRO_SCALED, + }}; + field6.insert(descriptors6); +#else + uint8_t descriptors6[] = { + mip::data_shared::ReferenceTimestamp::FIELD_DESCRIPTOR, + mip::data_sensor::ScaledAccel::FIELD_DESCRIPTOR, + mip::data_sensor::DATA_GYRO_SCALED, + }; + field6.insert(descriptors6); + // Equivalent to + //field6.insert(descriptors6, 3); +#endif + + // Update the field length. + // Note that if the field would exceed the remaining space in the packet, this will + // instead remove the field entirely and return false. + bool ok6 = field6.commit(); + assert(ok6); // Shouldn't happen in this example. + + // + // Complete packet #3 + // + + mip_packet_finalize(&packet); + print_packet(&packet, "3DM Poll Data command"); +} + +void create_packet_from_buffer() +{ + puts("\nCreate packet from buffer"); + + const uint8_t buffer[] = { + 0x75, 0x65, 0x80, 0x4c, 0x0a, 0xd5, 0x00, 0x00, 0x00, 0x05, 0x5e, 0xe6, 0x7c, 0xc0, 0x0a, 0xd6, + 0x00, 0x00, 0x00, 0x01, 0x4e, 0x43, 0x4a, 0x00, 0x0e, 0x04, 0x3d, 0x9e, 0xe8, 0x8d, 0x38, 0x7f, + 0xdb, 0x00, 0xbf, 0x7a, 0xaf, 0x03, 0x0e, 0x05, 0xbb, 0x0c, 0x1e, 0x30, 0xbb, 0x57, 0x2e, 0x68, + 0xbb, 0xaa, 0x24, 0xae, 0x0e, 0x07, 0xbc, 0x8a, 0xac, 0x80, 0xbc, 0x72, 0xc5, 0x0e, 0xbc, 0xc4, + 0xe2, 0xc1, 0x0e, 0x08, 0x3e, 0xee, 0x3d, 0x9f, 0xbd, 0x66, 0xda, 0xdd, 0xc0, 0xaf, 0xde, 0xf5, + 0x91, 0x96 + }; + + // Create a view of the packet in the buffer. + // Note: The buffer must not be modified, so do not call functions that manipulate the packet. + // E.g. finalize(), addField, createField, reset, etc. + mip::PacketView packet1(buffer, sizeof(buffer)); + + // Ensure the packet is valid before inspecting it. + // This is the combination of checking: + // 1. mip_packet_is_sane (buffer size and payload length checks) + // 2. The packet has a non-zero descriptor set. + // 3. The checksum is valid. + if(!packet1.isValid()) + { + assert(false); // The packet should be valid in this example. + return; + } + + // Print the packet. + print_packet(packet1, "Packet from buffer"); + + // Create a view from a span. + microstrain::Span span(buffer, sizeof(buffer)); + mip::PacketView packet2(span); + print_packet(packet2, "Packet from span"); + + // Create a C++ PacketView from the C equivalent. + mip::C::mip_packet_view packet3c; + mip::C::mip_packet_from_buffer(&packet3c, buffer, sizeof(buffer)); + mip::PacketView packet3(packet3c); + print_packet(packet3, "Packet from C packet"); + + // Example of what an application might do to parse specific data. + // This example is for demonstration of the techniques used with the MIP SDK; + // consider using the "dispatch" system (see the documentation) instead. + + // Is this a sensor data packet? + if(packet1.descriptorSet() == mip::data_sensor::DESCRIPTOR_SET) + { + puts("Sensor Data packet:"); + + for(mip::FieldView field : packet1) + { + mip::Serializer serializer(field.payloadSpan()); + + switch(field.fieldDescriptor()) + { + case mip::data_shared::ReferenceTimestamp::FIELD_DESCRIPTOR: + { + uint64_t nanoseconds; + + if(serializer.extract(nanoseconds)) + printf(" Ref Time = %lu\n", nanoseconds); + + break; + } + case mip::data_sensor::ScaledAccel::FIELD_DESCRIPTOR: + { + // Extract the 3-vector. + float x,y,z; + + if(serializer.extract(x,y,z)) + printf(" Scaled Accel = (%f, %f, %f)\n", x, y, z); + + break; + } + case mip::data_sensor::ScaledGyro::FIELD_DESCRIPTOR: + { + mip::data_sensor::ScaledGyro data; + + if(serializer.extract(data)) + printf(" Scaled Gyro = (%f, %f, %f)\n", data.scaled_gyro[0], data.scaled_gyro[1], data.scaled_gyro[2]); + + break; + } + } + } + } +} + +int main() +{ + create_packet_from_scratch(); + create_packet_from_buffer(); +} diff --git a/src/c/mip/mip_packet.c b/src/c/mip/mip_packet.c index 2d38cc353..d5d3c9353 100644 --- a/src/c/mip/mip_packet.c +++ b/src/c/mip/mip_packet.c @@ -35,7 +35,7 @@ /// MIP_PACKET_LENGTH_MIN bytes, calling the accessor functions is undefined /// behavior. /// -void mip_packet_from_buffer(mip_packet_view* packet, uint8_t* buffer, size_t length) +void mip_packet_from_buffer(mip_packet_view* packet, const uint8_t* buffer, size_t length) { assert(buffer != NULL); @@ -43,7 +43,7 @@ void mip_packet_from_buffer(mip_packet_view* packet, uint8_t* buffer, size_t len if( length > MIP_PACKET_LENGTH_MAX ) length = MIP_PACKET_LENGTH_MAX; - packet->_buffer = buffer; + packet->_buffer = (uint8_t*)buffer; packet->_buffer_length = (uint_least16_t)length; } @@ -291,7 +291,7 @@ bool mip_packet_is_data(const mip_packet_view* packet) bool mip_packet_add_field(mip_packet_view* packet, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length) { uint8_t* payload_buffer; - int remaining = mip_packet_alloc_field(packet, field_descriptor, payload_length, &payload_buffer); + int remaining = mip_packet_create_field(packet, field_descriptor, payload_length, &payload_buffer); if( remaining < 0 ) return false; @@ -330,7 +330,7 @@ bool mip_packet_add_field(mip_packet_view* packet, uint8_t field_descriptor, con /// is negative, the field could not be allocated and the payload must /// not be written. /// -int mip_packet_alloc_field(mip_packet_view* packet, uint8_t field_descriptor, uint8_t payload_length, uint8_t** const payload_ptr_out) +int mip_packet_create_field(mip_packet_view* packet, uint8_t field_descriptor, uint8_t payload_length, uint8_t** payload_ptr_out) { assert(payload_ptr_out != NULL); assert( payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX ); @@ -359,7 +359,7 @@ int mip_packet_alloc_field(mip_packet_view* packet, uint8_t field_descriptor, ui //////////////////////////////////////////////////////////////////////////////// ///@brief Changes the size of the last field in the packet. /// -/// Use this in conjunction with mip_packet_alloc_field() when the size of the +/// Use this in conjunction with mip_packet_create_field() when the size of the /// field is not known in advance. Pass a payload size of 0 to alloc_field and /// check that the returned available space is sufficient, then write the /// payload and call this function with the actual space used. @@ -377,7 +377,7 @@ int mip_packet_alloc_field(mip_packet_view* packet, uint8_t field_descriptor, ui ///@returns The space remaining in the packet after changing the field size. /// This will be negative if the new length did not fit. /// -int mip_packet_realloc_last_field(mip_packet_view* packet, uint8_t* payload_ptr, uint8_t new_payload_length) +int mip_packet_update_last_field_length(mip_packet_view* packet, uint8_t* payload_ptr, uint8_t new_payload_length) { assert(payload_ptr != NULL); assert( new_payload_length <= MIP_FIELD_PAYLOAD_LENGTH_MAX ); @@ -402,7 +402,7 @@ int mip_packet_realloc_last_field(mip_packet_view* packet, uint8_t* payload_ptr, //////////////////////////////////////////////////////////////////////////////// ///@brief Removes the last field from the packet after having allocated it. /// -/// Use only after allocating a field with mip_packet_alloc_field to cancel it. +/// Use only after allocating a field with mip_packet_create_field to cancel it. /// E.g. if it turns out that there isn't enough buffer space to write the /// payload. /// diff --git a/src/c/mip/mip_packet.h b/src/c/mip/mip_packet.h index e2ad918f7..46accb802 100644 --- a/src/c/mip/mip_packet.h +++ b/src/c/mip/mip_packet.h @@ -67,8 +67,8 @@ typedef struct mip_packet_view void mip_packet_create(mip_packet_view* packet, uint8_t* buffer, size_t buffer_size, uint8_t descriptor_set); bool mip_packet_add_field(mip_packet_view* packet, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length); -int mip_packet_alloc_field(mip_packet_view* packet, uint8_t field_descriptor, uint8_t payload_length, uint8_t** payload_ptr_out); -int mip_packet_realloc_last_field(mip_packet_view* packet, uint8_t* payload_ptr, uint8_t new_payload_length); +int mip_packet_create_field(mip_packet_view* packet, uint8_t field_descriptor, uint8_t payload_length, uint8_t** payload_ptr_out); +int mip_packet_update_last_field_length(mip_packet_view* packet, uint8_t* payload_ptr, uint8_t new_payload_length); int mip_packet_cancel_last_field(mip_packet_view* packet, uint8_t* payload_ptr); void mip_packet_finalize(mip_packet_view* packet); @@ -89,7 +89,7 @@ void mip_packet_reset(mip_packet_view* packet, uint8_t descriptor_set); /// ///@{ -void mip_packet_from_buffer(mip_packet_view* packet, uint8_t* buffer, size_t length); +void mip_packet_from_buffer(mip_packet_view* packet, const uint8_t* buffer, size_t length); uint8_t mip_packet_descriptor_set(const mip_packet_view* packet); uint_least16_t mip_packet_total_length(const mip_packet_view* packet); @@ -111,15 +111,7 @@ int mip_packet_remaining_space(const mip_packet_view* packet); bool mip_packet_is_data(const mip_packet_view* packet); ///@} -//////////////////////////////////////////////////////////////////////////////// -///@defgroup Serialization Serializers - Functions for serializing a MIP packet. -/// -///@{ -//void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor); -//void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet_view* packet); - -///@} ///@} ///@} //////////////////////////////////////////////////////////////////////////////// diff --git a/src/c/mip/mip_serialization.c b/src/c/mip/mip_serialization.c index 1a55932f4..58a855c5f 100644 --- a/src/c/mip/mip_serialization.c +++ b/src/c/mip/mip_serialization.c @@ -9,7 +9,7 @@ ///@brief Initialize a serialization struct for creation of a new field at the /// end of the packet. /// -///@note Call microstrain_serializer_finish_new_field after the data has been serialized. +///@note Call mip_serializer_finish_new_field after the data has been serialized. /// ///@note Only one new field per packet can be in progress at a time. /// @@ -19,7 +19,7 @@ ///@param field_descriptor /// Field descriptor of the new field. /// -void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor) +void mip_serializer_init_new_field(mip_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor) { assert(packet); @@ -27,29 +27,29 @@ void microstrain_serializer_init_new_field(microstrain_serializer* serializer, m serializer->_buffer_size = 0; serializer->_offset = 0; - const int length = mip_packet_alloc_field(packet, field_descriptor, 0, &serializer->_buffer); + const int length = mip_packet_create_field(packet, field_descriptor, 0, &serializer->_buffer); if( length >= 0 ) serializer->_buffer_size = length; } //////////////////////////////////////////////////////////////////////////////// -///@brief Call this after a new field allocated by microstrain_serializer_init_new_field +///@brief Call this after a new field allocated by mip_serializer_init_new_field /// has been written. /// /// This will either finish the field, or abort it if the serializer failed. /// -///@param serializer Must be created from microstrain_serializer_init_new_field. +///@param serializer Must be created from mip_serializer_init_new_field. ///@param packet Must be the original packet. /// -void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet_view* packet) +void mip_serializer_finish_new_field(const mip_serializer* serializer, mip_packet_view* packet) { assert(packet); if(microstrain_serializer_is_ok(serializer) ) { assert(serializer->_offset <= MIP_FIELD_LENGTH_MAX); // Payload too long! - mip_packet_realloc_last_field(packet, serializer->_buffer, (uint8_t) serializer->_offset); + mip_packet_update_last_field_length(packet, serializer->_buffer, (uint8_t) serializer->_offset); } else if( serializer->_buffer ) mip_packet_cancel_last_field(packet, serializer->_buffer); @@ -61,7 +61,7 @@ void microstrain_serializer_finish_new_field(const microstrain_serializer* seria ///@param serializer ///@param field /// -void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field_view* field) +void microstrain_serializer_init_from_field(mip_serializer* serializer, const mip_field_view* field) { microstrain_serializer_init_extraction(serializer, mip_field_payload(field), mip_field_payload_length(field)); } diff --git a/src/c/mip/mip_serialization.h b/src/c/mip/mip_serialization.h index ed314d21d..a9162a46c 100644 --- a/src/c/mip/mip_serialization.h +++ b/src/c/mip/mip_serialization.h @@ -11,9 +11,11 @@ namespace C { extern "C" { #endif -void microstrain_serializer_init_new_field(microstrain_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor); -void microstrain_serializer_finish_new_field(const microstrain_serializer* serializer, mip_packet_view* packet); -void microstrain_serializer_init_from_field(microstrain_serializer* serializer, const mip_field_view* field); +typedef microstrain_serializer mip_serializer; + +void mip_serializer_init_new_field(mip_serializer* serializer, mip_packet_view* packet, uint8_t field_descriptor); +void mip_serializer_finish_new_field(const mip_serializer* serializer, mip_packet_view* packet); +void microstrain_serializer_init_from_field(mip_serializer* serializer, const mip_field_view* field); #ifdef __cplusplus } // extern "C" diff --git a/src/cpp/microstrain/common/serialization/serializer.hpp b/src/cpp/microstrain/common/serialization/serializer.hpp index 4dbcb7cd9..d9f575bd6 100644 --- a/src/cpp/microstrain/common/serialization/serializer.hpp +++ b/src/cpp/microstrain/common/serialization/serializer.hpp @@ -952,7 +952,9 @@ bool Serializer::extract(Ts&... values) // https://stackoverflow.com/questions/13407205/calling-nonmember-instead-of-member-function using microstrain::extract; - return extract(*this, values...); + extract(*this, values...); + + return isOk(); } //////////////////////////////////////////////////////////////////////////////// diff --git a/src/cpp/mip/mip_packet.hpp b/src/cpp/mip/mip_packet.hpp index 3f8297fdf..c5301a016 100644 --- a/src/cpp/mip/mip_packet.hpp +++ b/src/cpp/mip/mip_packet.hpp @@ -45,12 +45,21 @@ class PacketView : public C::mip_packet_view ///@copydoc mip::C::mip_packet_create PacketView(uint8_t* buffer, size_t bufferSize, uint8_t descriptorSet) { C::mip_packet_create(this, buffer, bufferSize, descriptorSet); } ///@copydoc mip_packet_from_buffer - PacketView(uint8_t* buffer, size_t length) { C::mip_packet_from_buffer(this, buffer, length); } + PacketView(const uint8_t* buffer, size_t length) { C::mip_packet_from_buffer(this, const_cast(buffer), length); } /// Constructs a C++ %PacketRef class from the base C object. PacketView(const C::mip_packet_view* other) { std::memcpy(static_cast(this), other, sizeof(*this)); } /// Constructs a C++ %PacketRef class from the base C object. PacketView(const C::mip_packet_view& other) { std::memcpy(static_cast(this), &other, sizeof(*this)); } + ///@brief Create a new MIP packet in an existing buffer. + ///@param buffer Place to store the MIP packet bytes. + ///@param descriptorSet Initializes the packet to this descriptor set. + PacketView(microstrain::Span buffer, uint8_t descriptorSet) { C::mip_packet_create(this, buffer.data(), buffer.size(), descriptorSet); } + + ///@brief Create a reference to an existing MIP packet. + ///@param buffer Buffer containing an existing MIP packet. + ///@caution Do not call functions which modify the packet (addField, finalize, reset, etc) unless you know the buffer is not const. + PacketView(microstrain::Span buffer) { C::mip_packet_from_buffer(this, const_cast(buffer.data()), buffer.size()); } // // C function wrappers @@ -76,7 +85,7 @@ class PacketView : public C::mip_packet_view int remainingSpace() const { return C::mip_packet_remaining_space(this); } ///<@copydoc mip::C::mip_packet_remaining_space bool addField(uint8_t fieldDescriptor, const uint8_t* payload, uint8_t payloadLength) { return C::mip_packet_add_field(this, fieldDescriptor, payload, payloadLength); } ///<@copydoc mip::C::mip_packet_add_field - Serializer createField(uint8_t fieldDescriptor, uint8_t length) { uint8_t * ptr; if(C::mip_packet_alloc_field(this, fieldDescriptor, length, &ptr) < 0) length =0; return Serializer{ptr, length}; } + Serializer createField(uint8_t fieldDescriptor, uint8_t length) { uint8_t * ptr; if(C::mip_packet_create_field(this, fieldDescriptor, length, &ptr) < 0) length =0; return Serializer{ptr, length}; } //std::tuple createField(uint8_t fieldDescriptor) { uint8_t* ptr; int max_size = C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr); return max_size >= 0 ? std::make_tuple(ptr, max_size) : std::make_tuple(nullptr, 0); } ///<@copydoc mip::C::mip_packet_alloc_field //int finishLastField(uint8_t* payloadPtr, uint8_t newPayloadLength) { return C::mip_packet_realloc_last_field(this, payloadPtr, newPayloadLength); } ///<@copydoc mip::C::mip_packet_realloc_last_field //int cancelLastField(uint8_t* payloadPtr) { return C::mip_packet_cancel_last_field(this, payloadPtr); } ///<@copydoc mip::C::mip_packet_cancel_last_field @@ -95,7 +104,7 @@ class PacketView : public C::mip_packet_view bool ok = isOk(); if(ok) - ok &= C::mip_packet_realloc_last_field(&m_packet, basePointer(), (uint8_t)usedLength()) >= 0; + ok &= C::mip_packet_update_last_field_length(&m_packet, basePointer(), (uint8_t) usedLength()) >= 0; if(!ok) C::mip_packet_cancel_last_field(&m_packet, basePointer()); @@ -107,7 +116,7 @@ class PacketView : public C::mip_packet_view PacketView& m_packet; }; - AllocatedField createField(uint8_t fieldDescriptor) { uint8_t* ptr; size_t max_size = std::max(0, C::mip_packet_alloc_field(this, fieldDescriptor, 0, &ptr)); return {*this, ptr, max_size}; } + AllocatedField createField(uint8_t fieldDescriptor) { uint8_t* ptr; size_t max_size = std::max(0, C::mip_packet_create_field(this, fieldDescriptor, 0, &ptr)); return {*this, ptr, max_size}; } void finalize() { C::mip_packet_finalize(this); } ///<@copydoc mip::C::mip_packet_finalize @@ -273,7 +282,13 @@ class SizedPacketBuf : public PacketView ///@param fieldDescriptor If specified (not INVALID_FIELD_DESCRIPTOR), overrides the field descriptor. /// template - SizedPacketBuf(const FieldType& field, uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR) : PacketView(mData, sizeof(mData)) { createFromField(mData, sizeof(mData), field, fieldDescriptor); } + SizedPacketBuf( + const typename std::enable_if::value>::type& field, + uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR + ) : PacketView(mData, sizeof(mData)) + { + createFromField(mData, sizeof(mData), field, fieldDescriptor); + } ///@brief Explicitly obtains a reference to the packet data. diff --git a/test/mip/test_mip_fields.c b/test/mip/test_mip_fields.c index ee0a5f6c1..9fa409197 100644 --- a/test/mip/test_mip_fields.c +++ b/test/mip/test_mip_fields.c @@ -20,7 +20,7 @@ bool add_random_field() const uint8_t field_desc = (rand() % 255) + 1; uint8_t* payload; - if( !mip_packet_alloc_field(&packet, field_desc, length, &payload) ) + if( !mip_packet_create_field(&packet, field_desc, length, &payload) ) return false; for(unsigned int i=0; i Date: Wed, 2 Oct 2024 14:20:31 -0400 Subject: [PATCH 135/147] Update documentation: - Colorize C/C++ links red/green. - Update doxygen group names. --- CMakeLists.txt | 2 + docs/main.md | 25 ++- docs/mip_cmd_result.md | 2 +- docs/mip_packets.md | 224 ++++++++++++++++++++ docs/miscellaneous.md | 10 +- docs/serialization.md | 19 +- docs/style.css | 29 +++ examples/mip_packet_example.cpp | 11 +- src/c/mip/definitions/commands_3dm.h | 96 ++++----- src/c/mip/definitions/commands_aiding.h | 26 +-- src/c/mip/definitions/commands_base.h | 26 +-- src/c/mip/definitions/commands_filter.h | 110 +++++----- src/c/mip/definitions/commands_gnss.h | 10 +- src/c/mip/definitions/commands_rtk.h | 28 +-- src/c/mip/definitions/commands_system.h | 6 +- src/c/mip/definitions/common.h | 13 ++ src/c/mip/definitions/data_filter.h | 118 +++++------ src/c/mip/definitions/data_gnss.h | 58 ++--- src/c/mip/definitions/data_sensor.h | 50 ++--- src/c/mip/definitions/data_shared.h | 22 +- src/c/mip/definitions/data_system.h | 12 +- src/c/mip/mip_all.h | 12 ++ src/c/mip/mip_cmdqueue.h | 6 +- src/c/mip/mip_dispatch.h | 2 +- src/c/mip/mip_field.c | 2 +- src/c/mip/mip_field.h | 2 +- src/c/mip/mip_interface.h | 4 +- src/c/mip/mip_packet.h | 13 +- src/c/mip/mip_parser.h | 2 +- src/c/mip/mip_result.h | 2 + src/cpp/microstrain/common/index.hpp | 6 +- src/cpp/microstrain/common/span.hpp | 11 + src/cpp/microstrain/microstrain_all.hpp | 14 ++ src/cpp/mip/definitions/commands_3dm.hpp | 96 ++++----- src/cpp/mip/definitions/commands_aiding.hpp | 26 +-- src/cpp/mip/definitions/commands_base.hpp | 26 +-- src/cpp/mip/definitions/commands_filter.hpp | 110 +++++----- src/cpp/mip/definitions/commands_gnss.hpp | 10 +- src/cpp/mip/definitions/commands_rtk.hpp | 28 +-- src/cpp/mip/definitions/commands_system.hpp | 6 +- src/cpp/mip/definitions/common.hpp | 13 ++ src/cpp/mip/definitions/data_filter.hpp | 118 +++++------ src/cpp/mip/definitions/data_gnss.hpp | 58 ++--- src/cpp/mip/definitions/data_sensor.hpp | 50 ++--- src/cpp/mip/definitions/data_shared.hpp | 22 +- src/cpp/mip/definitions/data_system.hpp | 12 +- src/cpp/mip/mip.hpp | 8 +- src/cpp/mip/mip_packet.hpp | 2 + 48 files changed, 947 insertions(+), 611 deletions(-) create mode 100644 docs/mip_packets.md create mode 100644 docs/style.css diff --git a/CMakeLists.txt b/CMakeLists.txt index ccf4d73b2..e0b793d07 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -193,6 +193,8 @@ if(MICROSTRAIN_BUILD_DOCUMENTATION) set(DOXYGEN_QUIET YES) endif() + set(DOXYGEN_HTML_EXTRA_STYLESHEET "${CMAKE_CURRENT_LIST_DIR}/docs/style.css") + doxygen_add_docs(docs "${MICROSTRAIN_SRC_DIR}" "${CMAKE_CURRENT_LIST_DIR}/docs" COMMENT "Generating documentation." diff --git a/docs/main.md b/docs/main.md index 49fe279a7..e94ace5d8 100644 --- a/docs/main.md +++ b/docs/main.md @@ -4,7 +4,6 @@ MIP SDK {#mainpage} Welcome to the official MIP Software Development Kit. This software package provides everything you need to communicate with any MIP-compatible MicroStrain inertial sensor. -See @ref mip_interface for details on how to get started. ### Main Features @@ -12,17 +11,21 @@ See @ref mip_interface for details on how to get started. * Send commands using a single function * Packet parsing and field iteration * Data field deserialization -* Simple interface requires only two functions to be defined * Can be used to parse offline binary files * Dual C and C++ API for maximum usability, safety, flexibility, and convenience. -* Suitable for bare-metal microcontrollers (Minimal code size and memory footprint, No dynamic memory allocation, No dependence on any RTOS or threading) +* Suitable for bare-metal microcontrollers: + * Minimal code size and memory footprint + * No dynamic memory allocation + * No dependence on any RTOS or threads Quick Reference [C++] {#quickref_cpp} --------------------- All C++ functions and classes reside within the mip namespace. The C functions can be accessed via the mip::C namespace. +Within this documentation, links to C++ entities are shown in green. +* [C++ API Overview](@ref mip_cpp) * mip::Interface Top-level MIP interface class. * mip::PacketView An interface to a MIP packet for either transmission or reception. * mip::PacketBuf Similar to PacketRef but includes the data buffer. @@ -36,11 +39,11 @@ Quick Reference [C] {#quickref_c} C does not support the equivalent of C++ namespaces, so all definitions are global. Most names start with `mip_` to avoid conflicts. In these documentation pages, objects are referred to by their fully- -qualified C++ names for clarity. - -* [mip_interface (C)](mip_interface_c) -* [mip_packet (C)](mip_packet_c) -* [mip_field (C)](mip_field_c) -* [mip_parser (C)](mip_parser_c) -* [mip_cmd_result (C)](mip::C::mip_cmd_result) - +qualified C++ names for clarity. Within this documentation, links to C entities are shown in red. + +* [C API Overview](@ref mip_c) +* [mip_interface ](@ref mip_interface_c) +* [mip_packet ](@ref mip::C::mip_packet_view) +* [mip_field ](@ref mip::C::mip_field_view) +* [mip_parser ](@ref mip::C::mip_parser) +* [mip_cmd_result](@ref mip::C::mip_cmd_result) diff --git a/docs/mip_cmd_result.md b/docs/mip_cmd_result.md index 99149f5b5..2fdc46077 100644 --- a/docs/mip_cmd_result.md +++ b/docs/mip_cmd_result.md @@ -5,7 +5,7 @@ All of the command functions in the MIP SDK return a Command Result. Command res type in both C and C++: * [mip_command_result (C)](@ref mip::C::mip_cmd_result) -* [CmdResult (C++)](@ref mip::CmdResult) +* [mip::CmdResult (C++)](@ref mip::CmdResult) Command results are divided into two categories, reply codes and status codes. Reply codes are returned by the device directly: diff --git a/docs/mip_packets.md b/docs/mip_packets.md new file mode 100644 index 000000000..deee83d2c --- /dev/null +++ b/docs/mip_packets.md @@ -0,0 +1,224 @@ +MIP Packet Cheatsheet {#mip_packet_processing_cpp} +===================== + +New Packet Creation +------------------- + +mip::PacketView can construct a new MIP packet using any of the +constructor overloads taking a descriptor set parameter. + +### Create a new packet using an existing buffer for storage + + uint8_t buffer[mip::PACKET_LENGTH_MAX]; + + mip::PacketView packet(buffer, sizeof(buffer), descriptor_set); + +Using a Span: + + microstrain::Span buffer_span(buffer, sizeof(buffer)); + mip::PacketView packet(buffer_span, descriptor_set); + +### Create a new packet with a built-in buffer + + mip::PacketBuf packet( descriptor_set ); + +If you know the max size of the packet is less than PACKET_LENGTH_MAX, +you may use `SizedPacketBuf` instead: + + mip::SizedPacketBuf packet(descriptor_set); + +A PacketBuf inherits all of the methods from PacketRef and may be used +interchangeably. + +### Clear/restart a packet + +This effectively resets the packet as if the constructor was called again with +the same parameters (buffer, size, and descriptor set). + + packet.reset(); + +The descriptor set may be changed if desired: + + packet.reset( descriptor_set ); + +### Create a packet from a field using a C++ struct + + void send_command(mip::commands_base::CommSpeed& cmd) + { + mip::PacketBuf packet( cmd ); + + // send packet + } + +The packet is complete and ready to go after construction; the checksum has been computed in this case. + +Similar to the above example, multiple fields may be appended. +In this case, two message format commands are added to one packet. + + mip::PacketBuf packet(mip::commands_3dm::DESCRIPTOR_SET); + + mip::commands_3dm::MessageFormat sensor_format; + mip::commands_3dm::MessageFormat filter_format; + // initialize the commands here + + packet.addField(sensor_format); + packet.addField(filter_format); + + packet.finalize(); + + +Existing Packet Processing +-------------------------- + +### Create a PacketView over an existing packet buffer + + void handle_packet(const uint8_t* buffer, size_t length) + { + mip::PacketView packet(existing_buffer, sizeof(existing_buffer)); + } + +Using a span + + void handle_packet(microstrain::Span buffer) + { + mip::PacketView packet(buffer); + } + +### Validation + +A PacketView can only be used if the packet structure makes sense, i.e. if +PacketView::isSane() returns true. This checks the following: +1. The buffer is not NULL. +2. The size of the buffer is at least PACKET_LENGTH_MIN. +3. The payload length does not exceed the size of the buffer. + +Additional checks are performed by PacketView::isValid(): +1. The packet is sane, i.e. isSane() returns true. +2. The descriptor set is not invalid (0x00). +3. Computing the checksum matches the value in the buffer. + +You may compute the checksum manually as well: + + bool chk_valid = packet.checksumValue() == packet.computeChecksum(); + + +### PacketView properties + +Once a PacketView is created, it may be used to inspect the packet. + + uint8_t desc_set = packet.descriptorSet(); + size_t total_length = packet.totalLength(); + uint8_t payload_length = packet.payloadLength(); + + // Pointer to raw bytes (e.g. to send to the device) + // Do not modify data unless you can be sure the buffer passed + // to the constructor was not const! I.e. only if using PacketBuf + // or the descriptor_set version of PacketView's ctor. + uint8_t* data = packet.pointer(); + + // Pointer to the start of the paylaod. + // The caution about constness above applies here as well. + uint8_t* payload = packet.payload(); + + // This is the value that was passed to the constructor. + size_t buffer_size = packet.bufferSize(); + + // How much of the buffer's capacity has been used. + // Note that the max size is also limited by PACKET_SIZE_MAX. + // If this is negative, the packet is not "sane", i.e. + // PacketView::isSane() is false and you cannot safely iterate fields + // without risking reading past the end of the buffer. + // See "validation" above. + int remaining_space = packet.remainingSpace(); + +### Reading fields in a packet + +Generally, field offsets aren't known ahead of time so they must be iterated. + +The easiest way to do this is with a range-based for loop: + + void iter_fields(const mip::PacketView& packet) + { + for(mip::FieldView field : packet) + { + process_field(field); + } + } + +This is effectively the same as + + void iter_fields(const mip::PacketView& packet) + { + for(mip::FieldIterator fi = packet.begin(); fi != packet.end(); ++fi) + { + process_field(*field); + } + } + + +#### Manually searching for a field without FieldIterator + +The next field in a packet can be obtained directly with FieldView::next or FieldView::nextAfter. +Note that the validity needs to be checked in case there is no next field. +Here is an example code which checks if response data follows an ack/nack reply: + + FieldView first = packet.firstField(); + if(first.isValid()) + { + if( first.is_reply() ) + { + FieldView response = first.nextAfter(); + + if(response.isValid()) + printf("Got response field: 0x%02X\n", response.fieldDescriptor()); + } + } + +### Field properties + +FieldViews have properties similar to PacketViews: + + // Unsafe to access payload data or descriptor info unless valid. + // Generally this is already checked during field iteration. + bool valid = isValid(); + + uint8_t descriptor_set = field.descriptorSet(); // Same as the packet + uint8_t field_desc = field.fieldDescriptor(); + + // Combination of descriptor set and field descriptor. + CompositeDescriptor desc = field.descriptor(); + + uint8_t payload_length = field.payloadLength(); + const uint8_t* payload = field.payload(); + + // Span version of payload + microstrain::Span payload = field.payloadSpan(); + + // Determining the type of field, e.g. for routing it to the right function in your app. + bool is_data_field = field.isData(); // Data field, e.g. accel data + bool is_command = field.isCommand(); // Command to device + bool is_reply = field.isReply(); // Ack/nack field from device + bool is_response_data = field.isResponse(); // Reply from device containing data + +### Decoding field data + +After checking the descriptor, field data can be deserialized. + + if(field.descriptor() == mip::data_sensor::ScaledAccel::DESCRIPTOR) + { + mip::data_sensor::ScaledAccel data; + + if(field.extract(data)) + printf("Accel data = %f %f %f\n", data.scaled_accel[0], data.scaled_accel[1], data.scaled_accel[2]); + } + +You may also deserialize it manually. + + mip::Serializer serializer(field.payloadSpan()); + + // Same as prior example + //serializer.extract(data); + + // Separate parameters for scaled accel + float x,y,z; + serializer.extract(x,y,z); diff --git a/docs/miscellaneous.md b/docs/miscellaneous.md index 8d683afe1..6dc371978 100644 --- a/docs/miscellaneous.md +++ b/docs/miscellaneous.md @@ -4,21 +4,21 @@ Other Considerations {#other} Known Issues and Workarounds {#known_issues} ---------------------------- -### `suppress_ack` parameters are not supported +### suppress_ack parameters are not supported Some commands accept a parameter named `suppress_ack` which acts to prevent the standard ack/nack reply from being returned by the device, e.g. the -3DM Poll Data command. Use of this parameter is not supported in the MIP SDK +3DM Poll Data command. Use of this parameter is not directly supported by the MIP SDK and will cause the command to appear to time out after a short delay. -If you do not wish to wait for a reply (i.e. just send the command and continue) -you can build and send the command yourself: +If you wish to use this feature, (i.e. just send the command without waiting for an ACK/NACK), +you can build and send the command manually: ~~~~~~~~{.cpp} // Create the command with required parameters. mip::commands_3dm::PollData cmd; cmd.desc_set = mip::data_sensor::DESCRIPTOR_SET; -cmd.suppress_ack = true; +cmd.suppress_ack = true; // We can set this since we're not calling the standard cmd handling functions. cmd.num_descriptors = 2; cmd.descriptors[0] = mip::data_sensor::ScaledAccel::FIELD_DESCRIPTOR; cmd.descriptors[1] = mip::data_sensor::ScaledGyro::FIELD_DESCRIPTOR; diff --git a/docs/serialization.md b/docs/serialization.md index fbd6c7293..f52d63316 100644 --- a/docs/serialization.md +++ b/docs/serialization.md @@ -7,14 +7,15 @@ Serialization in C {#serialization_c} Serialization infrastructure in C is very basic and is currently limited to built-in types and big-endian protocols. To (de)serialize a buffer, follow these steps: -1. Create a serializer and initialize it via `microstrain_serializer_init_insertion` or `microstrain_serializer_init_extraction`, depending on whether you're +1. Create a serializer and initialize it via @ref microstrain_serializer_init_insertion + or @ref microstrain_serializer_init_extraction, depending on whether you're writing or reading data. -2. Call `microstrain_insert_*` or `microstrain_extract_*` for each parameter. -3. Call `microstrain_serializer_is_ok` to check if all the data was written/read successfully (i.e. fit in the buffer). - Alternatively, to verify if exactly buffer_size bytes were read/written, use `microstrain_serializer_is_complete`. +2. Call `microstrain_insert_*` or `microstrain_extract_*` for each parameter. E.g. @ref microstrain_extract_u32. +3. Call @ref microstrain_serializer_is_ok to check if all the data was written/read successfully (i.e. fit in the buffer). + Alternatively, to verify if exactly buffer_size bytes were read/written, use @ref microstrain_serializer_is_complete. 4. Transmit the written buffer or use the deserialized parameters. -When reading an array length from a buffer, it is recommended to use `microstrain_extract_count` to specify a maximum +When reading an array length from a buffer, it is recommended to use @ref microstrain_extract_count to specify a maximum length. This helps avoid buffer overrun bugs and associated security vulnerabilities. Serialization in C++ {#serialization_cpp} @@ -28,12 +29,12 @@ defined types. To (de)serialize a buffer, follow these steps: 1. Create a microstrain::Serializer, passing in a pointer to your buffer and the size. A starting offset may also be specified for convenience. -2. Call `serializer.insert` or `serializer.extract` with the values to be (de)serialized. Multiple calls may be made to +2. Call microstrain::Serializer::insert or microstrain::Serializer.extract with the values to be (de)serialized. Multiple calls may be made to these functions if needed. When reading an array length from a buffer, it is recommended to use - `Serializer::extract_count` to specify a maximum count. This helps avoid buffer overrun bugs and associated security + microstrain::Serializer::extract_count to specify a maximum count. This helps avoid buffer overrun bugs and associated security vulnerabilities. -3. Check if the data was written/read successfully (i.e. fit in the buffer) by calling `Serializer::isOk` or - `Serializer::isFinished` (use the latter if the entire buffer should have been used). +3. Check if the data was written/read successfully (i.e. fit in the buffer) by calling microstrain::Serializer::isOk or + microstrain::Serializer::isFinished (use the latter if the entire buffer should have been used). 4. Transmit the written buffer or use the deserialized parameters. Example: diff --git a/docs/style.css b/docs/style.css new file mode 100644 index 000000000..1baf53fe7 --- /dev/null +++ b/docs/style.css @@ -0,0 +1,29 @@ +a[href*="cpp.html"], a[href^="class"], a[href*="mip_1_1"], a[href*="microstrain_1_1"] { + filter: hue-rotate(-90deg) saturate(50%); +} +a[href^="group__c"], a[href*="_c.html"], a[href*="_1_1C_"] { + /*filter: brightness(120%);*/ + filter: hue-rotate(90deg) saturate(50%); +} + +/*.directory td.entry:has(> a) {*/ +/* background-color: aquamarine;*/ +/*}*/ + +/*td.entry:has(a.el[href="group__MipCommandQueue__c.html"]) {*/ +/* background-color: green;*/ +/*}*/ + + +/*td.entry:has(a.el[href$="__c.html"]) {*/ +/* !*background-color: #ebecf0;*!*/ +/* filter: brightness(90%);*/ +/*}*/ +/*td.entry:has(a.el[href$="__cpp.html"]) {*/ +/* !*background-color: #ebecf0;*!*/ +/* filter: brightness(90%);*/ +/*}*/ +/*td.entry.even:has(a.el[href$="__c.html"]) {*/ +/* !*background-color: #F7F8FB;*!*/ +/* background-color: #ebecf0;*/ +/*}*/ diff --git a/examples/mip_packet_example.cpp b/examples/mip_packet_example.cpp index 7f8db90ee..ad91b0977 100644 --- a/examples/mip_packet_example.cpp +++ b/examples/mip_packet_example.cpp @@ -330,11 +330,10 @@ void create_packet_from_buffer() } case mip::data_sensor::ScaledAccel::FIELD_DESCRIPTOR: { - // Extract the 3-vector. - float x,y,z; + mip::data_sensor::ScaledAccel data; - if(serializer.extract(x,y,z)) - printf(" Scaled Accel = (%f, %f, %f)\n", x, y, z); + if(serializer.extract(data)) + printf(" Scaled Accel = (%f, %f, %f)\n", data.scaled_accel[0], data.scaled_accel[1], data.scaled_accel[2]); break; } @@ -342,7 +341,9 @@ void create_packet_from_buffer() { mip::data_sensor::ScaledGyro data; - if(serializer.extract(data)) + // This calls the FieldView::extract helper function which handles deserialization directly. + // This is the simplest and preferred method. + if(field.extract(data)) printf(" Scaled Gyro = (%f, %f, %f)\n", data.scaled_gyro[0], data.scaled_gyro[1], data.scaled_gyro[2]); break; diff --git a/src/c/mip/definitions/commands_3dm.h b/src/c/mip/definitions/commands_3dm.h index e8fe54b3c..af660aa2f 100644 --- a/src/c/mip/definitions/commands_3dm.h +++ b/src/c/mip/definitions/commands_3dm.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_c MIP Commands [C] +///@addtogroup MipCommands_c ///@{ -///@defgroup 3dm_commands_c 3dm Commands [C] +///@defgroup 3dm_commands_c 3dm Commands /// ///@{ @@ -229,7 +229,7 @@ static inline void extract_mip_sensor_range_type(microstrain_serializer* seriali //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_poll_imu_message (0x0C,0x01) Poll Imu Message [C] +///@defgroup 3dm_poll_imu_message_c (0x0C,0x01) Poll Imu Message /// Poll the device for an IMU message with the specified format /// /// This function polls for an IMU message using the provided format. The resulting message @@ -257,7 +257,7 @@ mip_cmd_result mip_3dm_poll_imu_message(mip_interface* device, bool suppress_ack ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_poll_gnss_message (0x0C,0x02) Poll Gnss Message [C] +///@defgroup 3dm_poll_gnss_message_c (0x0C,0x02) Poll Gnss Message /// Poll the device for an GNSS message with the specified format /// /// This function polls for a GNSS message using the provided format. The resulting message @@ -285,7 +285,7 @@ mip_cmd_result mip_3dm_poll_gnss_message(mip_interface* device, bool suppress_ac ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_poll_filter_message (0x0C,0x03) Poll Filter Message [C] +///@defgroup 3dm_poll_filter_message_c (0x0C,0x03) Poll Filter Message /// Poll the device for an Estimation Filter message with the specified format /// /// This function polls for an Estimation Filter message using the provided format. The resulting message @@ -313,7 +313,7 @@ mip_cmd_result mip_3dm_poll_filter_message(mip_interface* device, bool suppress_ ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_imu_message_format (0x0C,0x08) Imu Message Format [C] +///@defgroup 3dm_imu_message_format_c (0x0C,0x08) Imu Message Format /// Set, read, or save the format of the IMU data packet. /// /// The resulting data messages will maintain the order of descriptors sent in the command. @@ -350,7 +350,7 @@ mip_cmd_result mip_3dm_default_imu_message_format(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_gps_message_format (0x0C,0x09) Gps Message Format [C] +///@defgroup 3dm_gps_message_format_c (0x0C,0x09) Gps Message Format /// Set, read, or save the format of the GNSS data packet. /// /// The resulting data messages will maintain the order of descriptors sent in the command. @@ -387,7 +387,7 @@ mip_cmd_result mip_3dm_default_gps_message_format(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_filter_message_format (0x0C,0x0A) Filter Message Format [C] +///@defgroup 3dm_filter_message_format_c (0x0C,0x0A) Filter Message Format /// Set, read, or save the format of the Estimation Filter data packet. /// /// The resulting data messages will maintain the order of descriptors sent in the command. @@ -424,7 +424,7 @@ mip_cmd_result mip_3dm_default_filter_message_format(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_imu_get_base_rate (0x0C,0x06) Imu Get Base Rate [C] +///@defgroup 3dm_imu_get_base_rate_c (0x0C,0x06) Imu Get Base Rate /// Get the base rate for the IMU data in Hz /// /// This is the fastest rate for this type of data available on the device. @@ -448,7 +448,7 @@ mip_cmd_result mip_3dm_imu_get_base_rate(mip_interface* device, uint16_t* rate_o ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_gps_get_base_rate (0x0C,0x07) Gps Get Base Rate [C] +///@defgroup 3dm_gps_get_base_rate_c (0x0C,0x07) Gps Get Base Rate /// Get the base rate for the GNSS data in Hz /// /// This is the fastest rate for this type of data available on the device. @@ -472,7 +472,7 @@ mip_cmd_result mip_3dm_gps_get_base_rate(mip_interface* device, uint16_t* rate_o ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_filter_get_base_rate (0x0C,0x0B) Filter Get Base Rate [C] +///@defgroup 3dm_filter_get_base_rate_c (0x0C,0x0B) Filter Get Base Rate /// Get the base rate for the Estimation Filter data in Hz /// /// This is the fastest rate for this type of data available on the device. @@ -496,7 +496,7 @@ mip_cmd_result mip_3dm_filter_get_base_rate(mip_interface* device, uint16_t* rat ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_poll_data (0x0C,0x0D) Poll Data [C] +///@defgroup 3dm_poll_data_c (0x0C,0x0D) Poll Data /// Poll the device for a message with the specified descriptor set and format. /// /// This function polls for a message using the provided format. The resulting message @@ -525,7 +525,7 @@ mip_cmd_result mip_3dm_poll_data(mip_interface* device, uint8_t desc_set, bool s ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_get_base_rate (0x0C,0x0E) Get Base Rate [C] +///@defgroup 3dm_get_base_rate_c (0x0C,0x0E) Get Base Rate /// Get the base rate for the specified descriptor set in Hz. /// ///@{ @@ -554,7 +554,7 @@ mip_cmd_result mip_3dm_get_base_rate(mip_interface* device, uint8_t desc_set, ui ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_message_format (0x0C,0x0F) Message Format [C] +///@defgroup 3dm_message_format_c (0x0C,0x0F) Message Format /// Set, read, or save the format for a given data packet. /// /// The resulting data messages will maintain the order of descriptors sent in the command. @@ -593,7 +593,7 @@ mip_cmd_result mip_3dm_default_message_format(mip_interface* device, uint8_t des ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_nmea_poll_data (0x0C,0x04) Nmea Poll Data [C] +///@defgroup 3dm_nmea_poll_data_c (0x0C,0x04) Nmea Poll Data /// Poll the device for a NMEA message with the specified format. /// /// This function polls for a NMEA message using the provided format. @@ -620,7 +620,7 @@ mip_cmd_result mip_3dm_nmea_poll_data(mip_interface* device, bool suppress_ack, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_nmea_message_format (0x0C,0x0C) Nmea Message Format [C] +///@defgroup 3dm_nmea_message_format_c (0x0C,0x0C) Nmea Message Format /// Set, read, or save the NMEA message format. /// ///@{ @@ -655,7 +655,7 @@ mip_cmd_result mip_3dm_default_nmea_message_format(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_device_settings (0x0C,0x30) Device Settings [C] +///@defgroup 3dm_device_settings_c (0x0C,0x30) Device Settings /// Save, Load, or Reset to Default the values for all device settings. /// /// When a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory. @@ -680,7 +680,7 @@ mip_cmd_result mip_3dm_default_device_settings(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_uart_baudrate (0x0C,0x40) Uart Baudrate [C] +///@defgroup 3dm_uart_baudrate_c (0x0C,0x40) Uart Baudrate /// Read, Save, Load, or Reset to Default the baud rate of the main communication channel. /// /// For all functions except 0x01 (use new settings), the new baud rate value is ignored. @@ -727,7 +727,7 @@ mip_cmd_result mip_3dm_default_uart_baudrate(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_factory_streaming (0x0C,0x10) Factory Streaming [C] +///@defgroup 3dm_factory_streaming_c (0x0C,0x10) Factory Streaming /// Configures the device for recording data for technical support. /// /// This command will configure all available data streams to predefined @@ -770,7 +770,7 @@ mip_cmd_result mip_3dm_factory_streaming(mip_interface* device, mip_3dm_factory_ ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_datastream_control (0x0C,0x11) Datastream Control [C] +///@defgroup 3dm_datastream_control_c (0x0C,0x11) Datastream Control /// Enable/disable the selected data stream. /// /// Each data stream (descriptor set) can be enabled or disabled. @@ -815,7 +815,7 @@ mip_cmd_result mip_3dm_default_datastream_control(mip_interface* device, uint8_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_constellation_settings (0x0C,0x21) Constellation Settings [C] +///@defgroup 3dm_constellation_settings_c (0x0C,0x21) Constellation Settings /// This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation. /// /// Maximum number of tracking channels to use (total for all constellations): @@ -921,7 +921,7 @@ mip_cmd_result mip_3dm_default_constellation_settings(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_gnss_sbas_settings (0x0C,0x22) Gnss Sbas Settings [C] +///@defgroup 3dm_gnss_sbas_settings_c (0x0C,0x22) Gnss Sbas Settings /// Configure the SBAS subsystem /// /// @@ -981,7 +981,7 @@ mip_cmd_result mip_3dm_default_gnss_sbas_settings(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_gnss_assisted_fix (0x0C,0x23) Gnss Assisted Fix [C] +///@defgroup 3dm_gnss_assisted_fix_c (0x0C,0x23) Gnss Assisted Fix /// Set the options for assisted GNSS fix. /// /// Devices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM. @@ -1045,7 +1045,7 @@ mip_cmd_result mip_3dm_default_gnss_assisted_fix(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_gnss_time_assistance (0x0C,0x24) Gnss Time Assistance [C] +///@defgroup 3dm_gnss_time_assistance_c (0x0C,0x24) Gnss Time Assistance /// Provide the GNSS subsystem with initial time information. /// /// This message is required immediately after power up if GNSS Assist was enabled when the device was powered off. @@ -1082,7 +1082,7 @@ mip_cmd_result mip_3dm_read_gnss_time_assistance(mip_interface* device, double* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_imu_lowpass_filter (0x0C,0x50) Imu Lowpass Filter [C] +///@defgroup 3dm_imu_lowpass_filter_c (0x0C,0x50) Imu Lowpass Filter /// Advanced configuration for the IMU data quantity low-pass filters. /// /// Deprecated, use the lowpass filter (0x0C,0x54) command instead. @@ -1138,7 +1138,7 @@ mip_cmd_result mip_3dm_default_imu_lowpass_filter(mip_interface* device, uint8_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_pps_source (0x0C,0x28) Pps Source [C] +///@defgroup 3dm_pps_source_c (0x0C,0x28) Pps Source /// Controls the Pulse Per Second (PPS) source. /// ///@{ @@ -1193,7 +1193,7 @@ mip_cmd_result mip_3dm_default_pps_source(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_gpio_config (0x0C,0x41) Gpio Config [C] +///@defgroup 3dm_gpio_config_c (0x0C,0x41) Gpio Config /// Configures the user GPIO pins on the connector for use with several built-in functions or for general input or output. /// /// GPIO pins are device-dependent. Some features are only available on @@ -1319,7 +1319,7 @@ mip_cmd_result mip_3dm_default_gpio_config(mip_interface* device, uint8_t pin); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_gpio_state (0x0C,0x42) Gpio State [C] +///@defgroup 3dm_gpio_state_c (0x0C,0x42) Gpio State /// Allows the state of the pin to be read or controlled. /// /// This command serves two purposes: 1) To allow reading the state of a pin via command, @@ -1366,7 +1366,7 @@ mip_cmd_result mip_3dm_read_gpio_state(mip_interface* device, uint8_t pin, bool* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_odometer (0x0C,0x43) Odometer [C] +///@defgroup 3dm_odometer_c (0x0C,0x43) Odometer /// Configures the hardware odometer interface. /// /// @@ -1423,7 +1423,7 @@ mip_cmd_result mip_3dm_default_odometer(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_get_event_support (0x0C,0x2A) Get Event Support [C] +///@defgroup 3dm_get_event_support_c (0x0C,0x2A) Get Event Support /// Lists the available trigger or action types. /// /// There are a limited number of trigger and action slots available @@ -1499,7 +1499,7 @@ mip_cmd_result mip_3dm_get_event_support(mip_interface* device, mip_3dm_get_even ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_event_control (0x0C,0x2B) Event Control [C] +///@defgroup 3dm_event_control_c (0x0C,0x2B) Event Control /// Enables or disables event triggers. /// /// Triggers can be disabled, enabled, and tested. While disabled, a trigger will @@ -1564,7 +1564,7 @@ mip_cmd_result mip_3dm_default_event_control(mip_interface* device, uint8_t inst ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_get_event_trigger_status (0x0C,0x2C) Get Event Trigger Status [C] +///@defgroup 3dm_get_event_trigger_status_c (0x0C,0x2C) Get Event Trigger Status /// ///@{ @@ -1621,7 +1621,7 @@ mip_cmd_result mip_3dm_get_event_trigger_status(mip_interface* device, uint8_t r ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_get_event_action_status (0x0C,0x2D) Get Event Action Status [C] +///@defgroup 3dm_get_event_action_status_c (0x0C,0x2D) Get Event Action Status /// ///@{ @@ -1661,7 +1661,7 @@ mip_cmd_result mip_3dm_get_event_action_status(mip_interface* device, uint8_t re ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_event_trigger (0x0C,0x2E) Event Trigger [C] +///@defgroup 3dm_event_trigger_c (0x0C,0x2E) Event Trigger /// Configures various types of event triggers. /// ///@{ @@ -1822,7 +1822,7 @@ mip_cmd_result mip_3dm_default_event_trigger(mip_interface* device, uint8_t inst ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_event_action (0x0C,0x2F) Event Action [C] +///@defgroup 3dm_event_action_c (0x0C,0x2F) Event Action /// Configures various types of event actions. /// ///@{ @@ -1932,7 +1932,7 @@ mip_cmd_result mip_3dm_default_event_action(mip_interface* device, uint8_t insta ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_accel_bias (0x0C,0x37) Accel Bias [C] +///@defgroup 3dm_accel_bias_c (0x0C,0x37) Accel Bias /// Configures the user specified accelerometer bias /// /// The user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame. @@ -1967,7 +1967,7 @@ mip_cmd_result mip_3dm_default_accel_bias(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_gyro_bias (0x0C,0x38) Gyro Bias [C] +///@defgroup 3dm_gyro_bias_c (0x0C,0x38) Gyro Bias /// Configures the user specified gyroscope bias /// /// The user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame. @@ -2002,7 +2002,7 @@ mip_cmd_result mip_3dm_default_gyro_bias(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_capture_gyro_bias (0x0C,0x39) Capture Gyro Bias [C] +///@defgroup 3dm_capture_gyro_bias_c (0x0C,0x39) Capture Gyro Bias /// Samples gyro for a specified time range and writes the averaged result to the Gyro Bias vector in RAM /// /// The device will average the gyro output for the duration of "averaging_time_ms." To store the resulting vector @@ -2035,7 +2035,7 @@ mip_cmd_result mip_3dm_capture_gyro_bias(mip_interface* device, uint16_t averagi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_mag_hard_iron_offset (0x0C,0x3A) Mag Hard Iron Offset [C] +///@defgroup 3dm_mag_hard_iron_offset_c (0x0C,0x3A) Mag Hard Iron Offset /// Configure the user specified magnetometer hard iron offset vector /// /// The values for this offset are determined empirically by external software algorithms @@ -2074,7 +2074,7 @@ mip_cmd_result mip_3dm_default_mag_hard_iron_offset(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_mag_soft_iron_matrix (0x0C,0x3B) Mag Soft Iron Matrix [C] +///@defgroup 3dm_mag_soft_iron_matrix_c (0x0C,0x3B) Mag Soft Iron Matrix /// Configure the user specified magnetometer soft iron offset matrix /// /// The values for this matrix are determined empirically by external software algorithms @@ -2117,7 +2117,7 @@ mip_cmd_result mip_3dm_default_mag_soft_iron_matrix(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_coning_sculling_enable (0x0C,0x3E) Coning Sculling Enable [C] +///@defgroup 3dm_coning_sculling_enable_c (0x0C,0x3E) Coning Sculling Enable /// Controls the Coning and Sculling Compenstation setting. /// ///@{ @@ -2150,7 +2150,7 @@ mip_cmd_result mip_3dm_default_coning_sculling_enable(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_sensor_2_vehicle_transform_euler (0x0C,0x31) Sensor 2 Vehicle Transform Euler [C] +///@defgroup 3dm_sensor_2_vehicle_transform_euler_c (0x0C,0x31) Sensor 2 Vehicle Transform Euler /// Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, Roll Euler angles. /// These are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference, /// and describe the transformation of vectors from the sensor body frame to the vehicle frame.
@@ -2211,7 +2211,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_euler(mip_interface* d ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_sensor_2_vehicle_transform_quaternion (0x0C,0x32) Sensor 2 Vehicle Transform Quaternion [C] +///@defgroup 3dm_sensor_2_vehicle_transform_quaternion_c (0x0C,0x32) Sensor 2 Vehicle Transform Quaternion /// Set the sensor to vehicle frame transformation using unit length quaternion. /// /// Note: This is the transformation, the inverse of the rotation. @@ -2276,7 +2276,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_quaternion(mip_interfa ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_sensor_2_vehicle_transform_dcm (0x0C,0x33) Sensor 2 Vehicle Transform Dcm [C] +///@defgroup 3dm_sensor_2_vehicle_transform_dcm_c (0x0C,0x33) Sensor 2 Vehicle Transform Dcm /// Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array. /// /// These angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
@@ -2339,7 +2339,7 @@ mip_cmd_result mip_3dm_default_sensor_2_vehicle_transform_dcm(mip_interface* dev ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_complementary_filter (0x0C,0x51) Complementary Filter [C] +///@defgroup 3dm_complementary_filter_c (0x0C,0x51) Complementary Filter /// Configure the settings for the complementary filter which produces the following (0x80) descriptor set values: attitude matrix (0x80,09), quaternion (0x80,0A), and Euler angle (0x80,0C) outputs. /// /// The filter can be configured to correct for pitch and roll using the accelerometer (with the assumption that linear acceleration is minimal), @@ -2382,7 +2382,7 @@ mip_cmd_result mip_3dm_default_complementary_filter(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_sensor_range (0x0C,0x52) Sensor Range [C] +///@defgroup 3dm_sensor_range_c (0x0C,0x52) Sensor Range /// Changes the IMU sensor gain. /// /// This allows you to optimize the range to get the best accuracy and performance @@ -2424,7 +2424,7 @@ mip_cmd_result mip_3dm_default_sensor_range(mip_interface* device, mip_sensor_ra ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_calibrated_sensor_ranges (0x0C,0x53) Calibrated Sensor Ranges [C] +///@defgroup 3dm_calibrated_sensor_ranges_c (0x0C,0x53) Calibrated Sensor Ranges /// Returns the supported sensor ranges which may be used with the 3DM Sensor Range (0x0C,0x52) command. /// /// The response includes an array of (u8, float) pairs which map each allowed setting @@ -2468,7 +2468,7 @@ mip_cmd_result mip_3dm_calibrated_sensor_ranges(mip_interface* device, mip_senso ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_3dm_lowpass_filter (0x0C,0x54) Lowpass Filter [C] +///@defgroup 3dm_lowpass_filter_c (0x0C,0x54) Lowpass Filter /// This command controls the low-pass anti-aliasing filter supported data quantities. /// /// See the device user manual for data quantities which support the anti-aliasing filter. diff --git a/src/c/mip/definitions/commands_aiding.h b/src/c/mip/definitions/commands_aiding.h index daee62020..e12c67577 100644 --- a/src/c/mip/definitions/commands_aiding.h +++ b/src/c/mip/definitions/commands_aiding.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_c MIP Commands [C] +///@addtogroup MipCommands_c ///@{ -///@defgroup aiding_commands_c Aiding Commands [C] +///@defgroup aiding_commands_c Aiding Commands /// ///@{ @@ -95,7 +95,7 @@ void extract_mip_time(microstrain_serializer* serializer, mip_time* self); //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_frame_config (0x13,0x01) Frame Config [C] +///@defgroup aiding_frame_config_c (0x13,0x01) Frame Config /// Defines an aiding frame associated with a specific sensor frame ID. /// The frame ID used in this command should mirror the frame ID used in the aiding command /// (if that aiding measurement is measured in this reference frame). @@ -185,7 +185,7 @@ mip_cmd_result mip_aiding_default_frame_config(mip_interface* device, uint8_t fr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_echo_control (0x13,0x1F) Echo Control [C] +///@defgroup aiding_echo_control_c (0x13,0x1F) Echo Control /// Controls command response behavior to external aiding commands /// ///@{ @@ -238,7 +238,7 @@ mip_cmd_result mip_aiding_default_echo_control(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_pos_ecef (0x13,0x21) Pos Ecef [C] +///@defgroup aiding_pos_ecef_c (0x13,0x21) Pos Ecef /// Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system. /// ///@{ @@ -279,7 +279,7 @@ mip_cmd_result mip_aiding_pos_ecef(mip_interface* device, const mip_time* time, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_pos_llh (0x13,0x22) Pos Llh [C] +///@defgroup aiding_pos_llh_c (0x13,0x22) Pos Llh /// Geodetic position aiding command. /// Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. /// Uncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height. @@ -324,7 +324,7 @@ mip_cmd_result mip_aiding_pos_llh(mip_interface* device, const mip_time* time, u ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_height_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [C] +///@defgroup aiding_height_above_ellipsoid_c (0x13,0x23) Height Above Ellipsoid /// Estimated value of the height above ellipsoid. /// ///@{ @@ -347,7 +347,7 @@ mip_cmd_result mip_aiding_height_above_ellipsoid(mip_interface* device, const mi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_vel_ecef (0x13,0x28) Vel Ecef [C] +///@defgroup aiding_vel_ecef_c (0x13,0x28) Vel Ecef /// ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame. /// ///@{ @@ -388,7 +388,7 @@ mip_cmd_result mip_aiding_vel_ecef(mip_interface* device, const mip_time* time, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_vel_ned (0x13,0x29) Vel Ned [C] +///@defgroup aiding_vel_ned_c (0x13,0x29) Vel Ned /// NED velocity aiding command. Coordinates are given in the local North-East-Down frame. /// ///@{ @@ -429,7 +429,7 @@ mip_cmd_result mip_aiding_vel_ned(mip_interface* device, const mip_time* time, u ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_vel_body_frame (0x13,0x2A) Vel Body Frame [C] +///@defgroup aiding_vel_body_frame_c (0x13,0x2A) Vel Body Frame /// Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame. /// ///@{ @@ -470,7 +470,7 @@ mip_cmd_result mip_aiding_vel_body_frame(mip_interface* device, const mip_time* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_heading_true (0x13,0x31) Heading True [C] +///@defgroup aiding_heading_true_c (0x13,0x31) Heading True /// ///@{ @@ -492,7 +492,7 @@ mip_cmd_result mip_aiding_heading_true(mip_interface* device, const mip_time* ti ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_magnetic_field (0x13,0x32) Magnetic Field [C] +///@defgroup aiding_magnetic_field_c (0x13,0x32) Magnetic Field /// Estimate of magnetic field in the frame associated with the given sensor ID. /// ///@{ @@ -533,7 +533,7 @@ mip_cmd_result mip_aiding_magnetic_field(mip_interface* device, const mip_time* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_aiding_pressure (0x13,0x33) Pressure [C] +///@defgroup aiding_pressure_c (0x13,0x33) Pressure /// Estimated value of air pressure. /// ///@{ diff --git a/src/c/mip/definitions/commands_base.h b/src/c/mip/definitions/commands_base.h index 45bbc7fb5..eda89b56a 100644 --- a/src/c/mip/definitions/commands_base.h +++ b/src/c/mip/definitions/commands_base.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_c MIP Commands [C] +///@addtogroup MipCommands_c ///@{ -///@defgroup base_commands_c Base Commands [C] +///@defgroup base_commands_c Base Commands /// ///@{ @@ -135,7 +135,7 @@ static inline void extract_mip_commanded_test_bits_gq7(microstrain_serializer* s //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_ping (0x01,0x01) Ping [C] +///@defgroup base_ping_c (0x01,0x01) Ping /// Test Communications with a device. /// /// The Device will respond with an ACK, if present and operating correctly. @@ -151,7 +151,7 @@ mip_cmd_result mip_base_ping(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_set_idle (0x01,0x02) Set Idle [C] +///@defgroup base_set_idle_c (0x01,0x02) Set Idle /// Turn off all device data streams. /// /// The Device will respond with an ACK, if present and operating correctly. @@ -167,7 +167,7 @@ mip_cmd_result mip_base_set_idle(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_get_device_info (0x01,0x03) Get Device Info [C] +///@defgroup base_get_device_info_c (0x01,0x03) Get Device Info /// Get the device ID strings and firmware version number. /// ///@{ @@ -188,7 +188,7 @@ mip_cmd_result mip_base_get_device_info(mip_interface* device, mip_base_device_i ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_get_device_descriptors (0x01,0x04) Get Device Descriptors [C] +///@defgroup base_get_device_descriptors_c (0x01,0x04) Get Device Descriptors /// Get the command and data descriptors supported by the device. /// /// Reply has two fields: "ACK/NACK" and "Descriptors". The "Descriptors" field is an array of 16 bit values. @@ -213,7 +213,7 @@ mip_cmd_result mip_base_get_device_descriptors(mip_interface* device, uint16_t* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_built_in_test (0x01,0x05) Built In Test [C] +///@defgroup base_built_in_test_c (0x01,0x05) Built In Test /// Run the device Built-In Test (BIT). /// /// The Built-In Test command always returns a 32 bit value. @@ -239,7 +239,7 @@ mip_cmd_result mip_base_built_in_test(mip_interface* device, uint32_t* result_ou ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_resume (0x01,0x06) Resume [C] +///@defgroup base_resume_c (0x01,0x06) Resume /// Take the device out of idle mode. /// /// The device responds with ACK upon success. @@ -253,7 +253,7 @@ mip_cmd_result mip_base_resume(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_get_extended_descriptors (0x01,0x07) Get Extended Descriptors [C] +///@defgroup base_get_extended_descriptors_c (0x01,0x07) Get Extended Descriptors /// Get the command and data descriptors supported by the device. /// /// Reply has two fields: "ACK/NACK" and "Descriptors". The "Descriptors" field is an array of 16 bit values. @@ -278,7 +278,7 @@ mip_cmd_result mip_base_get_extended_descriptors(mip_interface* device, uint16_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_continuous_bit (0x01,0x08) Continuous Bit [C] +///@defgroup base_continuous_bit_c (0x01,0x08) Continuous Bit /// Report result of continuous built-in test. /// /// This test is non-disruptive but is not as thorough as the commanded BIT. @@ -301,7 +301,7 @@ mip_cmd_result mip_base_continuous_bit(mip_interface* device, uint8_t* result_ou ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_comm_speed (0x01,0x09) Comm Speed [C] +///@defgroup base_comm_speed_c (0x01,0x09) Comm Speed /// Controls the baud rate of a specific port on the device. /// /// Please see the device user manual for supported baud rates on each port. @@ -351,7 +351,7 @@ mip_cmd_result mip_base_default_comm_speed(mip_interface* device, uint8_t port); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_gps_time_update (0x01,0x72) Gps Time Update [C] +///@defgroup base_gps_time_update_c (0x01,0x72) Gps Time Update /// Set device internal GPS time /// When combined with a PPS input signal applied to the I/O connector, this command enables complete synchronization of data outputs /// with an external time base, such as GPS system time. Since the hardware PPS synchronization can only detect the fractional number of seconds when pulses arrive, @@ -394,7 +394,7 @@ mip_cmd_result mip_base_write_gps_time_update(mip_interface* device, mip_base_gp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_base_soft_reset (0x01,0x7E) Soft Reset [C] +///@defgroup base_soft_reset_c (0x01,0x7E) Soft Reset /// Resets the device. /// /// Device responds with ACK and immediately resets. diff --git a/src/c/mip/definitions/commands_filter.h b/src/c/mip/definitions/commands_filter.h index 1fc6f8081..ebf9b8e5c 100644 --- a/src/c/mip/definitions/commands_filter.h +++ b/src/c/mip/definitions/commands_filter.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_c MIP Commands [C] +///@addtogroup MipCommands_c ///@{ -///@defgroup filter_commands_c Filter Commands [C] +///@defgroup filter_commands_c Filter Commands /// ///@{ @@ -216,7 +216,7 @@ static inline void extract_mip_filter_adaptive_measurement(microstrain_serialize //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_reset (0x0D,0x01) Reset [C] +///@defgroup filter_reset_c (0x0D,0x01) Reset /// Resets the filter to the initialization state. /// /// If the auto-initialization feature is disabled, the initial attitude or heading must be set in @@ -231,7 +231,7 @@ mip_cmd_result mip_filter_reset(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_set_initial_attitude (0x0D,0x02) Set Initial Attitude [C] +///@defgroup filter_set_initial_attitude_c (0x0D,0x02) Set Initial Attitude /// Set the sensor initial attitude. /// /// This command can only be issued in the "Init" state and should be used with a good @@ -263,7 +263,7 @@ mip_cmd_result mip_filter_set_initial_attitude(mip_interface* device, float roll ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_estimation_control (0x0D,0x14) Estimation Control [C] +///@defgroup filter_estimation_control_c (0x0D,0x14) Estimation Control /// Estimation Control Flags /// /// Controls which parameters are estimated by the Kalman Filter. @@ -328,7 +328,7 @@ mip_cmd_result mip_filter_default_estimation_control(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_external_gnss_update (0x0D,0x16) External Gnss Update [C] +///@defgroup filter_external_gnss_update_c (0x0D,0x16) External Gnss Update /// Provide a filter measurement from an external GNSS /// /// The GNSS source control must be set to "external" for this command to succeed, otherwise it will be NACK'd. @@ -358,7 +358,7 @@ mip_cmd_result mip_filter_external_gnss_update(mip_interface* device, double gps ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_external_heading_update (0x0D,0x17) External Heading Update [C] +///@defgroup filter_external_heading_update_c (0x0D,0x17) External Heading Update /// Provide a filter measurement from an external heading source /// /// The heading must be the sensor frame with respect to the NED frame. @@ -391,7 +391,7 @@ mip_cmd_result mip_filter_external_heading_update(mip_interface* device, float h ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_external_heading_update_with_time (0x0D,0x1F) External Heading Update With Time [C] +///@defgroup filter_external_heading_update_with_time_c (0x0D,0x1F) External Heading Update With Time /// Provide a filter measurement from an external heading source at a specific GPS time /// /// This is more accurate than the External Heading Update (0x0D, 0x17) and should be used in applications @@ -430,7 +430,7 @@ mip_cmd_result mip_filter_external_heading_update_with_time(mip_interface* devic ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_tare_orientation (0x0D,0x21) Tare Orientation [C] +///@defgroup filter_tare_orientation_c (0x0D,0x21) Tare Orientation /// Tare the device orientation. /// /// This function uses the current device orientation relative to the NED frame as the current sensor to vehicle transformation. @@ -485,7 +485,7 @@ mip_cmd_result mip_filter_default_tare_orientation(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_vehicle_dynamics_mode (0x0D,0x10) Vehicle Dynamics Mode [C] +///@defgroup filter_vehicle_dynamics_mode_c (0x0D,0x10) Vehicle Dynamics Mode /// Controls the vehicle dynamics mode. /// ///@{ @@ -539,7 +539,7 @@ mip_cmd_result mip_filter_default_vehicle_dynamics_mode(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_sensor_to_vehicle_rotation_euler (0x0D,0x11) Sensor To Vehicle Rotation Euler [C] +///@defgroup filter_sensor_to_vehicle_rotation_euler_c (0x0D,0x11) Sensor To Vehicle Rotation Euler /// Set the sensor to vehicle frame rotation using Yaw, Pitch, Roll Euler angles. /// /// Note: This is the rotation, the inverse of the transformation. @@ -598,7 +598,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_euler(mip_interface ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_sensor_to_vehicle_rotation_dcm (0x0D,0x4E) Sensor To Vehicle Rotation Dcm [C] +///@defgroup filter_sensor_to_vehicle_rotation_dcm_c (0x0D,0x4E) Sensor To Vehicle Rotation Dcm /// Set the sensor to vehicle frame rotation using a row-major direction cosine matrix. /// /// Note: This is the rotation, the inverse of the transformation. @@ -659,7 +659,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_dcm(mip_interface* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_sensor_to_vehicle_rotation_quaternion (0x0D,0x4F) Sensor To Vehicle Rotation Quaternion [C] +///@defgroup filter_sensor_to_vehicle_rotation_quaternion_c (0x0D,0x4F) Sensor To Vehicle Rotation Quaternion /// Set the sensor to vehicle frame rotation using a quaternion. /// /// Note: This is the rotation, the inverse of the transformation. @@ -719,7 +719,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_rotation_quaternion(mip_inte ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_sensor_to_vehicle_offset (0x0D,0x12) Sensor To Vehicle Offset [C] +///@defgroup filter_sensor_to_vehicle_offset_c (0x0D,0x12) Sensor To Vehicle Offset /// Set the sensor to vehicle frame offset, expressed in the sensor frame. /// /// This is a simple offset, not a lever arm. It does not compensate for inertial effects experienced from being offset from the center of gravity/rotation of the vehicle. @@ -760,7 +760,7 @@ mip_cmd_result mip_filter_default_sensor_to_vehicle_offset(mip_interface* device ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_antenna_offset (0x0D,0x13) Antenna Offset [C] +///@defgroup filter_antenna_offset_c (0x0D,0x13) Antenna Offset /// Configure the GNSS antenna offset. /// /// For 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. @@ -802,7 +802,7 @@ mip_cmd_result mip_filter_default_antenna_offset(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gnss_source (0x0D,0x15) Gnss Source [C] +///@defgroup filter_gnss_source_c (0x0D,0x15) Gnss Source /// Control the source of GNSS information used to update the Kalman Filter. /// /// Changing the GNSS source while the sensor is in the "running" state may temporarily place @@ -860,7 +860,7 @@ mip_cmd_result mip_filter_default_gnss_source(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_heading_source (0x0D,0x18) Heading Source [C] +///@defgroup filter_heading_source_c (0x0D,0x18) Heading Source /// Control the source of heading information used to update the Kalman Filter. /// /// 1. To use internal GNSS velocity vector for heading updates, the target application @@ -929,7 +929,7 @@ mip_cmd_result mip_filter_default_heading_source(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_auto_init_control (0x0D,0x19) Auto Init Control [C] +///@defgroup filter_auto_init_control_c (0x0D,0x19) Auto Init Control /// Filter Auto-initialization Control /// /// Enable/Disable automatic initialization upon device startup. @@ -970,7 +970,7 @@ mip_cmd_result mip_filter_default_auto_init_control(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_accel_noise (0x0D,0x1A) Accel Noise [C] +///@defgroup filter_accel_noise_c (0x0D,0x1A) Accel Noise /// Accelerometer Noise Standard Deviation /// /// Each of the noise values must be greater than 0.0. @@ -1009,7 +1009,7 @@ mip_cmd_result mip_filter_default_accel_noise(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gyro_noise (0x0D,0x1B) Gyro Noise [C] +///@defgroup filter_gyro_noise_c (0x0D,0x1B) Gyro Noise /// Gyroscope Noise Standard Deviation /// /// Each of the noise values must be greater than 0.0 @@ -1048,7 +1048,7 @@ mip_cmd_result mip_filter_default_gyro_noise(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_accel_bias_model (0x0D,0x1C) Accel Bias Model [C] +///@defgroup filter_accel_bias_model_c (0x0D,0x1C) Accel Bias Model /// Accelerometer Bias Model Parameters /// /// Noise values must be greater than 0.0 @@ -1086,7 +1086,7 @@ mip_cmd_result mip_filter_default_accel_bias_model(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gyro_bias_model (0x0D,0x1D) Gyro Bias Model [C] +///@defgroup filter_gyro_bias_model_c (0x0D,0x1D) Gyro Bias Model /// Gyroscope Bias Model Parameters /// /// Noise values must be greater than 0.0 @@ -1124,7 +1124,7 @@ mip_cmd_result mip_filter_default_gyro_bias_model(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_altitude_aiding (0x0D,0x47) Altitude Aiding [C] +///@defgroup filter_altitude_aiding_c (0x0D,0x47) Altitude Aiding /// Select altitude input for absolute altitude and/or vertical velocity. The primary altitude reading is always GNSS. /// Aiding inputs are used to improve GNSS altitude readings when GNSS is available and to backup GNSS during outages. /// @@ -1180,7 +1180,7 @@ mip_cmd_result mip_filter_default_altitude_aiding(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_pitch_roll_aiding (0x0D,0x4B) Pitch Roll Aiding [C] +///@defgroup filter_pitch_roll_aiding_c (0x0D,0x4B) Pitch Roll Aiding /// Select pitch/roll aiding input. Pitch/roll reading is always derived from GNSS corrected inertial solution. /// Aiding inputs are used to improve that solution during periods of low dynamics and GNSS outages. /// @@ -1233,7 +1233,7 @@ mip_cmd_result mip_filter_default_pitch_roll_aiding(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_auto_zupt (0x0D,0x1E) Auto Zupt [C] +///@defgroup filter_auto_zupt_c (0x0D,0x1E) Auto Zupt /// The ZUPT is triggered when the scalar magnitude of the GNSS reported velocity vector is equal-to or less than the threshold value. /// The device will NACK threshold values that are less than zero (i.e.negative.) /// @@ -1269,7 +1269,7 @@ mip_cmd_result mip_filter_default_auto_zupt(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_auto_angular_zupt (0x0D,0x20) Auto Angular Zupt [C] +///@defgroup filter_auto_angular_zupt_c (0x0D,0x20) Auto Angular Zupt /// Zero Angular Rate Update /// The ZUPT is triggered when the scalar magnitude of the angular rate vector is equal-to or less than the threshold value. /// The device will NACK threshold values that are less than zero (i.e.negative.) @@ -1306,7 +1306,7 @@ mip_cmd_result mip_filter_default_auto_angular_zupt(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_commanded_zupt (0x0D,0x22) Commanded Zupt [C] +///@defgroup filter_commanded_zupt_c (0x0D,0x22) Commanded Zupt /// Please see the device user manual for the maximum rate of this message. /// ///@{ @@ -1318,7 +1318,7 @@ mip_cmd_result mip_filter_commanded_zupt(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_commanded_angular_zupt (0x0D,0x23) Commanded Angular Zupt [C] +///@defgroup filter_commanded_angular_zupt_c (0x0D,0x23) Commanded Angular Zupt /// Please see the device user manual for the maximum rate of this message. /// ///@{ @@ -1330,7 +1330,7 @@ mip_cmd_result mip_filter_commanded_angular_zupt(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_mag_capture_auto_cal (0x0D,0x27) Mag Capture Auto Cal [C] +///@defgroup filter_mag_capture_auto_cal_c (0x0D,0x27) Mag Capture Auto Cal /// This command captures the current value of the auto-calibration, applies it to the current fixed hard and soft iron calibration coefficients, and replaces the current fixed hard and soft iron calibration coefficients with the new values. /// This may be used in place of (or in addition to) a manual hard and soft iron calibration utility. This command also resets the auto-calibration coefficients. /// Function selector SAVE is the same as issuing the 0x0C, 0x3A and 0x0C, 0x3B commands with the SAVE function selector. @@ -1352,7 +1352,7 @@ mip_cmd_result mip_filter_save_mag_capture_auto_cal(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gravity_noise (0x0D,0x28) Gravity Noise [C] +///@defgroup filter_gravity_noise_c (0x0D,0x28) Gravity Noise /// Set the expected gravity noise 1-sigma values. This function can be used to tune the filter performance in the target application. /// /// Note: Noise values must be greater than 0.0 @@ -1390,7 +1390,7 @@ mip_cmd_result mip_filter_default_gravity_noise(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_pressure_altitude_noise (0x0D,0x29) Pressure Altitude Noise [C] +///@defgroup filter_pressure_altitude_noise_c (0x0D,0x29) Pressure Altitude Noise /// Set the expected pressure altitude noise 1-sigma values. This function can be used to tune the filter performance in the target application. /// /// The noise value must be greater than 0.0 @@ -1428,7 +1428,7 @@ mip_cmd_result mip_filter_default_pressure_altitude_noise(mip_interface* device) ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_hard_iron_offset_noise (0x0D,0x2B) Hard Iron Offset Noise [C] +///@defgroup filter_hard_iron_offset_noise_c (0x0D,0x2B) Hard Iron Offset Noise /// Set the expected hard iron offset noise 1-sigma values. This function can be used to tune the filter performance in the target application. /// /// This function can be used to tune the filter performance in the target application. @@ -1468,7 +1468,7 @@ mip_cmd_result mip_filter_default_hard_iron_offset_noise(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_soft_iron_matrix_noise (0x0D,0x2C) Soft Iron Matrix Noise [C] +///@defgroup filter_soft_iron_matrix_noise_c (0x0D,0x2C) Soft Iron Matrix Noise /// Set the expected soft iron matrix noise 1-sigma values. /// This function can be used to tune the filter performance in the target application. /// @@ -1507,7 +1507,7 @@ mip_cmd_result mip_filter_default_soft_iron_matrix_noise(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_mag_noise (0x0D,0x42) Mag Noise [C] +///@defgroup filter_mag_noise_c (0x0D,0x42) Mag Noise /// Set the expected magnetometer noise 1-sigma values. /// This function can be used to tune the filter performance in the target application. /// @@ -1546,7 +1546,7 @@ mip_cmd_result mip_filter_default_mag_noise(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_inclination_source (0x0D,0x4C) Inclination Source [C] +///@defgroup filter_inclination_source_c (0x0D,0x4C) Inclination Source /// Set/Get the local magnetic field inclination angle source. /// /// This can be used to correct for the local value of inclination (dip angle) of the earthmagnetic field. @@ -1585,7 +1585,7 @@ mip_cmd_result mip_filter_default_inclination_source(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_magnetic_declination_source (0x0D,0x43) Magnetic Declination Source [C] +///@defgroup filter_magnetic_declination_source_c (0x0D,0x43) Magnetic Declination Source /// Set/Get the local magnetic field declination angle source. /// /// This can be used to correct for the local value of declination of the earthmagnetic field. @@ -1624,7 +1624,7 @@ mip_cmd_result mip_filter_default_magnetic_declination_source(mip_interface* dev ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_mag_field_magnitude_source (0x0D,0x4D) Mag Field Magnitude Source [C] +///@defgroup filter_mag_field_magnitude_source_c (0x0D,0x4D) Mag Field Magnitude Source /// Set/Get the local magnetic field magnitude source. /// /// This is used to specify the local magnitude of the earth's magnetic field. @@ -1662,7 +1662,7 @@ mip_cmd_result mip_filter_default_mag_field_magnitude_source(mip_interface* devi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_reference_position (0x0D,0x26) Reference Position [C] +///@defgroup filter_reference_position_c (0x0D,0x26) Reference Position /// Set the Lat/Long/Alt reference position for the sensor. /// /// This position is used by the sensor to calculate the WGS84 gravity and WMM2015 magnetic field parameters. @@ -1704,7 +1704,7 @@ mip_cmd_result mip_filter_default_reference_position(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_accel_magnitude_error_adaptive_measurement (0x0D,0x44) Accel Magnitude Error Adaptive Measurement [C] +///@defgroup filter_accel_magnitude_error_adaptive_measurement_c (0x0D,0x44) Accel Magnitude Error Adaptive Measurement /// Enable or disable the gravity magnitude error adaptive measurement. /// This function can be used to tune the filter performance in the target application /// @@ -1762,7 +1762,7 @@ mip_cmd_result mip_filter_default_accel_magnitude_error_adaptive_measurement(mip ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_mag_magnitude_error_adaptive_measurement (0x0D,0x45) Mag Magnitude Error Adaptive Measurement [C] +///@defgroup filter_mag_magnitude_error_adaptive_measurement_c (0x0D,0x45) Mag Magnitude Error Adaptive Measurement /// Enable or disable the magnetometer magnitude error adaptive measurement. /// This feature will reject magnetometer readings that are out of range of the thresholds specified (fixed adaptive) or calculated internally (auto-adaptive). /// @@ -1815,7 +1815,7 @@ mip_cmd_result mip_filter_default_mag_magnitude_error_adaptive_measurement(mip_i ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_mag_dip_angle_error_adaptive_measurement (0x0D,0x46) Mag Dip Angle Error Adaptive Measurement [C] +///@defgroup filter_mag_dip_angle_error_adaptive_measurement_c (0x0D,0x46) Mag Dip Angle Error Adaptive Measurement /// Enable or disable the magnetometer dip angle error adaptive measurement. /// This function can be used to tune the filter performance in the target application /// @@ -1866,7 +1866,7 @@ mip_cmd_result mip_filter_default_mag_dip_angle_error_adaptive_measurement(mip_i ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_aiding_measurement_enable (0x0D,0x50) Aiding Measurement Enable [C] +///@defgroup filter_aiding_measurement_enable_c (0x0D,0x50) Aiding Measurement Enable /// Enables / disables the specified aiding measurement source. /// /// @@ -1930,7 +1930,7 @@ mip_cmd_result mip_filter_default_aiding_measurement_enable(mip_interface* devic ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_run (0x0D,0x05) Run [C] +///@defgroup filter_run_c (0x0D,0x05) Run /// Manual run command. /// /// If the initialization configuration has the "wait_for_run_command" option enabled, the filter will wait until it receives this command before commencing integration and enabling the Kalman filter. Prior to the receipt of this command, the filter will remain in the filter initialization mode. @@ -1944,7 +1944,7 @@ mip_cmd_result mip_filter_run(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_kinematic_constraint (0x0D,0x51) Kinematic Constraint [C] +///@defgroup filter_kinematic_constraint_c (0x0D,0x51) Kinematic Constraint /// Controls kinematic constraint model selection for the navigation filter. /// /// See manual for explanation of how the kinematic constraints are applied. @@ -1983,7 +1983,7 @@ mip_cmd_result mip_filter_default_kinematic_constraint(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_initialization_configuration (0x0D,0x52) Initialization Configuration [C] +///@defgroup filter_initialization_configuration_c (0x0D,0x52) Initialization Configuration /// Controls the source and values used for initial conditions of the navigation solution. /// /// Notes: Initial conditions are the position, velocity, and attitude of the platform used when the filter starts running or is reset. @@ -2075,7 +2075,7 @@ mip_cmd_result mip_filter_default_initialization_configuration(mip_interface* de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_adaptive_filter_options (0x0D,0x53) Adaptive Filter Options [C] +///@defgroup filter_adaptive_filter_options_c (0x0D,0x53) Adaptive Filter Options /// Configures the basic setup for auto-adaptive filtering. See product manual for a detailed description of this feature. /// ///@{ @@ -2110,7 +2110,7 @@ mip_cmd_result mip_filter_default_adaptive_filter_options(mip_interface* device) ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_multi_antenna_offset (0x0D,0x54) Multi Antenna Offset [C] +///@defgroup filter_multi_antenna_offset_c (0x0D,0x54) Multi Antenna Offset /// Set the antenna lever arm. /// /// This command works with devices that utilize multiple antennas. @@ -2148,7 +2148,7 @@ mip_cmd_result mip_filter_default_multi_antenna_offset(mip_interface* device, ui ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_rel_pos_configuration (0x0D,0x55) Rel Pos Configuration [C] +///@defgroup filter_rel_pos_configuration_c (0x0D,0x55) Rel Pos Configuration /// Configure the reference location for filter relative positioning outputs /// ///@{ @@ -2185,7 +2185,7 @@ mip_cmd_result mip_filter_default_rel_pos_configuration(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_ref_point_lever_arm (0x0D,0x56) Ref Point Lever Arm [C] +///@defgroup filter_ref_point_lever_arm_c (0x0D,0x56) Ref Point Lever Arm /// Lever arm offset with respect to the sensor for the indicated point of reference. /// This is used to change the location of the indicated point of reference, and will affect filter position and velocity outputs. /// Changing this setting from default will result in a global position offset that depends on vehicle attitude, @@ -2245,7 +2245,7 @@ mip_cmd_result mip_filter_default_ref_point_lever_arm(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_speed_measurement (0x0D,0x60) Speed Measurement [C] +///@defgroup filter_speed_measurement_c (0x0D,0x60) Speed Measurement /// Speed aiding measurement, where speed is defined as rate of motion along the vehicle's x-axis direction. /// Can be used by an external odometer/speedometer, for example. /// This command cannot be used if the internal odometer is configured. @@ -2269,7 +2269,7 @@ mip_cmd_result mip_filter_speed_measurement(mip_interface* device, uint8_t sourc ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_speed_lever_arm (0x0D,0x61) Speed Lever Arm [C] +///@defgroup filter_speed_lever_arm_c (0x0D,0x61) Speed Lever Arm /// Lever arm offset for speed measurements. /// This is used to compensate for an off-center measurement point /// having a different speed due to rotation of the vehicle. @@ -2310,7 +2310,7 @@ mip_cmd_result mip_filter_default_speed_lever_arm(mip_interface* device, uint8_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_wheeled_vehicle_constraint_control (0x0D,0x63) Wheeled Vehicle Constraint Control [C] +///@defgroup filter_wheeled_vehicle_constraint_control_c (0x0D,0x63) Wheeled Vehicle Constraint Control /// Configure the wheeled vehicle kinematic constraint. /// /// When enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis. @@ -2349,7 +2349,7 @@ mip_cmd_result mip_filter_default_wheeled_vehicle_constraint_control(mip_interfa ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_vertical_gyro_constraint_control (0x0D,0x62) Vertical Gyro Constraint Control [C] +///@defgroup filter_vertical_gyro_constraint_control_c (0x0D,0x62) Vertical Gyro Constraint Control /// Configure the vertical gyro kinematic constraint. /// /// When enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track pitch @@ -2386,7 +2386,7 @@ mip_cmd_result mip_filter_default_vertical_gyro_constraint_control(mip_interface ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gnss_antenna_cal_control (0x0D,0x64) Gnss Antenna Cal Control [C] +///@defgroup filter_gnss_antenna_cal_control_c (0x0D,0x64) Gnss Antenna Cal Control /// Configure the GNSS antenna lever arm calibration. /// /// When enabled, the filter will enable lever arm error tracking, up to the maximum offset specified. @@ -2423,7 +2423,7 @@ mip_cmd_result mip_filter_default_gnss_antenna_cal_control(mip_interface* device ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_set_initial_heading (0x0D,0x03) Set Initial Heading [C] +///@defgroup filter_set_initial_heading_c (0x0D,0x03) Set Initial Heading /// Set the initial heading angle. /// /// The estimation filter will reset the heading estimate to provided value. If the product supports magnetometer aiding and this feature has been enabled, the heading diff --git a/src/c/mip/definitions/commands_gnss.h b/src/c/mip/definitions/commands_gnss.h index 4a26cf700..46c37ab66 100644 --- a/src/c/mip/definitions/commands_gnss.h +++ b/src/c/mip/definitions/commands_gnss.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_c MIP Commands [C] +///@addtogroup MipCommands_c ///@{ -///@defgroup gnss_commands_c Gnss Commands [C] +///@defgroup gnss_commands_c Gnss Commands /// ///@{ @@ -61,7 +61,7 @@ enum { MIP_GNSS_BEIDOU_ENABLE_B2A = 0x0004 }; //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_receiver_info (0x0E,0x01) Receiver Info [C] +///@defgroup gnss_receiver_info_c (0x0E,0x01) Receiver Info /// Return information about the GNSS receivers in the device. /// /// @@ -96,7 +96,7 @@ mip_cmd_result mip_gnss_receiver_info(mip_interface* device, uint8_t* num_receiv ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_signal_configuration (0x0E,0x02) Signal Configuration [C] +///@defgroup gnss_signal_configuration_c (0x0E,0x02) Signal Configuration /// Configure the GNSS signals used by the device. /// /// @@ -138,7 +138,7 @@ mip_cmd_result mip_gnss_default_signal_configuration(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_rtk_dongle_configuration (0x0E,0x10) Rtk Dongle Configuration [C] +///@defgroup gnss_rtk_dongle_configuration_c (0x0E,0x10) Rtk Dongle Configuration /// Configure the communications with the RTK Dongle connected to the device. /// /// diff --git a/src/c/mip/definitions/commands_rtk.h b/src/c/mip/definitions/commands_rtk.h index bd800f5b6..b94731c9f 100644 --- a/src/c/mip/definitions/commands_rtk.h +++ b/src/c/mip/definitions/commands_rtk.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_c MIP Commands [C] +///@addtogroup MipCommands_c ///@{ -///@defgroup rtk_commands_c Rtk Commands [C] +///@defgroup rtk_commands_c Rtk Commands /// ///@{ @@ -102,7 +102,7 @@ static inline void extract_mip_led_action(microstrain_serializer* serializer, mi //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_get_status_flags (0x0F,0x01) Get Status Flags [C] +///@defgroup rtk_get_status_flags_c (0x0F,0x01) Get Status Flags /// ///@{ @@ -174,7 +174,7 @@ mip_cmd_result mip_rtk_get_status_flags(mip_interface* device, mip_rtk_get_statu ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_get_imei (0x0F,0x02) Get Imei [C] +///@defgroup rtk_get_imei_c (0x0F,0x02) Get Imei /// ///@{ @@ -194,7 +194,7 @@ mip_cmd_result mip_rtk_get_imei(mip_interface* device, char* imei_out); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_get_imsi (0x0F,0x03) Get Imsi [C] +///@defgroup rtk_get_imsi_c (0x0F,0x03) Get Imsi /// ///@{ @@ -214,7 +214,7 @@ mip_cmd_result mip_rtk_get_imsi(mip_interface* device, char* imsi_out); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_get_iccid (0x0F,0x04) Get Iccid [C] +///@defgroup rtk_get_iccid_c (0x0F,0x04) Get Iccid /// ///@{ @@ -234,7 +234,7 @@ mip_cmd_result mip_rtk_get_iccid(mip_interface* device, char* iccid_out); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_connected_device_type (0x0F,0x06) Connected Device Type [C] +///@defgroup rtk_connected_device_type_c (0x0F,0x06) Connected Device Type /// ///@{ @@ -285,7 +285,7 @@ mip_cmd_result mip_rtk_default_connected_device_type(mip_interface* device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_get_act_code (0x0F,0x07) Get Act Code [C] +///@defgroup rtk_get_act_code_c (0x0F,0x07) Get Act Code /// ///@{ @@ -305,7 +305,7 @@ mip_cmd_result mip_rtk_get_act_code(mip_interface* device, char* activation_code ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_get_modem_firmware_version (0x0F,0x08) Get Modem Firmware Version [C] +///@defgroup rtk_get_modem_firmware_version_c (0x0F,0x08) Get Modem Firmware Version /// ///@{ @@ -325,7 +325,7 @@ mip_cmd_result mip_rtk_get_modem_firmware_version(mip_interface* device, char* m ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_get_rssi (0x0F,0x05) Get Rssi [C] +///@defgroup rtk_get_rssi_c (0x0F,0x05) Get Rssi /// Get the RSSI and connected/disconnected status of modem /// ///@{ @@ -348,7 +348,7 @@ mip_cmd_result mip_rtk_get_rssi(mip_interface* device, bool* valid_out, int32_t* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_service_status (0x0F,0x0A) Service Status [C] +///@defgroup rtk_service_status_c (0x0F,0x0A) Service Status /// The 3DMRTK will send this message to the server to indicate that the connection should remain open. The Server will respond with information and status. /// ///@{ @@ -398,7 +398,7 @@ mip_cmd_result mip_rtk_service_status(mip_interface* device, uint32_t reserved1, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_prod_erase_storage (0x0F,0x20) Prod Erase Storage [C] +///@defgroup rtk_prod_erase_storage_c (0x0F,0x20) Prod Erase Storage /// This command will erase the selected media to a raw and uninitialized state. ALL DATA WILL BE LOST. /// This command is only available in calibration mode. /// @@ -418,7 +418,7 @@ mip_cmd_result mip_rtk_prod_erase_storage(mip_interface* device, mip_media_selec ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_led_control (0x0F,0x21) Led Control [C] +///@defgroup rtk_led_control_c (0x0F,0x21) Led Control /// This command allows direct control of the LED on the 3DM RTK. This command is only available in calibration mode or Production Test Mode. /// ///@{ @@ -440,7 +440,7 @@ mip_cmd_result mip_rtk_led_control(mip_interface* device, const uint8_t* primary ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_rtk_modem_hard_reset (0x0F,0x22) Modem Hard Reset [C] +///@defgroup rtk_modem_hard_reset_c (0x0F,0x22) Modem Hard Reset /// This command will clear the modem flash. THIS MUST NOT BE DONE OFTEN AS IT CAN DAMAGE THE FLASH! /// This command is only available in calibration mode. /// diff --git a/src/c/mip/definitions/commands_system.h b/src/c/mip/definitions/commands_system.h index 915764830..1a44b7c67 100644 --- a/src/c/mip/definitions/commands_system.h +++ b/src/c/mip/definitions/commands_system.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_c MIP Commands [C] +///@addtogroup MipCommands_c ///@{ -///@defgroup system_commands_c System Commands [C] +///@defgroup system_commands_c System Commands /// ///@{ @@ -55,7 +55,7 @@ enum { MIP_SYSTEM_COMMAND_COMM_MODE_GPS = 0x03 }; //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_system_comm_mode (0x7F,0x10) Comm Mode [C] +///@defgroup system_comm_mode_c (0x7F,0x10) Comm Mode /// Advanced specialized communication modes. /// /// This command allows the user to communicate directly with various subsystems which may be present in MIP devices (i.e. IMU, GNSS, etc.) diff --git a/src/c/mip/definitions/common.h b/src/c/mip/definitions/common.h index 04a7c3e40..d86fc392f 100644 --- a/src/c/mip/definitions/common.h +++ b/src/c/mip/definitions/common.h @@ -1,5 +1,18 @@ #pragma once +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_c +///@{ +/// +///@defgroup MipCommands_c Mip Commands +///@brief Contains all MIP command definitions. +/// +///@defgroup MipData_c Mip Data +///@brief Contains all MIP data definitions. +/// +///@} +//////////////////////////////////////////////////////////////////////////////// + #include #include "../mip_field.h" diff --git a/src/c/mip/definitions/data_filter.h b/src/c/mip/definitions/data_filter.h index b88f2345c..f88b95b96 100644 --- a/src/c/mip/definitions/data_filter.h +++ b/src/c/mip/definitions/data_filter.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_c MIP Data [C] +///@addtogroup MipData_c ///@{ -///@defgroup filter_data_c Filter Data [C] +///@defgroup filter_data_c Filter Data /// ///@{ @@ -273,7 +273,7 @@ static inline void extract_mip_gnss_aid_status_flags(microstrain_serializer* ser //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_position_llh (0x82,0x01) Position Llh [C] +///@defgroup filter_position_llh_c (0x82,0x01) Position Llh /// Filter reported position in the WGS84 geodetic frame. /// ///@{ @@ -295,7 +295,7 @@ bool extract_mip_filter_position_llh_data_from_field(const mip_field_view* field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_velocity_ned (0x82,0x02) Velocity Ned [C] +///@defgroup filter_velocity_ned_c (0x82,0x02) Velocity Ned /// Filter reported velocity in the NED local-level frame. /// ///@{ @@ -317,7 +317,7 @@ bool extract_mip_filter_velocity_ned_data_from_field(const mip_field_view* field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_attitude_quaternion (0x82,0x03) Attitude Quaternion [C] +///@defgroup filter_attitude_quaternion_c (0x82,0x03) Attitude Quaternion /// 4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame. /// This quaternion satisfies the following relationship: /// @@ -345,7 +345,7 @@ bool extract_mip_filter_attitude_quaternion_data_from_field(const mip_field_view ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_attitude_dcm (0x82,0x04) Attitude Dcm [C] +///@defgroup filter_attitude_dcm_c (0x82,0x04) Attitude Dcm /// 3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame. /// This matrix satisfies the following relationship: /// @@ -375,7 +375,7 @@ bool extract_mip_filter_attitude_dcm_data_from_field(const mip_field_view* field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_euler_angles (0x82,0x05) Euler Angles [C] +///@defgroup filter_euler_angles_c (0x82,0x05) Euler Angles /// Filter reported Euler angles describing the orientation of the device with respect to the NED local-level frame. /// The Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order. /// @@ -398,7 +398,7 @@ bool extract_mip_filter_euler_angles_data_from_field(const mip_field_view* field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gyro_bias (0x82,0x06) Gyro Bias [C] +///@defgroup filter_gyro_bias_c (0x82,0x06) Gyro Bias /// Filter reported gyro bias expressed in the sensor frame. /// ///@{ @@ -418,7 +418,7 @@ bool extract_mip_filter_gyro_bias_data_from_field(const mip_field_view* field, v ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_accel_bias (0x82,0x07) Accel Bias [C] +///@defgroup filter_accel_bias_c (0x82,0x07) Accel Bias /// Filter reported accelerometer bias expressed in the sensor frame. /// ///@{ @@ -438,7 +438,7 @@ bool extract_mip_filter_accel_bias_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_position_llh_uncertainty (0x82,0x08) Position Llh Uncertainty [C] +///@defgroup filter_position_llh_uncertainty_c (0x82,0x08) Position Llh Uncertainty /// Filter reported 1-sigma position uncertainty in the NED local-level frame. /// ///@{ @@ -460,7 +460,7 @@ bool extract_mip_filter_position_llh_uncertainty_data_from_field(const mip_field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_velocity_ned_uncertainty (0x82,0x09) Velocity Ned Uncertainty [C] +///@defgroup filter_velocity_ned_uncertainty_c (0x82,0x09) Velocity Ned Uncertainty /// Filter reported 1-sigma velocity uncertainties in the NED local-level frame. /// ///@{ @@ -482,7 +482,7 @@ bool extract_mip_filter_velocity_ned_uncertainty_data_from_field(const mip_field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_euler_angles_uncertainty (0x82,0x0A) Euler Angles Uncertainty [C] +///@defgroup filter_euler_angles_uncertainty_c (0x82,0x0A) Euler Angles Uncertainty /// Filter reported 1-sigma Euler angle uncertainties. /// The uncertainties are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order. /// @@ -505,7 +505,7 @@ bool extract_mip_filter_euler_angles_uncertainty_data_from_field(const mip_field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gyro_bias_uncertainty (0x82,0x0B) Gyro Bias Uncertainty [C] +///@defgroup filter_gyro_bias_uncertainty_c (0x82,0x0B) Gyro Bias Uncertainty /// Filter reported 1-sigma gyro bias uncertainties expressed in the sensor frame. /// ///@{ @@ -525,7 +525,7 @@ bool extract_mip_filter_gyro_bias_uncertainty_data_from_field(const mip_field_vi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_accel_bias_uncertainty (0x82,0x0C) Accel Bias Uncertainty [C] +///@defgroup filter_accel_bias_uncertainty_c (0x82,0x0C) Accel Bias Uncertainty /// Filter reported 1-sigma accelerometer bias uncertainties expressed in the sensor frame. /// ///@{ @@ -545,7 +545,7 @@ bool extract_mip_filter_accel_bias_uncertainty_data_from_field(const mip_field_v ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_timestamp (0x82,0x11) Timestamp [C] +///@defgroup filter_timestamp_c (0x82,0x11) Timestamp /// GPS timestamp of the Filter data /// /// Should the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time. @@ -572,7 +572,7 @@ bool extract_mip_filter_timestamp_data_from_field(const mip_field_view* field, v ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_status (0x82,0x10) Status [C] +///@defgroup filter_status_c (0x82,0x10) Status /// Device-specific filter status indicators. /// ///@{ @@ -593,7 +593,7 @@ bool extract_mip_filter_status_data_from_field(const mip_field_view* field, void ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_linear_accel (0x82,0x0D) Linear Accel [C] +///@defgroup filter_linear_accel_c (0x82,0x0D) Linear Accel /// Filter-compensated linear acceleration expressed in the vehicle frame. /// Note: The estimated gravity has been removed from this data leaving only linear acceleration. /// @@ -614,7 +614,7 @@ bool extract_mip_filter_linear_accel_data_from_field(const mip_field_view* field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gravity_vector (0x82,0x13) Gravity Vector [C] +///@defgroup filter_gravity_vector_c (0x82,0x13) Gravity Vector /// Filter reported gravity vector expressed in the vehicle frame. /// ///@{ @@ -634,7 +634,7 @@ bool extract_mip_filter_gravity_vector_data_from_field(const mip_field_view* fie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_comp_accel (0x82,0x1C) Comp Accel [C] +///@defgroup filter_comp_accel_c (0x82,0x1C) Comp Accel /// Filter-compensated acceleration expressed in the vehicle frame. /// ///@{ @@ -654,7 +654,7 @@ bool extract_mip_filter_comp_accel_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_comp_angular_rate (0x82,0x0E) Comp Angular Rate [C] +///@defgroup filter_comp_angular_rate_c (0x82,0x0E) Comp Angular Rate /// Filter-compensated angular rate expressed in the vehicle frame. /// ///@{ @@ -674,7 +674,7 @@ bool extract_mip_filter_comp_angular_rate_data_from_field(const mip_field_view* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_quaternion_attitude_uncertainty (0x82,0x12) Quaternion Attitude Uncertainty [C] +///@defgroup filter_quaternion_attitude_uncertainty_c (0x82,0x12) Quaternion Attitude Uncertainty /// Filter reported quaternion uncertainties. /// ///@{ @@ -694,7 +694,7 @@ bool extract_mip_filter_quaternion_attitude_uncertainty_data_from_field(const mi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_wgs84_gravity_mag (0x82,0x0F) Wgs84 Gravity Mag [C] +///@defgroup filter_wgs84_gravity_mag_c (0x82,0x0F) Wgs84 Gravity Mag /// Filter reported WGS84 gravity magnitude. /// ///@{ @@ -714,7 +714,7 @@ bool extract_mip_filter_wgs84_gravity_mag_data_from_field(const mip_field_view* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_heading_update_state (0x82,0x14) Heading Update State [C] +///@defgroup filter_heading_update_state_c (0x82,0x14) Heading Update State /// Filter reported heading update state. /// /// Heading updates can be applied from the sources listed below. Note, some of these sources may be combined. @@ -761,7 +761,7 @@ bool extract_mip_filter_heading_update_state_data_from_field(const mip_field_vie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_magnetic_model (0x82,0x15) Magnetic Model [C] +///@defgroup filter_magnetic_model_c (0x82,0x15) Magnetic Model /// The World Magnetic Model is used for this data. Please refer to the device user manual for the current version of the model. /// A valid GNSS location is required for the model to be valid. /// @@ -786,7 +786,7 @@ bool extract_mip_filter_magnetic_model_data_from_field(const mip_field_view* fie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_accel_scale_factor (0x82,0x17) Accel Scale Factor [C] +///@defgroup filter_accel_scale_factor_c (0x82,0x17) Accel Scale Factor /// Filter reported accelerometer scale factor expressed in the sensor frame. /// ///@{ @@ -806,7 +806,7 @@ bool extract_mip_filter_accel_scale_factor_data_from_field(const mip_field_view* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_accel_scale_factor_uncertainty (0x82,0x19) Accel Scale Factor Uncertainty [C] +///@defgroup filter_accel_scale_factor_uncertainty_c (0x82,0x19) Accel Scale Factor Uncertainty /// Filter reported 1-sigma accelerometer scale factor uncertainty expressed in the sensor frame. /// ///@{ @@ -826,7 +826,7 @@ bool extract_mip_filter_accel_scale_factor_uncertainty_data_from_field(const mip ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gyro_scale_factor (0x82,0x16) Gyro Scale Factor [C] +///@defgroup filter_gyro_scale_factor_c (0x82,0x16) Gyro Scale Factor /// Filter reported gyro scale factor expressed in the sensor frame. /// ///@{ @@ -846,7 +846,7 @@ bool extract_mip_filter_gyro_scale_factor_data_from_field(const mip_field_view* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gyro_scale_factor_uncertainty (0x82,0x18) Gyro Scale Factor Uncertainty [C] +///@defgroup filter_gyro_scale_factor_uncertainty_c (0x82,0x18) Gyro Scale Factor Uncertainty /// Filter reported 1-sigma gyro scale factor uncertainty expressed in the sensor frame. /// ///@{ @@ -866,7 +866,7 @@ bool extract_mip_filter_gyro_scale_factor_uncertainty_data_from_field(const mip_ ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_mag_bias (0x82,0x1A) Mag Bias [C] +///@defgroup filter_mag_bias_c (0x82,0x1A) Mag Bias /// Filter reported magnetometer bias expressed in the sensor frame. /// ///@{ @@ -886,7 +886,7 @@ bool extract_mip_filter_mag_bias_data_from_field(const mip_field_view* field, vo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_mag_bias_uncertainty (0x82,0x1B) Mag Bias Uncertainty [C] +///@defgroup filter_mag_bias_uncertainty_c (0x82,0x1B) Mag Bias Uncertainty /// Filter reported 1-sigma magnetometer bias uncertainty expressed in the sensor frame. /// ///@{ @@ -906,7 +906,7 @@ bool extract_mip_filter_mag_bias_uncertainty_data_from_field(const mip_field_vie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_standard_atmosphere (0x82,0x20) Standard Atmosphere [C] +///@defgroup filter_standard_atmosphere_c (0x82,0x20) Standard Atmosphere /// Filter reported standard atmosphere parameters. /// /// The US 1976 Standard Atmosphere Model is used. A valid GNSS location is required for the model to be valid. @@ -932,7 +932,7 @@ bool extract_mip_filter_standard_atmosphere_data_from_field(const mip_field_view ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_pressure_altitude (0x82,0x21) Pressure Altitude [C] +///@defgroup filter_pressure_altitude_c (0x82,0x21) Pressure Altitude /// Filter reported pressure altitude. /// /// The US 1976 Standard Atmosphere Model is used to calculate the pressure altitude in meters. @@ -956,7 +956,7 @@ bool extract_mip_filter_pressure_altitude_data_from_field(const mip_field_view* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_density_altitude (0x82,0x22) Density Altitude [C] +///@defgroup filter_density_altitude_c (0x82,0x22) Density Altitude /// ///@{ @@ -975,7 +975,7 @@ bool extract_mip_filter_density_altitude_data_from_field(const mip_field_view* f ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_antenna_offset_correction (0x82,0x30) Antenna Offset Correction [C] +///@defgroup filter_antenna_offset_correction_c (0x82,0x30) Antenna Offset Correction /// Filter reported GNSS antenna offset in vehicle frame. /// /// This offset added to any previously stored offset vector to compensate for errors in definition. @@ -997,7 +997,7 @@ bool extract_mip_filter_antenna_offset_correction_data_from_field(const mip_fiel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_antenna_offset_correction_uncertainty (0x82,0x31) Antenna Offset Correction Uncertainty [C] +///@defgroup filter_antenna_offset_correction_uncertainty_c (0x82,0x31) Antenna Offset Correction Uncertainty /// Filter reported 1-sigma GNSS antenna offset uncertainties in vehicle frame. /// ///@{ @@ -1017,7 +1017,7 @@ bool extract_mip_filter_antenna_offset_correction_uncertainty_data_from_field(co ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_multi_antenna_offset_correction (0x82,0x34) Multi Antenna Offset Correction [C] +///@defgroup filter_multi_antenna_offset_correction_c (0x82,0x34) Multi Antenna Offset Correction /// Filter reported GNSS antenna offset in vehicle frame. /// /// This offset added to any previously stored offset vector to compensate for errors in definition. @@ -1040,7 +1040,7 @@ bool extract_mip_filter_multi_antenna_offset_correction_data_from_field(const mi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_multi_antenna_offset_correction_uncertainty (0x82,0x35) Multi Antenna Offset Correction Uncertainty [C] +///@defgroup filter_multi_antenna_offset_correction_uncertainty_c (0x82,0x35) Multi Antenna Offset Correction Uncertainty /// Filter reported 1-sigma GNSS antenna offset uncertainties in vehicle frame. /// ///@{ @@ -1061,7 +1061,7 @@ bool extract_mip_filter_multi_antenna_offset_correction_uncertainty_data_from_fi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_magnetometer_offset (0x82,0x25) Magnetometer Offset [C] +///@defgroup filter_magnetometer_offset_c (0x82,0x25) Magnetometer Offset /// Filter reported magnetometer hard iron offset in sensor frame. /// /// This offset added to any previously stored hard iron offset vector to compensate for magnetometer in-run bias errors. @@ -1083,7 +1083,7 @@ bool extract_mip_filter_magnetometer_offset_data_from_field(const mip_field_view ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_magnetometer_matrix (0x82,0x26) Magnetometer Matrix [C] +///@defgroup filter_magnetometer_matrix_c (0x82,0x26) Magnetometer Matrix /// Filter reported magnetometer soft iron matrix in sensor frame. /// /// This matrix is post multiplied to any previously stored soft iron matrix to compensate for magnetometer in-run errors. @@ -1105,7 +1105,7 @@ bool extract_mip_filter_magnetometer_matrix_data_from_field(const mip_field_view ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_magnetometer_offset_uncertainty (0x82,0x28) Magnetometer Offset Uncertainty [C] +///@defgroup filter_magnetometer_offset_uncertainty_c (0x82,0x28) Magnetometer Offset Uncertainty /// Filter reported 1-sigma magnetometer hard iron offset uncertainties in sensor frame. /// ///@{ @@ -1125,7 +1125,7 @@ bool extract_mip_filter_magnetometer_offset_uncertainty_data_from_field(const mi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_magnetometer_matrix_uncertainty (0x82,0x29) Magnetometer Matrix Uncertainty [C] +///@defgroup filter_magnetometer_matrix_uncertainty_c (0x82,0x29) Magnetometer Matrix Uncertainty /// Filter reported 1-sigma magnetometer soft iron matrix uncertainties in sensor frame. /// ///@{ @@ -1145,7 +1145,7 @@ bool extract_mip_filter_magnetometer_matrix_uncertainty_data_from_field(const mi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_magnetometer_covariance_matrix (0x82,0x2A) Magnetometer Covariance Matrix [C] +///@defgroup filter_magnetometer_covariance_matrix_c (0x82,0x2A) Magnetometer Covariance Matrix /// ///@{ @@ -1164,7 +1164,7 @@ bool extract_mip_filter_magnetometer_covariance_matrix_data_from_field(const mip ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_magnetometer_residual_vector (0x82,0x2C) Magnetometer Residual Vector [C] +///@defgroup filter_magnetometer_residual_vector_c (0x82,0x2C) Magnetometer Residual Vector /// Filter reported magnetometer measurement residuals in vehicle frame. /// ///@{ @@ -1184,7 +1184,7 @@ bool extract_mip_filter_magnetometer_residual_vector_data_from_field(const mip_f ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_clock_correction (0x82,0x32) Clock Correction [C] +///@defgroup filter_clock_correction_c (0x82,0x32) Clock Correction /// Filter reported GNSS receiver clock error parameters. /// ///@{ @@ -1206,7 +1206,7 @@ bool extract_mip_filter_clock_correction_data_from_field(const mip_field_view* f ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_clock_correction_uncertainty (0x82,0x33) Clock Correction Uncertainty [C] +///@defgroup filter_clock_correction_uncertainty_c (0x82,0x33) Clock Correction Uncertainty /// Filter reported 1-sigma GNSS receiver clock error parameters. /// ///@{ @@ -1228,7 +1228,7 @@ bool extract_mip_filter_clock_correction_uncertainty_data_from_field(const mip_f ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gnss_pos_aid_status (0x82,0x43) Gnss Pos Aid Status [C] +///@defgroup filter_gnss_pos_aid_status_c (0x82,0x43) Gnss Pos Aid Status /// Filter reported GNSS position aiding status /// ///@{ @@ -1250,7 +1250,7 @@ bool extract_mip_filter_gnss_pos_aid_status_data_from_field(const mip_field_view ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gnss_att_aid_status (0x82,0x44) Gnss Att Aid Status [C] +///@defgroup filter_gnss_att_aid_status_c (0x82,0x44) Gnss Att Aid Status /// Filter reported dual antenna GNSS attitude aiding status /// ///@{ @@ -1271,7 +1271,7 @@ bool extract_mip_filter_gnss_att_aid_status_data_from_field(const mip_field_view ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_head_aid_status (0x82,0x45) Head Aid Status [C] +///@defgroup filter_head_aid_status_c (0x82,0x45) Head Aid Status /// Filter reported GNSS heading aiding status /// ///@{ @@ -1311,7 +1311,7 @@ bool extract_mip_filter_head_aid_status_data_from_field(const mip_field_view* fi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_rel_pos_ned (0x82,0x42) Rel Pos Ned [C] +///@defgroup filter_rel_pos_ned_c (0x82,0x42) Rel Pos Ned /// Filter reported relative position, with respect to configured reference position /// ///@{ @@ -1331,7 +1331,7 @@ bool extract_mip_filter_rel_pos_ned_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_ecef_pos (0x82,0x40) Ecef Pos [C] +///@defgroup filter_ecef_pos_c (0x82,0x40) Ecef Pos /// Filter reported ECEF position /// ///@{ @@ -1351,7 +1351,7 @@ bool extract_mip_filter_ecef_pos_data_from_field(const mip_field_view* field, vo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_ecef_vel (0x82,0x41) Ecef Vel [C] +///@defgroup filter_ecef_vel_c (0x82,0x41) Ecef Vel /// Filter reported ECEF velocity /// ///@{ @@ -1371,7 +1371,7 @@ bool extract_mip_filter_ecef_vel_data_from_field(const mip_field_view* field, vo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_ecef_pos_uncertainty (0x82,0x36) Ecef Pos Uncertainty [C] +///@defgroup filter_ecef_pos_uncertainty_c (0x82,0x36) Ecef Pos Uncertainty /// Filter reported 1-sigma position uncertainty in the ECEF frame. /// ///@{ @@ -1391,7 +1391,7 @@ bool extract_mip_filter_ecef_pos_uncertainty_data_from_field(const mip_field_vie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_ecef_vel_uncertainty (0x82,0x37) Ecef Vel Uncertainty [C] +///@defgroup filter_ecef_vel_uncertainty_c (0x82,0x37) Ecef Vel Uncertainty /// Filter reported 1-sigma velocity uncertainties in the ECEF frame. /// ///@{ @@ -1411,7 +1411,7 @@ bool extract_mip_filter_ecef_vel_uncertainty_data_from_field(const mip_field_vie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_aiding_measurement_summary (0x82,0x46) Aiding Measurement Summary [C] +///@defgroup filter_aiding_measurement_summary_c (0x82,0x46) Aiding Measurement Summary /// Filter reported aiding measurement summary. This message contains a summary of the specified aiding measurement over the previous measurement interval ending at the specified time. /// ///@{ @@ -1433,7 +1433,7 @@ bool extract_mip_filter_aiding_measurement_summary_data_from_field(const mip_fie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_odometer_scale_factor_error (0x82,0x47) Odometer Scale Factor Error [C] +///@defgroup filter_odometer_scale_factor_error_c (0x82,0x47) Odometer Scale Factor Error /// Filter reported odometer scale factor error. The total scale factor estimate is the user indicated scale factor, plus the user indicated scale factor times the scale factor error. /// ///@{ @@ -1453,7 +1453,7 @@ bool extract_mip_filter_odometer_scale_factor_error_data_from_field(const mip_fi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_odometer_scale_factor_error_uncertainty (0x82,0x48) Odometer Scale Factor Error Uncertainty [C] +///@defgroup filter_odometer_scale_factor_error_uncertainty_c (0x82,0x48) Odometer Scale Factor Error Uncertainty /// Filter reported odometer scale factor error uncertainty. /// ///@{ @@ -1473,7 +1473,7 @@ bool extract_mip_filter_odometer_scale_factor_error_uncertainty_data_from_field( ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_gnss_dual_antenna_status (0x82,0x49) Gnss Dual Antenna Status [C] +///@defgroup filter_gnss_dual_antenna_status_c (0x82,0x49) Gnss Dual Antenna Status /// Summary information for status of GNSS dual antenna heading estimate. /// ///@{ @@ -1534,7 +1534,7 @@ bool extract_mip_filter_gnss_dual_antenna_status_data_from_field(const mip_field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_aiding_frame_config_error (0x82,0x50) Aiding Frame Config Error [C] +///@defgroup filter_aiding_frame_config_error_c (0x82,0x50) Aiding Frame Config Error /// Filter reported aiding source frame configuration error /// /// These estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ). @@ -1557,7 +1557,7 @@ bool extract_mip_filter_aiding_frame_config_error_data_from_field(const mip_fiel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_filter_aiding_frame_config_error_uncertainty (0x82,0x51) Aiding Frame Config Error Uncertainty [C] +///@defgroup filter_aiding_frame_config_error_uncertainty_c (0x82,0x51) Aiding Frame Config Error Uncertainty /// Filter reported aiding source frame configuration error uncertainty /// /// These estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ). diff --git a/src/c/mip/definitions/data_gnss.h b/src/c/mip/definitions/data_gnss.h index 84c659db9..5dbe74ee6 100644 --- a/src/c/mip/definitions/data_gnss.h +++ b/src/c/mip/definitions/data_gnss.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_c MIP Data [C] +///@addtogroup MipData_c ///@{ -///@defgroup gnss_data_c Gnss Data [C] +///@defgroup gnss_data_c Gnss Data /// ///@{ @@ -204,7 +204,7 @@ enum { MIP_GNSS_SV_INFO_MAX_SV_NUMBER = 32 }; //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_pos_llh (0x81,0x03) Pos Llh [C] +///@defgroup gnss_pos_llh_c (0x81,0x03) Pos Llh /// GNSS reported position in the WGS84 geodetic frame /// ///@{ @@ -250,7 +250,7 @@ bool extract_mip_gnss_pos_llh_data_from_field(const mip_field_view* field, void* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_pos_ecef (0x81,0x04) Pos Ecef [C] +///@defgroup gnss_pos_ecef_c (0x81,0x04) Pos Ecef /// GNSS reported position in the Earth-centered, Earth-Fixed (ECEF) frame /// ///@{ @@ -289,7 +289,7 @@ bool extract_mip_gnss_pos_ecef_data_from_field(const mip_field_view* field, void ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_vel_ned (0x81,0x05) Vel Ned [C] +///@defgroup gnss_vel_ned_c (0x81,0x05) Vel Ned /// GNSS reported velocity in the NED frame /// ///@{ @@ -336,7 +336,7 @@ bool extract_mip_gnss_vel_ned_data_from_field(const mip_field_view* field, void* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_vel_ecef (0x81,0x06) Vel Ecef [C] +///@defgroup gnss_vel_ecef_c (0x81,0x06) Vel Ecef /// GNSS reported velocity in the Earth-centered, Earth-Fixed (ECEF) frame /// ///@{ @@ -375,7 +375,7 @@ bool extract_mip_gnss_vel_ecef_data_from_field(const mip_field_view* field, void ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_dop (0x81,0x07) Dop [C] +///@defgroup gnss_dop_c (0x81,0x07) Dop /// GNSS reported dilution of precision information. /// ///@{ @@ -424,7 +424,7 @@ bool extract_mip_gnss_dop_data_from_field(const mip_field_view* field, void* ptr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_utc_time (0x81,0x08) Utc Time [C] +///@defgroup gnss_utc_time_c (0x81,0x08) Utc Time /// GNSS reported Coordinated Universal Time /// ///@{ @@ -468,7 +468,7 @@ bool extract_mip_gnss_utc_time_data_from_field(const mip_field_view* field, void ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_gps_time (0x81,0x09) Gps Time [C] +///@defgroup gnss_gps_time_c (0x81,0x09) Gps Time /// GNSS reported GPS Time /// ///@{ @@ -507,7 +507,7 @@ bool extract_mip_gnss_gps_time_data_from_field(const mip_field_view* field, void ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_clock_info (0x81,0x0A) Clock Info [C] +///@defgroup gnss_clock_info_c (0x81,0x0A) Clock Info /// GNSS reported receiver clock parameters /// ///@{ @@ -548,7 +548,7 @@ bool extract_mip_gnss_clock_info_data_from_field(const mip_field_view* field, vo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_fix_info (0x81,0x0B) Fix Info [C] +///@defgroup gnss_fix_info_c (0x81,0x0B) Fix Info /// GNSS reported position fix type /// ///@{ @@ -629,7 +629,7 @@ bool extract_mip_gnss_fix_info_data_from_field(const mip_field_view* field, void ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_sv_info (0x81,0x0C) Sv Info [C] +///@defgroup gnss_sv_info_c (0x81,0x0C) Sv Info /// GNSS reported space vehicle information /// /// When enabled, these fields will arrive in separate MIP packets @@ -694,7 +694,7 @@ bool extract_mip_gnss_sv_info_data_from_field(const mip_field_view* field, void* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_hw_status (0x81,0x0D) Hw Status [C] +///@defgroup gnss_hw_status_c (0x81,0x0D) Hw Status /// GNSS reported hardware status /// ///@{ @@ -794,7 +794,7 @@ bool extract_mip_gnss_hw_status_data_from_field(const mip_field_view* field, voi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_dgps_info (0x81,0x0E) Dgps Info [C] +///@defgroup gnss_dgps_info_c (0x81,0x0E) Dgps Info /// GNSS reported DGNSS status /// ///
Possible Base Station Status Values:
@@ -849,7 +849,7 @@ bool extract_mip_gnss_dgps_info_data_from_field(const mip_field_view* field, voi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_dgps_channel (0x81,0x0F) Dgps Channel [C] +///@defgroup gnss_dgps_channel_c (0x81,0x0F) Dgps Channel /// GNSS reported DGPS Channel Status status /// /// When enabled, a separate field for each active space vehicle will be sent in the packet. @@ -894,7 +894,7 @@ bool extract_mip_gnss_dgps_channel_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_clock_info_2 (0x81,0x10) Clock Info 2 [C] +///@defgroup gnss_clock_info_2_c (0x81,0x10) Clock Info 2 /// GNSS reported receiver clock parameters /// /// This supersedes MIP_DATA_DESC_GNSS_CLOCK_INFO with additional information. @@ -939,7 +939,7 @@ bool extract_mip_gnss_clock_info_2_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_gps_leap_seconds (0x81,0x11) Gps Leap Seconds [C] +///@defgroup gnss_gps_leap_seconds_c (0x81,0x11) Gps Leap Seconds /// GNSS reported leap seconds (difference between GPS and UTC Time) /// ///@{ @@ -975,7 +975,7 @@ bool extract_mip_gnss_gps_leap_seconds_data_from_field(const mip_field_view* fie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_sbas_info (0x81,0x12) Sbas Info [C] +///@defgroup gnss_sbas_info_c (0x81,0x12) Sbas Info /// GNSS SBAS status /// ///@{ @@ -1040,7 +1040,7 @@ bool extract_mip_gnss_sbas_info_data_from_field(const mip_field_view* field, voi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_sbas_correction (0x81,0x13) Sbas Correction [C] +///@defgroup gnss_sbas_correction_c (0x81,0x13) Sbas Correction /// GNSS calculated SBAS Correction /// /// UDREI - the variance of a normal distribution associated with the user differential range errors for a @@ -1109,7 +1109,7 @@ bool extract_mip_gnss_sbas_correction_data_from_field(const mip_field_view* fiel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_rf_error_detection (0x81,0x14) Rf Error Detection [C] +///@defgroup gnss_rf_error_detection_c (0x81,0x14) Rf Error Detection /// GNSS Error Detection subsystem status /// ///@{ @@ -1211,7 +1211,7 @@ bool extract_mip_gnss_rf_error_detection_data_from_field(const mip_field_view* f ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_base_station_info (0x81,0x30) Base Station Info [C] +///@defgroup gnss_base_station_info_c (0x81,0x30) Base Station Info /// RTCM reported base station information (sourced from RTCM Message 1005 or 1006) /// /// Valid Flag Mapping: @@ -1283,7 +1283,7 @@ bool extract_mip_gnss_base_station_info_data_from_field(const mip_field_view* fi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_rtk_corrections_status (0x81,0x31) Rtk Corrections Status [C] +///@defgroup gnss_rtk_corrections_status_c (0x81,0x31) Rtk Corrections Status /// ///@{ @@ -1357,7 +1357,7 @@ bool extract_mip_gnss_rtk_corrections_status_data_from_field(const mip_field_vie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_satellite_status (0x81,0x20) Satellite Status [C] +///@defgroup gnss_satellite_status_c (0x81,0x20) Satellite Status /// Status information for a GNSS satellite. /// ///@{ @@ -1408,7 +1408,7 @@ bool extract_mip_gnss_satellite_status_data_from_field(const mip_field_view* fie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_raw (0x81,0x22) Raw [C] +///@defgroup gnss_raw_c (0x81,0x22) Raw /// GNSS Raw observation. /// ///@{ @@ -1499,7 +1499,7 @@ bool extract_mip_gnss_raw_data_from_field(const mip_field_view* field, void* ptr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_gps_ephemeris (0x81,0x61) Gps Ephemeris [C] +///@defgroup gnss_gps_ephemeris_c (0x81,0x61) Gps Ephemeris /// GPS Ephemeris Data /// ///@{ @@ -1570,7 +1570,7 @@ bool extract_mip_gnss_gps_ephemeris_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_galileo_ephemeris (0x81,0x63) Galileo Ephemeris [C] +///@defgroup gnss_galileo_ephemeris_c (0x81,0x63) Galileo Ephemeris /// Galileo Ephemeris Data /// ///@{ @@ -1641,7 +1641,7 @@ bool extract_mip_gnss_galileo_ephemeris_data_from_field(const mip_field_view* fi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_glo_ephemeris (0x81,0x62) Glo Ephemeris [C] +///@defgroup gnss_glo_ephemeris_c (0x81,0x62) Glo Ephemeris /// Glonass Ephemeris Data /// ///@{ @@ -1701,7 +1701,7 @@ bool extract_mip_gnss_glo_ephemeris_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_gps_iono_corr (0x81,0x71) Gps Iono Corr [C] +///@defgroup gnss_gps_iono_corr_c (0x81,0x71) Gps Iono Corr /// Ionospheric Correction Terms for GNSS /// ///@{ @@ -1744,7 +1744,7 @@ bool extract_mip_gnss_gps_iono_corr_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_gnss_galileo_iono_corr (0x81,0x73) Galileo Iono Corr [C] +///@defgroup gnss_galileo_iono_corr_c (0x81,0x73) Galileo Iono Corr /// Ionospheric Correction Terms for Galileo /// ///@{ diff --git a/src/c/mip/definitions/data_sensor.h b/src/c/mip/definitions/data_sensor.h index ff79e525c..d2d35497d 100644 --- a/src/c/mip/definitions/data_sensor.h +++ b/src/c/mip/definitions/data_sensor.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_c MIP Data [C] +///@addtogroup MipData_c ///@{ -///@defgroup sensor_data_c Sensor Data [C] +///@defgroup sensor_data_c Sensor Data /// ///@{ @@ -70,7 +70,7 @@ enum //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_raw_accel (0x80,0x01) Raw Accel [C] +///@defgroup sensor_raw_accel_c (0x80,0x01) Raw Accel /// Three element vector representing the sensed acceleration. /// This quantity is temperature compensated and expressed in the sensor body frame. /// @@ -90,7 +90,7 @@ bool extract_mip_sensor_raw_accel_data_from_field(const mip_field_view* field, v ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_raw_gyro (0x80,0x02) Raw Gyro [C] +///@defgroup sensor_raw_gyro_c (0x80,0x02) Raw Gyro /// Three element vector representing the sensed angular rate. /// This quantity is temperature compensated and expressed in the sensor body frame. /// @@ -110,7 +110,7 @@ bool extract_mip_sensor_raw_gyro_data_from_field(const mip_field_view* field, vo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_raw_mag (0x80,0x03) Raw Mag [C] +///@defgroup sensor_raw_mag_c (0x80,0x03) Raw Mag /// Three element vector representing the sensed magnetic field. /// This quantity is temperature compensated and expressed in the vehicle frame. /// @@ -130,7 +130,7 @@ bool extract_mip_sensor_raw_mag_data_from_field(const mip_field_view* field, voi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_raw_pressure (0x80,0x16) Raw Pressure [C] +///@defgroup sensor_raw_pressure_c (0x80,0x16) Raw Pressure /// Scalar value representing the sensed ambient pressure. /// This quantity is temperature compensated. /// @@ -150,7 +150,7 @@ bool extract_mip_sensor_raw_pressure_data_from_field(const mip_field_view* field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_scaled_accel (0x80,0x04) Scaled Accel [C] +///@defgroup sensor_scaled_accel_c (0x80,0x04) Scaled Accel /// 3-element vector representing the sensed acceleration. /// This quantity is temperature compensated and expressed in the vehicle frame. /// @@ -170,7 +170,7 @@ bool extract_mip_sensor_scaled_accel_data_from_field(const mip_field_view* field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_scaled_gyro (0x80,0x05) Scaled Gyro [C] +///@defgroup sensor_scaled_gyro_c (0x80,0x05) Scaled Gyro /// 3-element vector representing the sensed angular rate. /// This quantity is temperature compensated and expressed in the vehicle frame. /// @@ -190,7 +190,7 @@ bool extract_mip_sensor_scaled_gyro_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_scaled_mag (0x80,0x06) Scaled Mag [C] +///@defgroup sensor_scaled_mag_c (0x80,0x06) Scaled Mag /// 3-element vector representing the sensed magnetic field. /// This quantity is temperature compensated and expressed in the vehicle frame. /// @@ -210,7 +210,7 @@ bool extract_mip_sensor_scaled_mag_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_scaled_pressure (0x80,0x17) Scaled Pressure [C] +///@defgroup sensor_scaled_pressure_c (0x80,0x17) Scaled Pressure /// Scalar value representing the sensed ambient pressure. /// ///@{ @@ -229,7 +229,7 @@ bool extract_mip_sensor_scaled_pressure_data_from_field(const mip_field_view* fi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_delta_theta (0x80,0x07) Delta Theta [C] +///@defgroup sensor_delta_theta_c (0x80,0x07) Delta Theta /// 3-element vector representing the time integral of angular rate. /// This quantity is the integral of sensed angular rate over the period set by the IMU message format. It is expressed in the vehicle frame. /// @@ -249,7 +249,7 @@ bool extract_mip_sensor_delta_theta_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_delta_velocity (0x80,0x08) Delta Velocity [C] +///@defgroup sensor_delta_velocity_c (0x80,0x08) Delta Velocity /// 3-element vector representing the time integral of acceleration. /// This quantity is the integral of sensed acceleration over the period set by the IMU message format. It is expressed in the vehicle frame. /// @@ -269,7 +269,7 @@ bool extract_mip_sensor_delta_velocity_data_from_field(const mip_field_view* fie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_comp_orientation_matrix (0x80,0x09) Comp Orientation Matrix [C] +///@defgroup sensor_comp_orientation_matrix_c (0x80,0x09) Comp Orientation Matrix /// 3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame. /// This matrix satisfies the following relationship: /// @@ -298,7 +298,7 @@ bool extract_mip_sensor_comp_orientation_matrix_data_from_field(const mip_field_ ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_comp_quaternion (0x80,0x0A) Comp Quaternion [C] +///@defgroup sensor_comp_quaternion_c (0x80,0x0A) Comp Quaternion /// 4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame. /// This quaternion satisfies the following relationship: /// @@ -325,7 +325,7 @@ bool extract_mip_sensor_comp_quaternion_data_from_field(const mip_field_view* fi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_comp_euler_angles (0x80,0x0C) Comp Euler Angles [C] +///@defgroup sensor_comp_euler_angles_c (0x80,0x0C) Comp Euler Angles /// Euler angles describing the orientation of the device with respect to the NED local-level frame. /// The Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order. /// @@ -347,7 +347,7 @@ bool extract_mip_sensor_comp_euler_angles_data_from_field(const mip_field_view* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_comp_orientation_update_matrix (0x80,0x0B) Comp Orientation Update Matrix [C] +///@defgroup sensor_comp_orientation_update_matrix_c (0x80,0x0B) Comp Orientation Update Matrix /// DEPRECATED! /// ///@{ @@ -366,7 +366,7 @@ bool extract_mip_sensor_comp_orientation_update_matrix_data_from_field(const mip ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_orientation_raw_temp (0x80,0x0D) Orientation Raw Temp [C] +///@defgroup sensor_orientation_raw_temp_c (0x80,0x0D) Orientation Raw Temp /// DEPRECATED! /// ///@{ @@ -385,7 +385,7 @@ bool extract_mip_sensor_orientation_raw_temp_data_from_field(const mip_field_vie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_internal_timestamp (0x80,0x0E) Internal Timestamp [C] +///@defgroup sensor_internal_timestamp_c (0x80,0x0E) Internal Timestamp /// DEPRECATED! /// ///@{ @@ -404,7 +404,7 @@ bool extract_mip_sensor_internal_timestamp_data_from_field(const mip_field_view* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_pps_timestamp (0x80,0x0F) Pps Timestamp [C] +///@defgroup sensor_pps_timestamp_c (0x80,0x0F) Pps Timestamp /// DEPRECATED! /// ///@{ @@ -424,7 +424,7 @@ bool extract_mip_sensor_pps_timestamp_data_from_field(const mip_field_view* fiel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_gps_timestamp (0x80,0x12) Gps Timestamp [C] +///@defgroup sensor_gps_timestamp_c (0x80,0x12) Gps Timestamp /// GPS timestamp of the SENSOR data /// /// Should the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time. @@ -471,7 +471,7 @@ bool extract_mip_sensor_gps_timestamp_data_from_field(const mip_field_view* fiel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_temperature_abs (0x80,0x14) Temperature Abs [C] +///@defgroup sensor_temperature_abs_c (0x80,0x14) Temperature Abs /// SENSOR reported temperature statistics /// /// Temperature may originate from the MEMS sensors, or be calculated in combination with board temperature sensors. @@ -496,7 +496,7 @@ bool extract_mip_sensor_temperature_abs_data_from_field(const mip_field_view* fi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_up_vector (0x80,0x11) Up Vector [C] +///@defgroup sensor_up_vector_c (0x80,0x11) Up Vector /// Gyro-stabilized 3-element vector representing the complementary filter's estimated vertical direction. /// This quantity is expressed in the vehicle frame. /// @@ -521,7 +521,7 @@ bool extract_mip_sensor_up_vector_data_from_field(const mip_field_view* field, v ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_north_vector (0x80,0x10) North Vector [C] +///@defgroup sensor_north_vector_c (0x80,0x10) North Vector /// Gyro-stabilized 3-element vector representing the complementary filter's estimate of magnetic north. /// This quantity is expressed in the vehicle frame. /// @@ -543,7 +543,7 @@ bool extract_mip_sensor_north_vector_data_from_field(const mip_field_view* field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_overrange_status (0x80,0x18) Overrange Status [C] +///@defgroup sensor_overrange_status_c (0x80,0x18) Overrange Status /// ///@{ @@ -586,7 +586,7 @@ bool extract_mip_sensor_overrange_status_data_from_field(const mip_field_view* f ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_sensor_odometer_data (0x80,0x40) Odometer Data [C] +///@defgroup sensor_odometer_data_c (0x80,0x40) Odometer Data /// ///@{ diff --git a/src/c/mip/definitions/data_shared.h b/src/c/mip/definitions/data_shared.h index 3d25b14e7..4869bb87f 100644 --- a/src/c/mip/definitions/data_shared.h +++ b/src/c/mip/definitions/data_shared.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_c MIP Data [C] +///@addtogroup MipData_c ///@{ -///@defgroup shared_data_c Shared Data [C] +///@defgroup shared_data_c Shared Data /// ///@{ @@ -55,7 +55,7 @@ enum { MIP_DATA_DESC_SHARED_START = 0xD0 }; //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_shared_event_source (0xFF,0xD0) Event Source [C] +///@defgroup shared_event_source_c (0xFF,0xD0) Event Source /// Identifies which event trigger caused this packet to be emitted. /// /// Generally this is used to determine whether a packet was emitted @@ -77,7 +77,7 @@ bool extract_mip_shared_event_source_data_from_field(const mip_field_view* field ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_shared_ticks (0xFF,0xD1) Ticks [C] +///@defgroup shared_ticks_c (0xFF,0xD1) Ticks /// Time since powerup in multiples of the base rate. /// /// The counter will wrap around to 0 after approximately 50 days. @@ -99,7 +99,7 @@ bool extract_mip_shared_ticks_data_from_field(const mip_field_view* field, void* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_shared_delta_ticks (0xFF,0xD2) Delta Ticks [C] +///@defgroup shared_delta_ticks_c (0xFF,0xD2) Delta Ticks /// Ticks since the last output of this field. /// /// This field can be used to track the amount of time passed between @@ -122,7 +122,7 @@ bool extract_mip_shared_delta_ticks_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_shared_gps_timestamp (0xFF,0xD3) Gps Timestamp [C] +///@defgroup shared_gps_timestamp_c (0xFF,0xD3) Gps Timestamp /// Outputs the current GPS system time in time-of-week and week number format. /// /// For events, this is the time of the event trigger. @@ -164,7 +164,7 @@ bool extract_mip_shared_gps_timestamp_data_from_field(const mip_field_view* fiel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_shared_delta_time (0xFF,0xD4) Delta Time [C] +///@defgroup shared_delta_time_c (0xFF,0xD4) Delta Time /// Time in the synchronized clock domain since the last output of this field within the same descriptor set and event instance. /// /// This can be used to track the amount of time passed between @@ -192,7 +192,7 @@ bool extract_mip_shared_delta_time_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_shared_reference_timestamp (0xFF,0xD5) Reference Timestamp [C] +///@defgroup shared_reference_timestamp_c (0xFF,0xD5) Reference Timestamp /// Internal reference timestamp. /// /// This timestamp represents the time at which the corresponding @@ -218,7 +218,7 @@ bool extract_mip_shared_reference_timestamp_data_from_field(const mip_field_view ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_shared_reference_time_delta (0xFF,0xD6) Reference Time Delta [C] +///@defgroup shared_reference_time_delta_c (0xFF,0xD6) Reference Time Delta /// Delta time since the last packet. /// /// Difference between the time as reported by the shared reference time field, 0xD5, @@ -246,7 +246,7 @@ bool extract_mip_shared_reference_time_delta_data_from_field(const mip_field_vie ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_shared_external_timestamp (0xFF,0xD7) External Timestamp [C] +///@defgroup shared_external_timestamp_c (0xFF,0xD7) External Timestamp /// External timestamp in nanoseconds. /// /// This timestamp represents the time at which the corresponding @@ -290,7 +290,7 @@ bool extract_mip_shared_external_timestamp_data_from_field(const mip_field_view* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_shared_external_time_delta (0xFF,0xD8) External Time Delta [C] +///@defgroup shared_external_time_delta_c (0xFF,0xD8) External Time Delta /// Delta time since the last packet containing delta external (0xFF,0xD4) or delta gps time (0xFF,0xD8). /// /// Difference between the time as reported by the shared external time field, 0xD7, diff --git a/src/c/mip/definitions/data_system.h b/src/c/mip/definitions/data_system.h index 89b639987..ca9e09681 100644 --- a/src/c/mip/definitions/data_system.h +++ b/src/c/mip/definitions/data_system.h @@ -17,9 +17,9 @@ extern "C" { #endif // __cplusplus //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_c MIP Data [C] +///@addtogroup MipData_c ///@{ -///@defgroup system_data_c System Data [C] +///@defgroup system_data_c System Data /// ///@{ @@ -48,7 +48,7 @@ enum //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_system_built_in_test (0xA0,0x01) Built In Test [C] +///@defgroup system_built_in_test_c (0xA0,0x01) Built In Test /// Contains the continuous built-in-test (BIT) results. /// /// Due to the large size of this field, it is recommended to stream it at @@ -85,7 +85,7 @@ bool extract_mip_system_built_in_test_data_from_field(const mip_field_view* fiel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_system_time_sync_status (0xA0,0x02) Time Sync Status [C] +///@defgroup system_time_sync_status_c (0xA0,0x02) Time Sync Status /// Indicates whether a sync has been achieved using the PPS signal. /// ///@{ @@ -105,7 +105,7 @@ bool extract_mip_system_time_sync_status_data_from_field(const mip_field_view* f ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_system_gpio_state (0xA0,0x03) Gpio State [C] +///@defgroup system_gpio_state_c (0xA0,0x03) Gpio State /// Indicates the state of all of the user GPIO pins. /// /// This message can be used to correlate external signals @@ -142,7 +142,7 @@ bool extract_mip_system_gpio_state_data_from_field(const mip_field_view* field, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup c_system_gpio_analog_value (0xA0,0x04) Gpio Analog Value [C] +///@defgroup system_gpio_analog_value_c (0xA0,0x04) Gpio Analog Value /// Indicates the analog value of the given user GPIO. /// The pin must be configured for analog input. /// diff --git a/src/c/mip/mip_all.h b/src/c/mip/mip_all.h index 2500b2561..6e51c5fd8 100644 --- a/src/c/mip/mip_all.h +++ b/src/c/mip/mip_all.h @@ -1,5 +1,17 @@ #pragma once +//////////////////////////////////////////////////////////////////////////////// +///@defgroup mip MIP +///@{ +/// +///@defgroup mip_c C API +///@brief This module contains functions and classes for communicating with a +/// MIP device in %C. +/// +///@} +//////////////////////////////////////////////////////////////////////////////// + + // MIP Core #include "mip_cmdqueue.h" #include "mip_descriptors.h" diff --git a/src/c/mip/mip_cmdqueue.h b/src/c/mip/mip_cmdqueue.h index bc860ec35..6a2df9f9d 100644 --- a/src/c/mip/mip_cmdqueue.h +++ b/src/c/mip/mip_cmdqueue.h @@ -18,7 +18,7 @@ extern "C" { ///@{ //////////////////////////////////////////////////////////////////////////////// -///@defgroup MipCommandQueue_c Mip Command Queue [C] +///@defgroup MipCommandQueue_c Mip Command Queue /// ///@brief Functions for handling command responses. /// @@ -26,7 +26,7 @@ extern "C" { //////////////////////////////////////////////////////////////////////////////// -///@defgroup PendingCommand mip_pending_cmd functions [C] +///@defgroup PendingCommand_c mip_pending_cmd functions /// ///@{ @@ -72,7 +72,7 @@ bool mip_pending_cmd_check_timeout(const mip_pending_cmd* cmd, mip_timestamp now ///@} //////////////////////////////////////////////////////////////////////////////// -///@defgroup CommandQueue mip_cmd_queue functions [C] +///@defgroup CommandQueue_c mip_cmd_queue functions /// ///@note This should be considered an "opaque" structure; its members should be /// considered an internal implementation detail. Avoid accessing them directly diff --git a/src/c/mip/mip_dispatch.h b/src/c/mip/mip_dispatch.h index 5af7350ed..8ad8ac9a0 100644 --- a/src/c/mip/mip_dispatch.h +++ b/src/c/mip/mip_dispatch.h @@ -21,7 +21,7 @@ extern "C" { //////////////////////////////////////////////////////////////////////////////// -///@defgroup MipDispatch_c Mip Dispatch [C] +///@defgroup MipDispatch_c Mip Dispatch /// ///@brief System for issuing callbacks from MIP packets or fields. /// diff --git a/src/c/mip/mip_field.c b/src/c/mip/mip_field.c index 72a4e9e4c..ce66d6b8d 100644 --- a/src/c/mip/mip_field.c +++ b/src/c/mip/mip_field.c @@ -167,7 +167,7 @@ mip_field_view mip_field_first_from_packet(const mip_packet_view* packet) } //////////////////////////////////////////////////////////////////////////////// -///@brief Gets the next field after the specified field._ +///@brief Gets the next field after the specified field. /// ///@param field /// An existing MIP field in a packet. Can be invalid, in which case the diff --git a/src/c/mip/mip_field.h b/src/c/mip/mip_field.h index 6c1dbb8d3..1ea259aa1 100644 --- a/src/c/mip/mip_field.h +++ b/src/c/mip/mip_field.h @@ -16,7 +16,7 @@ extern "C" { ///@{ //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_field_c Mip Fields [C] +///@defgroup mip_field_c Mip Fields /// ///@brief Functions for processing received MIP fields. /// diff --git a/src/c/mip/mip_interface.h b/src/c/mip/mip_interface.h index 0da725613..dad828edd 100644 --- a/src/c/mip/mip_interface.h +++ b/src/c/mip/mip_interface.h @@ -17,9 +17,9 @@ extern "C" { ///@addtogroup mip_c ///@{ //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_interface_c Mip Interface [C] +///@defgroup mip_interface_c Mip Interface /// -///@brief High-level C functions for controlling a MIP device. +///@brief High-level %C functions for controlling a MIP device. /// /// This module contains functions and classes for communicating with a /// MIP device in C. diff --git a/src/c/mip/mip_packet.h b/src/c/mip/mip_packet.h index 46accb802..63620c588 100644 --- a/src/c/mip/mip_packet.h +++ b/src/c/mip/mip_packet.h @@ -23,9 +23,9 @@ struct microstrain_serializer; ///@{ //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_packet_c Mip Packet [C] +///@defgroup mip_packet_c Mip Packet /// -///@brief Functions for handling MIP packets. +///@brief Functions for building and processing MIP packets. /// /// A MIP Packet is represented by the mip_packet_view struct. /// @@ -55,7 +55,7 @@ typedef struct mip_packet_view //////////////////////////////////////////////////////////////////////////////// -///@defgroup PacketBuilding Packet Building [C] +///@defgroup PacketBuilding Packet Building /// ///@brief Functions for building new MIP packets. /// @@ -77,7 +77,9 @@ void mip_packet_reset(mip_packet_view* packet, uint8_t descriptor_set); ///@} //////////////////////////////////////////////////////////////////////////////// -///@defgroup Accessors Accessors - Functions for accessing information about an existing MIP packet. +///@defgroup Accessors_c Accessors +/// +///@brief Functions for accessing information about an existing MIP packet. /// /// Use these functions to get information about a MIP packet after it has been /// parsed. Generally, first the descriptor set would be inspected followed by @@ -87,6 +89,9 @@ void mip_packet_reset(mip_packet_view* packet, uint8_t descriptor_set); /// calls it, e.g. mip_packet_is_valid()), these functions may also be used on /// packets which are under construction via the PacketBuilding functions. /// +///@caution Do not call the packet-building functions unless you know the +/// input buffer is not const. +/// ///@{ void mip_packet_from_buffer(mip_packet_view* packet, const uint8_t* buffer, size_t length); diff --git a/src/c/mip/mip_parser.h b/src/c/mip/mip_parser.h index c5c85cc1a..830469f3f 100644 --- a/src/c/mip/mip_parser.h +++ b/src/c/mip/mip_parser.h @@ -21,7 +21,7 @@ extern "C" { //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_parser_c mip_parser [C] +///@defgroup mip_parser_c Mip Parser /// ///@brief Functions for parsing MIP packets /// diff --git a/src/c/mip/mip_result.h b/src/c/mip/mip_result.h index 0cfb8b153..e57676a48 100644 --- a/src/c/mip/mip_result.h +++ b/src/c/mip/mip_result.h @@ -22,6 +22,8 @@ extern "C" { /// Values at or below MIP_STATUS_USER_START (negative values) are reserved for /// status codes from user code. /// +/// See @ref command_results +/// typedef enum mip_cmd_result { MIP_STATUS_USER_START = -10, ///< Values defined by user code must be less than or equal to this value. diff --git a/src/cpp/microstrain/common/index.hpp b/src/cpp/microstrain/common/index.hpp index 22c97e2eb..629a980af 100644 --- a/src/cpp/microstrain/common/index.hpp +++ b/src/cpp/microstrain/common/index.hpp @@ -14,12 +14,12 @@ namespace microstrain /// Use this to help avoid off-by-one errors when using indices into arrays at /// the same time as referring to MIP values which typically start at 1. /// - /// Use the .index() or .id() methods to get the actual value, depending on + /// Use the index() or id() methods to get the actual value, depending on /// what you need. The index() method returns an unsigned int in the range [0,N-1] /// while the id() method returns an unsigned int in the range [1,N] /// /// isAssigned() can be used to see if the value is valid, i.e. initialized. - /// isValid(N) can be used to check if the value is within a maximum count. + /// isValid() can be used to check if the value is within a maximum count. /// /// The default value with no initialization is INVALID. /// @@ -70,7 +70,7 @@ namespace microstrain //////////////////////////////////////////////////////////////////////////////// ///@brief Representes an ID number ranging from 1..N including N. /// - /// This is interchangeable with the Index class above. + /// This is interchangeable with the Index class. /// class Id { diff --git a/src/cpp/microstrain/common/span.hpp b/src/cpp/microstrain/common/span.hpp index f211ce99e..8b10fb759 100644 --- a/src/cpp/microstrain/common/span.hpp +++ b/src/cpp/microstrain/common/span.hpp @@ -25,6 +25,17 @@ namespace microstrain static constexpr size_t DYNAMIC_EXTENT = -1; +//////////////////////////////////////////////////////////////////////////////// +///@brief Implementation of std::span from C++20. +/// +/// This class represents a pointer and length. It provides the minimum +/// functionality required by this SDK while trying to be interchangeable +/// with std::span. +/// +/// https://en.cppreference.com/w/cpp/container/span +/// +/// See @ref cpp_standards +/// template struct Span { diff --git a/src/cpp/microstrain/microstrain_all.hpp b/src/cpp/microstrain/microstrain_all.hpp index 1463696ac..5a0233561 100644 --- a/src/cpp/microstrain/microstrain_all.hpp +++ b/src/cpp/microstrain/microstrain_all.hpp @@ -8,3 +8,17 @@ #include "common/serialization.hpp" #include "common/serialization/readwrite.hpp" #include "common/serialization/serializer.hpp" + +//////////////////////////////////////////////////////////////////////////////// +///@defgroup microstrain MicroStrain API +///@{ +/// +///@defgroup microstrain_c MicroStrain C API +///@{ +///@} +/// +///@defgroup microstrain_cpp MicroStrain C++ API +///@{ +///@} +/// +///@} diff --git a/src/cpp/mip/definitions/commands_3dm.hpp b/src/cpp/mip/definitions/commands_3dm.hpp index f2f1e90be..f45238309 100644 --- a/src/cpp/mip/definitions/commands_3dm.hpp +++ b/src/cpp/mip/definitions/commands_3dm.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace commands_3dm { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_cpp MIP Commands [CPP] +///@addtogroup MipCommands_cpp ///@{ -///@defgroup 3dm_commands_cpp 3dm Commands [CPP] +///@defgroup 3dm_commands_cpp 3dm Commands /// ///@{ @@ -192,7 +192,7 @@ enum class SensorRangeType : uint8_t //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_poll_imu_message (0x0C,0x01) Poll Imu Message [CPP] +///@defgroup 3dm_poll_imu_message_cpp (0x0C,0x01) Poll Imu Message /// Poll the device for an IMU message with the specified format /// /// This function polls for an IMU message using the provided format. The resulting message @@ -240,7 +240,7 @@ TypedResult pollImuMessage(C::mip_interface& device, bool suppre ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_poll_gnss_message (0x0C,0x02) Poll Gnss Message [CPP] +///@defgroup 3dm_poll_gnss_message_cpp (0x0C,0x02) Poll Gnss Message /// Poll the device for an GNSS message with the specified format /// /// This function polls for a GNSS message using the provided format. The resulting message @@ -288,7 +288,7 @@ TypedResult pollGnssMessage(C::mip_interface& device, bool supp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_poll_filter_message (0x0C,0x03) Poll Filter Message [CPP] +///@defgroup 3dm_poll_filter_message_cpp (0x0C,0x03) Poll Filter Message /// Poll the device for an Estimation Filter message with the specified format /// /// This function polls for an Estimation Filter message using the provided format. The resulting message @@ -336,7 +336,7 @@ TypedResult pollFilterMessage(C::mip_interface& device, bool ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_imu_message_format (0x0C,0x08) Imu Message Format [CPP] +///@defgroup 3dm_imu_message_format_cpp (0x0C,0x08) Imu Message Format /// Set, read, or save the format of the IMU data packet. /// /// The resulting data messages will maintain the order of descriptors sent in the command. @@ -418,7 +418,7 @@ TypedResult defaultImuMessageFormat(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_gps_message_format (0x0C,0x09) Gps Message Format [CPP] +///@defgroup 3dm_gps_message_format_cpp (0x0C,0x09) Gps Message Format /// Set, read, or save the format of the GNSS data packet. /// /// The resulting data messages will maintain the order of descriptors sent in the command. @@ -500,7 +500,7 @@ TypedResult defaultGpsMessageFormat(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_filter_message_format (0x0C,0x0A) Filter Message Format [CPP] +///@defgroup 3dm_filter_message_format_cpp (0x0C,0x0A) Filter Message Format /// Set, read, or save the format of the Estimation Filter data packet. /// /// The resulting data messages will maintain the order of descriptors sent in the command. @@ -582,7 +582,7 @@ TypedResult defaultFilterMessageFormat(C::mip_interface& de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_imu_get_base_rate (0x0C,0x06) Imu Get Base Rate [CPP] +///@defgroup 3dm_imu_get_base_rate_cpp (0x0C,0x06) Imu Get Base Rate /// Get the base rate for the IMU data in Hz /// /// This is the fastest rate for this type of data available on the device. @@ -648,7 +648,7 @@ TypedResult imuGetBaseRate(C::mip_interface& device, uint16_t* r ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_gps_get_base_rate (0x0C,0x07) Gps Get Base Rate [CPP] +///@defgroup 3dm_gps_get_base_rate_cpp (0x0C,0x07) Gps Get Base Rate /// Get the base rate for the GNSS data in Hz /// /// This is the fastest rate for this type of data available on the device. @@ -714,7 +714,7 @@ TypedResult gpsGetBaseRate(C::mip_interface& device, uint16_t* r ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_filter_get_base_rate (0x0C,0x0B) Filter Get Base Rate [CPP] +///@defgroup 3dm_filter_get_base_rate_cpp (0x0C,0x0B) Filter Get Base Rate /// Get the base rate for the Estimation Filter data in Hz /// /// This is the fastest rate for this type of data available on the device. @@ -780,7 +780,7 @@ TypedResult filterGetBaseRate(C::mip_interface& device, uint1 ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_poll_data (0x0C,0x0D) Poll Data [CPP] +///@defgroup 3dm_poll_data_cpp (0x0C,0x0D) Poll Data /// Poll the device for a message with the specified descriptor set and format. /// /// This function polls for a message using the provided format. The resulting message @@ -829,7 +829,7 @@ TypedResult pollData(C::mip_interface& device, uint8_t descSet, bool s ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_get_base_rate (0x0C,0x0E) Get Base Rate [CPP] +///@defgroup 3dm_get_base_rate_cpp (0x0C,0x0E) Get Base Rate /// Get the base rate for the specified descriptor set in Hz. /// ///@{ @@ -896,7 +896,7 @@ TypedResult getBaseRate(C::mip_interface& device, uint8_t descSet, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_message_format (0x0C,0x0F) Message Format [CPP] +///@defgroup 3dm_message_format_cpp (0x0C,0x0F) Message Format /// Set, read, or save the format for a given data packet. /// /// The resulting data messages will maintain the order of descriptors sent in the command. @@ -981,7 +981,7 @@ TypedResult defaultMessageFormat(C::mip_interface& device, uint8_ ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_nmea_poll_data (0x0C,0x04) Nmea Poll Data [CPP] +///@defgroup 3dm_nmea_poll_data_cpp (0x0C,0x04) Nmea Poll Data /// Poll the device for a NMEA message with the specified format. /// /// This function polls for a NMEA message using the provided format. @@ -1028,7 +1028,7 @@ TypedResult nmeaPollData(C::mip_interface& device, bool suppressAc ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_nmea_message_format (0x0C,0x0C) Nmea Message Format [CPP] +///@defgroup 3dm_nmea_message_format_cpp (0x0C,0x0C) Nmea Message Format /// Set, read, or save the NMEA message format. /// ///@{ @@ -1108,7 +1108,7 @@ TypedResult defaultNmeaMessageFormat(C::mip_interface& device ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_device_settings (0x0C,0x30) Device Settings [CPP] +///@defgroup 3dm_device_settings_cpp (0x0C,0x30) Device Settings /// Save, Load, or Reset to Default the values for all device settings. /// /// When a save current settings command is issued, a brief data disturbance may occur while all settings are written to non-volatile memory. @@ -1160,7 +1160,7 @@ TypedResult defaultDeviceSettings(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_uart_baudrate (0x0C,0x40) Uart Baudrate [CPP] +///@defgroup 3dm_uart_baudrate_cpp (0x0C,0x40) Uart Baudrate /// Read, Save, Load, or Reset to Default the baud rate of the main communication channel. /// /// For all functions except 0x01 (use new settings), the new baud rate value is ignored. @@ -1252,7 +1252,7 @@ TypedResult defaultUartBaudrate(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_factory_streaming (0x0C,0x10) Factory Streaming [CPP] +///@defgroup 3dm_factory_streaming_cpp (0x0C,0x10) Factory Streaming /// Configures the device for recording data for technical support. /// /// This command will configure all available data streams to predefined @@ -1302,7 +1302,7 @@ TypedResult factoryStreaming(C::mip_interface& device, Factory ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_datastream_control (0x0C,0x11) Datastream Control [CPP] +///@defgroup 3dm_datastream_control_cpp (0x0C,0x11) Datastream Control /// Enable/disable the selected data stream. /// /// Each data stream (descriptor set) can be enabled or disabled. @@ -1392,7 +1392,7 @@ TypedResult defaultDatastreamControl(C::mip_interface& device ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_constellation_settings (0x0C,0x21) Constellation Settings [CPP] +///@defgroup 3dm_constellation_settings_cpp (0x0C,0x21) Constellation Settings /// This command configures which satellite constellations are enabled and how many channels are dedicated to tracking each constellation. /// /// Maximum number of tracking channels to use (total for all constellations): @@ -1540,7 +1540,7 @@ TypedResult defaultConstellationSettings(C::mip_interface ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_gnss_sbas_settings (0x0C,0x22) Gnss Sbas Settings [CPP] +///@defgroup 3dm_gnss_sbas_settings_cpp (0x0C,0x22) Gnss Sbas Settings /// Configure the SBAS subsystem /// /// @@ -1657,7 +1657,7 @@ TypedResult defaultGnssSbasSettings(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_gnss_assisted_fix (0x0C,0x23) Gnss Assisted Fix [CPP] +///@defgroup 3dm_gnss_assisted_fix_cpp (0x0C,0x23) Gnss Assisted Fix /// Set the options for assisted GNSS fix. /// /// Devices that implement this command have a dedicated GNSS flash memory and a non-volatile FRAM. @@ -1753,7 +1753,7 @@ TypedResult defaultGnssAssistedFix(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_gnss_time_assistance (0x0C,0x24) Gnss Time Assistance [CPP] +///@defgroup 3dm_gnss_time_assistance_cpp (0x0C,0x24) Gnss Time Assistance /// Provide the GNSS subsystem with initial time information. /// /// This message is required immediately after power up if GNSS Assist was enabled when the device was powered off. @@ -1835,7 +1835,7 @@ TypedResult readGnssTimeAssistance(C::mip_interface& device, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_imu_lowpass_filter (0x0C,0x50) Imu Lowpass Filter [CPP] +///@defgroup 3dm_imu_lowpass_filter_cpp (0x0C,0x50) Imu Lowpass Filter /// Advanced configuration for the IMU data quantity low-pass filters. /// /// Deprecated, use the lowpass filter (0x0C,0x54) command instead. @@ -1937,7 +1937,7 @@ TypedResult defaultImuLowpassFilter(C::mip_interface& device, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_pps_source (0x0C,0x28) Pps Source [CPP] +///@defgroup 3dm_pps_source_cpp (0x0C,0x28) Pps Source /// Controls the Pulse Per Second (PPS) source. /// ///@{ @@ -2024,7 +2024,7 @@ TypedResult defaultPpsSource(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_gpio_config (0x0C,0x41) Gpio Config [CPP] +///@defgroup 3dm_gpio_config_cpp (0x0C,0x41) Gpio Config /// Configures the user GPIO pins on the connector for use with several built-in functions or for general input or output. /// /// GPIO pins are device-dependent. Some features are only available on @@ -2184,7 +2184,7 @@ TypedResult defaultGpioConfig(C::mip_interface& device, uint8_t pin) ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_gpio_state (0x0C,0x42) Gpio State [CPP] +///@defgroup 3dm_gpio_state_cpp (0x0C,0x42) Gpio State /// Allows the state of the pin to be read or controlled. /// /// This command serves two purposes: 1) To allow reading the state of a pin via command, @@ -2276,7 +2276,7 @@ TypedResult readGpioState(C::mip_interface& device, uint8_t pin, bool ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_odometer (0x0C,0x43) Odometer [CPP] +///@defgroup 3dm_odometer_cpp (0x0C,0x43) Odometer /// Configures the hardware odometer interface. /// /// @@ -2365,7 +2365,7 @@ TypedResult defaultOdometer(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_get_event_support (0x0C,0x2A) Get Event Support [CPP] +///@defgroup 3dm_get_event_support_cpp (0x0C,0x2A) Get Event Support /// Lists the available trigger or action types. /// /// There are a limited number of trigger and action slots available @@ -2467,7 +2467,7 @@ TypedResult getEventSupport(C::mip_interface& device, GetEventS ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_event_control (0x0C,0x2B) Event Control [CPP] +///@defgroup 3dm_event_control_cpp (0x0C,0x2B) Event Control /// Enables or disables event triggers. /// /// Triggers can be disabled, enabled, and tested. While disabled, a trigger will @@ -2565,7 +2565,7 @@ TypedResult defaultEventControl(C::mip_interface& device, uint8_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_get_event_trigger_status (0x0C,0x2C) Get Event Trigger Status [CPP] +///@defgroup 3dm_get_event_trigger_status_cpp (0x0C,0x2C) Get Event Trigger Status /// ///@{ @@ -2673,7 +2673,7 @@ TypedResult getEventTriggerStatus(C::mip_interface& devic ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_get_event_action_status (0x0C,0x2D) Get Event Action Status [CPP] +///@defgroup 3dm_get_event_action_status_cpp (0x0C,0x2D) Get Event Action Status /// ///@{ @@ -2751,7 +2751,7 @@ TypedResult getEventActionStatus(C::mip_interface& device, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_event_trigger (0x0C,0x2E) Event Trigger [CPP] +///@defgroup 3dm_event_trigger_cpp (0x0C,0x2E) Event Trigger /// Configures various types of event triggers. /// ///@{ @@ -2922,7 +2922,7 @@ TypedResult defaultEventTrigger(C::mip_interface& device, uint8_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_event_action (0x0C,0x2F) Event Action [CPP] +///@defgroup 3dm_event_action_cpp (0x0C,0x2F) Event Action /// Configures various types of event actions. /// ///@{ @@ -3055,7 +3055,7 @@ TypedResult defaultEventAction(C::mip_interface& device, uint8_t in ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_accel_bias (0x0C,0x37) Accel Bias [CPP] +///@defgroup 3dm_accel_bias_cpp (0x0C,0x37) Accel Bias /// Configures the user specified accelerometer bias /// /// The user specified bias is subtracted from the calibrated accelerometer output. Value is input in the sensor frame. @@ -3135,7 +3135,7 @@ TypedResult defaultAccelBias(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_gyro_bias (0x0C,0x38) Gyro Bias [CPP] +///@defgroup 3dm_gyro_bias_cpp (0x0C,0x38) Gyro Bias /// Configures the user specified gyroscope bias /// /// The user specified bias is subtracted from the calibrated angular rate output. Value is input in the sensor frame. @@ -3215,7 +3215,7 @@ TypedResult defaultGyroBias(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_capture_gyro_bias (0x0C,0x39) Capture Gyro Bias [CPP] +///@defgroup 3dm_capture_gyro_bias_cpp (0x0C,0x39) Capture Gyro Bias /// Samples gyro for a specified time range and writes the averaged result to the Gyro Bias vector in RAM /// /// The device will average the gyro output for the duration of "averaging_time_ms." To store the resulting vector @@ -3286,7 +3286,7 @@ TypedResult captureGyroBias(C::mip_interface& device, uint16_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_mag_hard_iron_offset (0x0C,0x3A) Mag Hard Iron Offset [CPP] +///@defgroup 3dm_mag_hard_iron_offset_cpp (0x0C,0x3A) Mag Hard Iron Offset /// Configure the user specified magnetometer hard iron offset vector /// /// The values for this offset are determined empirically by external software algorithms @@ -3370,7 +3370,7 @@ TypedResult defaultMagHardIronOffset(C::mip_interface& device ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_mag_soft_iron_matrix (0x0C,0x3B) Mag Soft Iron Matrix [CPP] +///@defgroup 3dm_mag_soft_iron_matrix_cpp (0x0C,0x3B) Mag Soft Iron Matrix /// Configure the user specified magnetometer soft iron offset matrix /// /// The values for this matrix are determined empirically by external software algorithms @@ -3458,7 +3458,7 @@ TypedResult defaultMagSoftIronMatrix(C::mip_interface& device ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_coning_sculling_enable (0x0C,0x3E) Coning Sculling Enable [CPP] +///@defgroup 3dm_coning_sculling_enable_cpp (0x0C,0x3E) Coning Sculling Enable /// Controls the Coning and Sculling Compenstation setting. /// ///@{ @@ -3536,7 +3536,7 @@ TypedResult defaultConingScullingEnable(C::mip_interface& ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_sensor_2_vehicle_transform_euler (0x0C,0x31) Sensor 2 Vehicle Transform Euler [CPP] +///@defgroup 3dm_sensor_2_vehicle_transform_euler_cpp (0x0C,0x31) Sensor 2 Vehicle Transform Euler /// Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, Roll Euler angles. /// These are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference, /// and describe the transformation of vectors from the sensor body frame to the vehicle frame.
@@ -3642,7 +3642,7 @@ TypedResult defaultSensor2VehicleTransformEuler(C: ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_sensor_2_vehicle_transform_quaternion (0x0C,0x32) Sensor 2 Vehicle Transform Quaternion [CPP] +///@defgroup 3dm_sensor_2_vehicle_transform_quaternion_cpp (0x0C,0x32) Sensor 2 Vehicle Transform Quaternion /// Set the sensor to vehicle frame transformation using unit length quaternion. /// /// Note: This is the transformation, the inverse of the rotation. @@ -3752,7 +3752,7 @@ TypedResult defaultSensor2VehicleTransformQua ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_sensor_2_vehicle_transform_dcm (0x0C,0x33) Sensor 2 Vehicle Transform Dcm [CPP] +///@defgroup 3dm_sensor_2_vehicle_transform_dcm_cpp (0x0C,0x33) Sensor 2 Vehicle Transform Dcm /// Set the sensor to vehicle frame transformation using a using a 3 x 3 direction cosine matrix EQSTART M_{ned}^{veh} EQEND, stored in row-major order in a 9-element array. /// /// These angles define the transformation of vectors from the sensor body frame to the fixed vehicle frame, according to:
@@ -3860,7 +3860,7 @@ TypedResult defaultSensor2VehicleTransformDcm(C::mip ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_complementary_filter (0x0C,0x51) Complementary Filter [CPP] +///@defgroup 3dm_complementary_filter_cpp (0x0C,0x51) Complementary Filter /// Configure the settings for the complementary filter which produces the following (0x80) descriptor set values: attitude matrix (0x80,09), quaternion (0x80,0A), and Euler angle (0x80,0C) outputs. /// /// The filter can be configured to correct for pitch and roll using the accelerometer (with the assumption that linear acceleration is minimal), @@ -3948,7 +3948,7 @@ TypedResult defaultComplementaryFilter(C::mip_interface& de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_sensor_range (0x0C,0x52) Sensor Range [CPP] +///@defgroup 3dm_sensor_range_cpp (0x0C,0x52) Sensor Range /// Changes the IMU sensor gain. /// /// This allows you to optimize the range to get the best accuracy and performance @@ -4036,7 +4036,7 @@ TypedResult defaultSensorRange(C::mip_interface& device, SensorRang ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_calibrated_sensor_ranges (0x0C,0x53) Calibrated Sensor Ranges [CPP] +///@defgroup 3dm_calibrated_sensor_ranges_cpp (0x0C,0x53) Calibrated Sensor Ranges /// Returns the supported sensor ranges which may be used with the 3DM Sensor Range (0x0C,0x52) command. /// /// The response includes an array of (u8, float) pairs which map each allowed setting @@ -4118,7 +4118,7 @@ TypedResult calibratedSensorRanges(C::mip_interface& dev ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_3dm_lowpass_filter (0x0C,0x54) Lowpass Filter [CPP] +///@defgroup 3dm_lowpass_filter_cpp (0x0C,0x54) Lowpass Filter /// This command controls the low-pass anti-aliasing filter supported data quantities. /// /// See the device user manual for data quantities which support the anti-aliasing filter. diff --git a/src/cpp/mip/definitions/commands_aiding.hpp b/src/cpp/mip/definitions/commands_aiding.hpp index 827981656..59f523cd1 100644 --- a/src/cpp/mip/definitions/commands_aiding.hpp +++ b/src/cpp/mip/definitions/commands_aiding.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace commands_aiding { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_cpp MIP Commands [CPP] +///@addtogroup MipCommands_cpp ///@{ -///@defgroup aiding_commands_cpp Aiding Commands [CPP] +///@defgroup aiding_commands_cpp Aiding Commands /// ///@{ @@ -82,7 +82,7 @@ struct Time //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_frame_config (0x13,0x01) Frame Config [CPP] +///@defgroup aiding_frame_config_cpp (0x13,0x01) Frame Config /// Defines an aiding frame associated with a specific sensor frame ID. /// The frame ID used in this command should mirror the frame ID used in the aiding command /// (if that aiding measurement is measured in this reference frame). @@ -206,7 +206,7 @@ TypedResult defaultFrameConfig(C::mip_interface& device, uint8_t fr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_echo_control (0x13,0x1F) Echo Control [CPP] +///@defgroup aiding_echo_control_cpp (0x13,0x1F) Echo Control /// Controls command response behavior to external aiding commands /// ///@{ @@ -291,7 +291,7 @@ TypedResult defaultEchoControl(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_pos_ecef (0x13,0x21) Pos Ecef [CPP] +///@defgroup aiding_pos_ecef_cpp (0x13,0x21) Pos Ecef /// Cartesian vector position aiding command. Coordinates are given in the WGS84 ECEF system. /// ///@{ @@ -364,7 +364,7 @@ TypedResult posEcef(C::mip_interface& device, const Time& time, uint8_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_pos_llh (0x13,0x22) Pos Llh [CPP] +///@defgroup aiding_pos_llh_cpp (0x13,0x22) Pos Llh /// Geodetic position aiding command. /// Coordinates are given in WGS84 geodetic latitude, longitude, and height above the ellipsoid. /// Uncertainty is given in NED coordinates, which are parallel to incremental changes in latitude, longitude, and height. @@ -441,7 +441,7 @@ TypedResult posLlh(C::mip_interface& device, const Time& time, uint8_t f ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_height_above_ellipsoid (0x13,0x23) Height Above Ellipsoid [CPP] +///@defgroup aiding_height_above_ellipsoid_cpp (0x13,0x23) Height Above Ellipsoid /// Estimated value of the height above ellipsoid. /// ///@{ @@ -484,7 +484,7 @@ TypedResult heightAboveEllipsoid(C::mip_interface& device, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_vel_ecef (0x13,0x28) Vel Ecef [CPP] +///@defgroup aiding_vel_ecef_cpp (0x13,0x28) Vel Ecef /// ECEF velocity aiding command. Coordinates are given in the WGS84 ECEF frame. /// ///@{ @@ -557,7 +557,7 @@ TypedResult velEcef(C::mip_interface& device, const Time& time, uint8_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_vel_ned (0x13,0x29) Vel Ned [CPP] +///@defgroup aiding_vel_ned_cpp (0x13,0x29) Vel Ned /// NED velocity aiding command. Coordinates are given in the local North-East-Down frame. /// ///@{ @@ -630,7 +630,7 @@ TypedResult velNed(C::mip_interface& device, const Time& time, uint8_t f ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_vel_body_frame (0x13,0x2A) Vel Body Frame [CPP] +///@defgroup aiding_vel_body_frame_cpp (0x13,0x2A) Vel Body Frame /// Estimated of velocity of the vehicle in the frame associated with the given sensor ID, relative to the vehicle frame. /// ///@{ @@ -703,7 +703,7 @@ TypedResult velBodyFrame(C::mip_interface& device, const Time& tim ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_heading_true (0x13,0x31) Heading True [CPP] +///@defgroup aiding_heading_true_cpp (0x13,0x31) Heading True /// ///@{ @@ -745,7 +745,7 @@ TypedResult headingTrue(C::mip_interface& device, const Time& time, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_magnetic_field (0x13,0x32) Magnetic Field [CPP] +///@defgroup aiding_magnetic_field_cpp (0x13,0x32) Magnetic Field /// Estimate of magnetic field in the frame associated with the given sensor ID. /// ///@{ @@ -818,7 +818,7 @@ TypedResult magneticField(C::mip_interface& device, const Time& t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_aiding_pressure (0x13,0x33) Pressure [CPP] +///@defgroup aiding_pressure_cpp (0x13,0x33) Pressure /// Estimated value of air pressure. /// ///@{ diff --git a/src/cpp/mip/definitions/commands_base.hpp b/src/cpp/mip/definitions/commands_base.hpp index 81ab1e895..6d9b3d992 100644 --- a/src/cpp/mip/definitions/commands_base.hpp +++ b/src/cpp/mip/definitions/commands_base.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace commands_base { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_cpp MIP Commands [CPP] +///@addtogroup MipCommands_cpp ///@{ -///@defgroup base_commands_cpp Base Commands [CPP] +///@defgroup base_commands_cpp Base Commands /// ///@{ @@ -184,7 +184,7 @@ struct CommandedTestBitsGq7 : Bitfield //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_ping (0x01,0x01) Ping [CPP] +///@defgroup base_ping_cpp (0x01,0x01) Ping /// Test Communications with a device. /// /// The Device will respond with an ACK, if present and operating correctly. @@ -224,7 +224,7 @@ TypedResult ping(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_set_idle (0x01,0x02) Set Idle [CPP] +///@defgroup base_set_idle_cpp (0x01,0x02) Set Idle /// Turn off all device data streams. /// /// The Device will respond with an ACK, if present and operating correctly. @@ -264,7 +264,7 @@ TypedResult setIdle(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_get_device_info (0x01,0x03) Get Device Info [CPP] +///@defgroup base_get_device_info_cpp (0x01,0x03) Get Device Info /// Get the device ID strings and firmware version number. /// ///@{ @@ -327,7 +327,7 @@ TypedResult getDeviceInfo(C::mip_interface& device, BaseDeviceInf ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_get_device_descriptors (0x01,0x04) Get Device Descriptors [CPP] +///@defgroup base_get_device_descriptors_cpp (0x01,0x04) Get Device Descriptors /// Get the command and data descriptors supported by the device. /// /// Reply has two fields: "ACK/NACK" and "Descriptors". The "Descriptors" field is an array of 16 bit values. @@ -394,7 +394,7 @@ TypedResult getDeviceDescriptors(C::mip_interface& device, ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_built_in_test (0x01,0x05) Built In Test [CPP] +///@defgroup base_built_in_test_cpp (0x01,0x05) Built In Test /// Run the device Built-In Test (BIT). /// /// The Built-In Test command always returns a 32 bit value. @@ -462,7 +462,7 @@ TypedResult builtInTest(C::mip_interface& device, uint32_t* resultO ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_resume (0x01,0x06) Resume [CPP] +///@defgroup base_resume_cpp (0x01,0x06) Resume /// Take the device out of idle mode. /// /// The device responds with ACK upon success. @@ -500,7 +500,7 @@ TypedResult resume(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_get_extended_descriptors (0x01,0x07) Get Extended Descriptors [CPP] +///@defgroup base_get_extended_descriptors_cpp (0x01,0x07) Get Extended Descriptors /// Get the command and data descriptors supported by the device. /// /// Reply has two fields: "ACK/NACK" and "Descriptors". The "Descriptors" field is an array of 16 bit values. @@ -567,7 +567,7 @@ TypedResult getExtendedDescriptors(C::mip_interface& dev ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_continuous_bit (0x01,0x08) Continuous Bit [CPP] +///@defgroup base_continuous_bit_cpp (0x01,0x08) Continuous Bit /// Report result of continuous built-in test. /// /// This test is non-disruptive but is not as thorough as the commanded BIT. @@ -632,7 +632,7 @@ TypedResult continuousBit(C::mip_interface& device, uint8_t* resu ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_comm_speed (0x01,0x09) Comm Speed [CPP] +///@defgroup base_comm_speed_cpp (0x01,0x09) Comm Speed /// Controls the baud rate of a specific port on the device. /// /// Please see the device user manual for supported baud rates on each port. @@ -727,7 +727,7 @@ TypedResult defaultCommSpeed(C::mip_interface& device, uint8_t port); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_gps_time_update (0x01,0x72) Gps Time Update [CPP] +///@defgroup base_gps_time_update_cpp (0x01,0x72) Gps Time Update /// Set device internal GPS time /// When combined with a PPS input signal applied to the I/O connector, this command enables complete synchronization of data outputs /// with an external time base, such as GPS system time. Since the hardware PPS synchronization can only detect the fractional number of seconds when pulses arrive, @@ -784,7 +784,7 @@ TypedResult writeGpsTimeUpdate(C::mip_interface& device, GpsTimeU ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_base_soft_reset (0x01,0x7E) Soft Reset [CPP] +///@defgroup base_soft_reset_cpp (0x01,0x7E) Soft Reset /// Resets the device. /// /// Device responds with ACK and immediately resets. diff --git a/src/cpp/mip/definitions/commands_filter.hpp b/src/cpp/mip/definitions/commands_filter.hpp index b175b27ec..1104d1a52 100644 --- a/src/cpp/mip/definitions/commands_filter.hpp +++ b/src/cpp/mip/definitions/commands_filter.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace commands_filter { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_cpp MIP Commands [CPP] +///@addtogroup MipCommands_cpp ///@{ -///@defgroup filter_commands_cpp Filter Commands [CPP] +///@defgroup filter_commands_cpp Filter Commands /// ///@{ @@ -179,7 +179,7 @@ enum class FilterAdaptiveMeasurement : uint8_t //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_reset (0x0D,0x01) Reset [CPP] +///@defgroup filter_reset_cpp (0x0D,0x01) Reset /// Resets the filter to the initialization state. /// /// If the auto-initialization feature is disabled, the initial attitude or heading must be set in @@ -218,7 +218,7 @@ TypedResult reset(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_set_initial_attitude (0x0D,0x02) Set Initial Attitude [CPP] +///@defgroup filter_set_initial_attitude_cpp (0x0D,0x02) Set Initial Attitude /// Set the sensor initial attitude. /// /// This command can only be issued in the "Init" state and should be used with a good @@ -270,7 +270,7 @@ TypedResult setInitialAttitude(C::mip_interface& device, flo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_estimation_control (0x0D,0x14) Estimation Control [CPP] +///@defgroup filter_estimation_control_cpp (0x0D,0x14) Estimation Control /// Estimation Control Flags /// /// Controls which parameters are estimated by the Kalman Filter. @@ -400,7 +400,7 @@ TypedResult defaultEstimationControl(C::mip_interface& device ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_external_gnss_update (0x0D,0x16) External Gnss Update [CPP] +///@defgroup filter_external_gnss_update_cpp (0x0D,0x16) External Gnss Update /// Provide a filter measurement from an external GNSS /// /// The GNSS source control must be set to "external" for this command to succeed, otherwise it will be NACK'd. @@ -450,7 +450,7 @@ TypedResult externalGnssUpdate(C::mip_interface& device, dou ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_external_heading_update (0x0D,0x17) External Heading Update [CPP] +///@defgroup filter_external_heading_update_cpp (0x0D,0x17) External Heading Update /// Provide a filter measurement from an external heading source /// /// The heading must be the sensor frame with respect to the NED frame. @@ -503,7 +503,7 @@ TypedResult externalHeadingUpdate(C::mip_interface& devic ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_external_heading_update_with_time (0x0D,0x1F) External Heading Update With Time [CPP] +///@defgroup filter_external_heading_update_with_time_cpp (0x0D,0x1F) External Heading Update With Time /// Provide a filter measurement from an external heading source at a specific GPS time /// /// This is more accurate than the External Heading Update (0x0D, 0x17) and should be used in applications @@ -562,7 +562,7 @@ TypedResult externalHeadingUpdateWithTime(C::mip_ ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_tare_orientation (0x0D,0x21) Tare Orientation [CPP] +///@defgroup filter_tare_orientation_cpp (0x0D,0x21) Tare Orientation /// Tare the device orientation. /// /// This function uses the current device orientation relative to the NED frame as the current sensor to vehicle transformation. @@ -674,7 +674,7 @@ TypedResult defaultTareOrientation(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_vehicle_dynamics_mode (0x0D,0x10) Vehicle Dynamics Mode [CPP] +///@defgroup filter_vehicle_dynamics_mode_cpp (0x0D,0x10) Vehicle Dynamics Mode /// Controls the vehicle dynamics mode. /// ///@{ @@ -760,7 +760,7 @@ TypedResult defaultVehicleDynamicsMode(C::mip_interface& de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_sensor_to_vehicle_rotation_euler (0x0D,0x11) Sensor To Vehicle Rotation Euler [CPP] +///@defgroup filter_sensor_to_vehicle_rotation_euler_cpp (0x0D,0x11) Sensor To Vehicle Rotation Euler /// Set the sensor to vehicle frame rotation using Yaw, Pitch, Roll Euler angles. /// /// Note: This is the rotation, the inverse of the transformation. @@ -864,7 +864,7 @@ TypedResult defaultSensorToVehicleRotationEuler(C: ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_sensor_to_vehicle_rotation_dcm (0x0D,0x4E) Sensor To Vehicle Rotation Dcm [CPP] +///@defgroup filter_sensor_to_vehicle_rotation_dcm_cpp (0x0D,0x4E) Sensor To Vehicle Rotation Dcm /// Set the sensor to vehicle frame rotation using a row-major direction cosine matrix. /// /// Note: This is the rotation, the inverse of the transformation. @@ -970,7 +970,7 @@ TypedResult defaultSensorToVehicleRotationDcm(C::mip ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_sensor_to_vehicle_rotation_quaternion (0x0D,0x4F) Sensor To Vehicle Rotation Quaternion [CPP] +///@defgroup filter_sensor_to_vehicle_rotation_quaternion_cpp (0x0D,0x4F) Sensor To Vehicle Rotation Quaternion /// Set the sensor to vehicle frame rotation using a quaternion. /// /// Note: This is the rotation, the inverse of the transformation. @@ -1075,7 +1075,7 @@ TypedResult defaultSensorToVehicleRotationQua ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_sensor_to_vehicle_offset (0x0D,0x12) Sensor To Vehicle Offset [CPP] +///@defgroup filter_sensor_to_vehicle_offset_cpp (0x0D,0x12) Sensor To Vehicle Offset /// Set the sensor to vehicle frame offset, expressed in the sensor frame. /// /// This is a simple offset, not a lever arm. It does not compensate for inertial effects experienced from being offset from the center of gravity/rotation of the vehicle. @@ -1161,7 +1161,7 @@ TypedResult defaultSensorToVehicleOffset(C::mip_interface ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_antenna_offset (0x0D,0x13) Antenna Offset [CPP] +///@defgroup filter_antenna_offset_cpp (0x0D,0x13) Antenna Offset /// Configure the GNSS antenna offset. /// /// For 5-series products, this is expressed in the sensor frame, from the sensor origin to the GNSS antenna RF center. @@ -1248,7 +1248,7 @@ TypedResult defaultAntennaOffset(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gnss_source (0x0D,0x15) Gnss Source [CPP] +///@defgroup filter_gnss_source_cpp (0x0D,0x15) Gnss Source /// Control the source of GNSS information used to update the Kalman Filter. /// /// Changing the GNSS source while the sensor is in the "running" state may temporarily place @@ -1338,7 +1338,7 @@ TypedResult defaultGnssSource(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_heading_source (0x0D,0x18) Heading Source [CPP] +///@defgroup filter_heading_source_cpp (0x0D,0x18) Heading Source /// Control the source of heading information used to update the Kalman Filter. /// /// 1. To use internal GNSS velocity vector for heading updates, the target application @@ -1439,7 +1439,7 @@ TypedResult defaultHeadingSource(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_auto_init_control (0x0D,0x19) Auto Init Control [CPP] +///@defgroup filter_auto_init_control_cpp (0x0D,0x19) Auto Init Control /// Filter Auto-initialization Control /// /// Enable/Disable automatic initialization upon device startup. @@ -1525,7 +1525,7 @@ TypedResult defaultAutoInitControl(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_accel_noise (0x0D,0x1A) Accel Noise [CPP] +///@defgroup filter_accel_noise_cpp (0x0D,0x1A) Accel Noise /// Accelerometer Noise Standard Deviation /// /// Each of the noise values must be greater than 0.0. @@ -1609,7 +1609,7 @@ TypedResult defaultAccelNoise(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gyro_noise (0x0D,0x1B) Gyro Noise [CPP] +///@defgroup filter_gyro_noise_cpp (0x0D,0x1B) Gyro Noise /// Gyroscope Noise Standard Deviation /// /// Each of the noise values must be greater than 0.0 @@ -1693,7 +1693,7 @@ TypedResult defaultGyroNoise(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_accel_bias_model (0x0D,0x1C) Accel Bias Model [CPP] +///@defgroup filter_accel_bias_model_cpp (0x0D,0x1C) Accel Bias Model /// Accelerometer Bias Model Parameters /// /// Noise values must be greater than 0.0 @@ -1776,7 +1776,7 @@ TypedResult defaultAccelBiasModel(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gyro_bias_model (0x0D,0x1D) Gyro Bias Model [CPP] +///@defgroup filter_gyro_bias_model_cpp (0x0D,0x1D) Gyro Bias Model /// Gyroscope Bias Model Parameters /// /// Noise values must be greater than 0.0 @@ -1859,7 +1859,7 @@ TypedResult defaultGyroBiasModel(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_altitude_aiding (0x0D,0x47) Altitude Aiding [CPP] +///@defgroup filter_altitude_aiding_cpp (0x0D,0x47) Altitude Aiding /// Select altitude input for absolute altitude and/or vertical velocity. The primary altitude reading is always GNSS. /// Aiding inputs are used to improve GNSS altitude readings when GNSS is available and to backup GNSS during outages. /// @@ -1947,7 +1947,7 @@ TypedResult defaultAltitudeAiding(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_pitch_roll_aiding (0x0D,0x4B) Pitch Roll Aiding [CPP] +///@defgroup filter_pitch_roll_aiding_cpp (0x0D,0x4B) Pitch Roll Aiding /// Select pitch/roll aiding input. Pitch/roll reading is always derived from GNSS corrected inertial solution. /// Aiding inputs are used to improve that solution during periods of low dynamics and GNSS outages. /// @@ -2032,7 +2032,7 @@ TypedResult defaultPitchRollAiding(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_auto_zupt (0x0D,0x1E) Auto Zupt [CPP] +///@defgroup filter_auto_zupt_cpp (0x0D,0x1E) Auto Zupt /// The ZUPT is triggered when the scalar magnitude of the GNSS reported velocity vector is equal-to or less than the threshold value. /// The device will NACK threshold values that are less than zero (i.e.negative.) /// @@ -2113,7 +2113,7 @@ TypedResult defaultAutoZupt(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_auto_angular_zupt (0x0D,0x20) Auto Angular Zupt [CPP] +///@defgroup filter_auto_angular_zupt_cpp (0x0D,0x20) Auto Angular Zupt /// Zero Angular Rate Update /// The ZUPT is triggered when the scalar magnitude of the angular rate vector is equal-to or less than the threshold value. /// The device will NACK threshold values that are less than zero (i.e.negative.) @@ -2195,7 +2195,7 @@ TypedResult defaultAutoAngularZupt(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_commanded_zupt (0x0D,0x22) Commanded Zupt [CPP] +///@defgroup filter_commanded_zupt_cpp (0x0D,0x22) Commanded Zupt /// Please see the device user manual for the maximum rate of this message. /// ///@{ @@ -2231,7 +2231,7 @@ TypedResult commandedZupt(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_commanded_angular_zupt (0x0D,0x23) Commanded Angular Zupt [CPP] +///@defgroup filter_commanded_angular_zupt_cpp (0x0D,0x23) Commanded Angular Zupt /// Please see the device user manual for the maximum rate of this message. /// ///@{ @@ -2267,7 +2267,7 @@ TypedResult commandedAngularZupt(C::mip_interface& device) ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_mag_capture_auto_cal (0x0D,0x27) Mag Capture Auto Cal [CPP] +///@defgroup filter_mag_capture_auto_cal_cpp (0x0D,0x27) Mag Capture Auto Cal /// This command captures the current value of the auto-calibration, applies it to the current fixed hard and soft iron calibration coefficients, and replaces the current fixed hard and soft iron calibration coefficients with the new values. /// This may be used in place of (or in addition to) a manual hard and soft iron calibration utility. This command also resets the auto-calibration coefficients. /// Function selector SAVE is the same as issuing the 0x0C, 0x3A and 0x0C, 0x3B commands with the SAVE function selector. @@ -2316,7 +2316,7 @@ TypedResult saveMagCaptureAutoCal(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gravity_noise (0x0D,0x28) Gravity Noise [CPP] +///@defgroup filter_gravity_noise_cpp (0x0D,0x28) Gravity Noise /// Set the expected gravity noise 1-sigma values. This function can be used to tune the filter performance in the target application. /// /// Note: Noise values must be greater than 0.0 @@ -2399,7 +2399,7 @@ TypedResult defaultGravityNoise(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_pressure_altitude_noise (0x0D,0x29) Pressure Altitude Noise [CPP] +///@defgroup filter_pressure_altitude_noise_cpp (0x0D,0x29) Pressure Altitude Noise /// Set the expected pressure altitude noise 1-sigma values. This function can be used to tune the filter performance in the target application. /// /// The noise value must be greater than 0.0 @@ -2482,7 +2482,7 @@ TypedResult defaultPressureAltitudeNoise(C::mip_interface ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_hard_iron_offset_noise (0x0D,0x2B) Hard Iron Offset Noise [CPP] +///@defgroup filter_hard_iron_offset_noise_cpp (0x0D,0x2B) Hard Iron Offset Noise /// Set the expected hard iron offset noise 1-sigma values. This function can be used to tune the filter performance in the target application. /// /// This function can be used to tune the filter performance in the target application. @@ -2567,7 +2567,7 @@ TypedResult defaultHardIronOffsetNoise(C::mip_interface& de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_soft_iron_matrix_noise (0x0D,0x2C) Soft Iron Matrix Noise [CPP] +///@defgroup filter_soft_iron_matrix_noise_cpp (0x0D,0x2C) Soft Iron Matrix Noise /// Set the expected soft iron matrix noise 1-sigma values. /// This function can be used to tune the filter performance in the target application. /// @@ -2651,7 +2651,7 @@ TypedResult defaultSoftIronMatrixNoise(C::mip_interface& de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_mag_noise (0x0D,0x42) Mag Noise [CPP] +///@defgroup filter_mag_noise_cpp (0x0D,0x42) Mag Noise /// Set the expected magnetometer noise 1-sigma values. /// This function can be used to tune the filter performance in the target application. /// @@ -2735,7 +2735,7 @@ TypedResult defaultMagNoise(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_inclination_source (0x0D,0x4C) Inclination Source [CPP] +///@defgroup filter_inclination_source_cpp (0x0D,0x4C) Inclination Source /// Set/Get the local magnetic field inclination angle source. /// /// This can be used to correct for the local value of inclination (dip angle) of the earthmagnetic field. @@ -2819,7 +2819,7 @@ TypedResult defaultInclinationSource(C::mip_interface& device ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_magnetic_declination_source (0x0D,0x43) Magnetic Declination Source [CPP] +///@defgroup filter_magnetic_declination_source_cpp (0x0D,0x43) Magnetic Declination Source /// Set/Get the local magnetic field declination angle source. /// /// This can be used to correct for the local value of declination of the earthmagnetic field. @@ -2903,7 +2903,7 @@ TypedResult defaultMagneticDeclinationSource(C::mip_i ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_mag_field_magnitude_source (0x0D,0x4D) Mag Field Magnitude Source [CPP] +///@defgroup filter_mag_field_magnitude_source_cpp (0x0D,0x4D) Mag Field Magnitude Source /// Set/Get the local magnetic field magnitude source. /// /// This is used to specify the local magnitude of the earth's magnetic field. @@ -2986,7 +2986,7 @@ TypedResult defaultMagFieldMagnitudeSource(C::mip_inter ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_reference_position (0x0D,0x26) Reference Position [CPP] +///@defgroup filter_reference_position_cpp (0x0D,0x26) Reference Position /// Set the Lat/Long/Alt reference position for the sensor. /// /// This position is used by the sensor to calculate the WGS84 gravity and WMM2015 magnetic field parameters. @@ -3073,7 +3073,7 @@ TypedResult defaultReferencePosition(C::mip_interface& device ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_accel_magnitude_error_adaptive_measurement (0x0D,0x44) Accel Magnitude Error Adaptive Measurement [CPP] +///@defgroup filter_accel_magnitude_error_adaptive_measurement_cpp (0x0D,0x44) Accel Magnitude Error Adaptive Measurement /// Enable or disable the gravity magnitude error adaptive measurement. /// This function can be used to tune the filter performance in the target application /// @@ -3176,7 +3176,7 @@ TypedResult defaultAccelMagnitudeErrorAd ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_mag_magnitude_error_adaptive_measurement (0x0D,0x45) Mag Magnitude Error Adaptive Measurement [CPP] +///@defgroup filter_mag_magnitude_error_adaptive_measurement_cpp (0x0D,0x45) Mag Magnitude Error Adaptive Measurement /// Enable or disable the magnetometer magnitude error adaptive measurement. /// This feature will reject magnetometer readings that are out of range of the thresholds specified (fixed adaptive) or calculated internally (auto-adaptive). /// @@ -3274,7 +3274,7 @@ TypedResult defaultMagMagnitudeErrorAdapti ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_mag_dip_angle_error_adaptive_measurement (0x0D,0x46) Mag Dip Angle Error Adaptive Measurement [CPP] +///@defgroup filter_mag_dip_angle_error_adaptive_measurement_cpp (0x0D,0x46) Mag Dip Angle Error Adaptive Measurement /// Enable or disable the magnetometer dip angle error adaptive measurement. /// This function can be used to tune the filter performance in the target application /// @@ -3370,7 +3370,7 @@ TypedResult defaultMagDipAngleErrorAdaptive ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_aiding_measurement_enable (0x0D,0x50) Aiding Measurement Enable [CPP] +///@defgroup filter_aiding_measurement_enable_cpp (0x0D,0x50) Aiding Measurement Enable /// Enables / disables the specified aiding measurement source. /// /// @@ -3467,7 +3467,7 @@ TypedResult defaultAidingMeasurementEnable(C::mip_inter ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_run (0x0D,0x05) Run [CPP] +///@defgroup filter_run_cpp (0x0D,0x05) Run /// Manual run command. /// /// If the initialization configuration has the "wait_for_run_command" option enabled, the filter will wait until it receives this command before commencing integration and enabling the Kalman filter. Prior to the receipt of this command, the filter will remain in the filter initialization mode. @@ -3505,7 +3505,7 @@ TypedResult run(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_kinematic_constraint (0x0D,0x51) Kinematic Constraint [CPP] +///@defgroup filter_kinematic_constraint_cpp (0x0D,0x51) Kinematic Constraint /// Controls kinematic constraint model selection for the navigation filter. /// /// See manual for explanation of how the kinematic constraints are applied. @@ -3589,7 +3589,7 @@ TypedResult defaultKinematicConstraint(C::mip_interface& de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_initialization_configuration (0x0D,0x52) Initialization Configuration [CPP] +///@defgroup filter_initialization_configuration_cpp (0x0D,0x52) Initialization Configuration /// Controls the source and values used for initial conditions of the navigation solution. /// /// Notes: Initial conditions are the position, velocity, and attitude of the platform used when the filter starts running or is reset. @@ -3728,7 +3728,7 @@ TypedResult defaultInitializationConfiguration(C::m ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_adaptive_filter_options (0x0D,0x53) Adaptive Filter Options [CPP] +///@defgroup filter_adaptive_filter_options_cpp (0x0D,0x53) Adaptive Filter Options /// Configures the basic setup for auto-adaptive filtering. See product manual for a detailed description of this feature. /// ///@{ @@ -3808,7 +3808,7 @@ TypedResult defaultAdaptiveFilterOptions(C::mip_interface ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_multi_antenna_offset (0x0D,0x54) Multi Antenna Offset [CPP] +///@defgroup filter_multi_antenna_offset_cpp (0x0D,0x54) Multi Antenna Offset /// Set the antenna lever arm. /// /// This command works with devices that utilize multiple antennas. @@ -3892,7 +3892,7 @@ TypedResult defaultMultiAntennaOffset(C::mip_interface& devi ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_rel_pos_configuration (0x0D,0x55) Rel Pos Configuration [CPP] +///@defgroup filter_rel_pos_configuration_cpp (0x0D,0x55) Rel Pos Configuration /// Configure the reference location for filter relative positioning outputs /// ///@{ @@ -3974,7 +3974,7 @@ TypedResult defaultRelPosConfiguration(C::mip_interface& de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_ref_point_lever_arm (0x0D,0x56) Ref Point Lever Arm [CPP] +///@defgroup filter_ref_point_lever_arm_cpp (0x0D,0x56) Ref Point Lever Arm /// Lever arm offset with respect to the sensor for the indicated point of reference. /// This is used to change the location of the indicated point of reference, and will affect filter position and velocity outputs. /// Changing this setting from default will result in a global position offset that depends on vehicle attitude, @@ -4066,7 +4066,7 @@ TypedResult defaultRefPointLeverArm(C::mip_interface& device); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_speed_measurement (0x0D,0x60) Speed Measurement [CPP] +///@defgroup filter_speed_measurement_cpp (0x0D,0x60) Speed Measurement /// Speed aiding measurement, where speed is defined as rate of motion along the vehicle's x-axis direction. /// Can be used by an external odometer/speedometer, for example. /// This command cannot be used if the internal odometer is configured. @@ -4110,7 +4110,7 @@ TypedResult speedMeasurement(C::mip_interface& device, uint8_t ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_speed_lever_arm (0x0D,0x61) Speed Lever Arm [CPP] +///@defgroup filter_speed_lever_arm_cpp (0x0D,0x61) Speed Lever Arm /// Lever arm offset for speed measurements. /// This is used to compensate for an off-center measurement point /// having a different speed due to rotation of the vehicle. @@ -4197,7 +4197,7 @@ TypedResult defaultSpeedLeverArm(C::mip_interface& device, uint8_ ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_wheeled_vehicle_constraint_control (0x0D,0x63) Wheeled Vehicle Constraint Control [CPP] +///@defgroup filter_wheeled_vehicle_constraint_control_cpp (0x0D,0x63) Wheeled Vehicle Constraint Control /// Configure the wheeled vehicle kinematic constraint. /// /// When enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis. @@ -4281,7 +4281,7 @@ TypedResult defaultWheeledVehicleConstraintCont ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_vertical_gyro_constraint_control (0x0D,0x62) Vertical Gyro Constraint Control [CPP] +///@defgroup filter_vertical_gyro_constraint_control_cpp (0x0D,0x62) Vertical Gyro Constraint Control /// Configure the vertical gyro kinematic constraint. /// /// When enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track pitch @@ -4363,7 +4363,7 @@ TypedResult defaultVerticalGyroConstraintControl( ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gnss_antenna_cal_control (0x0D,0x64) Gnss Antenna Cal Control [CPP] +///@defgroup filter_gnss_antenna_cal_control_cpp (0x0D,0x64) Gnss Antenna Cal Control /// Configure the GNSS antenna lever arm calibration. /// /// When enabled, the filter will enable lever arm error tracking, up to the maximum offset specified. @@ -4445,7 +4445,7 @@ TypedResult defaultGnssAntennaCalControl(C::mip_interface ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_set_initial_heading (0x0D,0x03) Set Initial Heading [CPP] +///@defgroup filter_set_initial_heading_cpp (0x0D,0x03) Set Initial Heading /// Set the initial heading angle. /// /// The estimation filter will reset the heading estimate to provided value. If the product supports magnetometer aiding and this feature has been enabled, the heading diff --git a/src/cpp/mip/definitions/commands_gnss.hpp b/src/cpp/mip/definitions/commands_gnss.hpp index 9d01cd366..27a1f922b 100644 --- a/src/cpp/mip/definitions/commands_gnss.hpp +++ b/src/cpp/mip/definitions/commands_gnss.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace commands_gnss { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_cpp MIP Commands [CPP] +///@addtogroup MipCommands_cpp ///@{ -///@defgroup gnss_commands_cpp Gnss Commands [CPP] +///@defgroup gnss_commands_cpp Gnss Commands /// ///@{ @@ -60,7 +60,7 @@ static constexpr const uint16_t GNSS_BEIDOU_ENABLE_B2A = 0x0004; //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_receiver_info (0x0E,0x01) Receiver Info [CPP] +///@defgroup gnss_receiver_info_cpp (0x0E,0x01) Receiver Info /// Return information about the GNSS receivers in the device. /// /// @@ -137,7 +137,7 @@ TypedResult receiverInfo(C::mip_interface& device, uint8_t* numRec ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_signal_configuration (0x0E,0x02) Signal Configuration [CPP] +///@defgroup gnss_signal_configuration_cpp (0x0E,0x02) Signal Configuration /// Configure the GNSS signals used by the device. /// /// @@ -224,7 +224,7 @@ TypedResult defaultSignalConfiguration(C::mip_interface& de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_rtk_dongle_configuration (0x0E,0x10) Rtk Dongle Configuration [CPP] +///@defgroup gnss_rtk_dongle_configuration_cpp (0x0E,0x10) Rtk Dongle Configuration /// Configure the communications with the RTK Dongle connected to the device. /// /// diff --git a/src/cpp/mip/definitions/commands_rtk.hpp b/src/cpp/mip/definitions/commands_rtk.hpp index 9b2dc749d..5550ceded 100644 --- a/src/cpp/mip/definitions/commands_rtk.hpp +++ b/src/cpp/mip/definitions/commands_rtk.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace commands_rtk { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_cpp MIP Commands [CPP] +///@addtogroup MipCommands_cpp ///@{ -///@defgroup rtk_commands_cpp Rtk Commands [CPP] +///@defgroup rtk_commands_cpp Rtk Commands /// ///@{ @@ -77,7 +77,7 @@ enum class LedAction : uint8_t //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_get_status_flags (0x0F,0x01) Get Status Flags [CPP] +///@defgroup rtk_get_status_flags_cpp (0x0F,0x01) Get Status Flags /// ///@{ @@ -250,7 +250,7 @@ TypedResult getStatusFlags(C::mip_interface& device, GetStatusFl ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_get_imei (0x0F,0x02) Get Imei [CPP] +///@defgroup rtk_get_imei_cpp (0x0F,0x02) Get Imei /// ///@{ @@ -312,7 +312,7 @@ TypedResult getImei(C::mip_interface& device, char* imeiOut); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_get_imsi (0x0F,0x03) Get Imsi [CPP] +///@defgroup rtk_get_imsi_cpp (0x0F,0x03) Get Imsi /// ///@{ @@ -374,7 +374,7 @@ TypedResult getImsi(C::mip_interface& device, char* imsiOut); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_get_iccid (0x0F,0x04) Get Iccid [CPP] +///@defgroup rtk_get_iccid_cpp (0x0F,0x04) Get Iccid /// ///@{ @@ -436,7 +436,7 @@ TypedResult getIccid(C::mip_interface& device, char* iccidOut); ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_connected_device_type (0x0F,0x06) Connected Device Type [CPP] +///@defgroup rtk_connected_device_type_cpp (0x0F,0x06) Connected Device Type /// ///@{ @@ -519,7 +519,7 @@ TypedResult defaultConnectedDeviceType(C::mip_interface& de ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_get_act_code (0x0F,0x07) Get Act Code [CPP] +///@defgroup rtk_get_act_code_cpp (0x0F,0x07) Get Act Code /// ///@{ @@ -581,7 +581,7 @@ TypedResult getActCode(C::mip_interface& device, char* activationcod ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_get_modem_firmware_version (0x0F,0x08) Get Modem Firmware Version [CPP] +///@defgroup rtk_get_modem_firmware_version_cpp (0x0F,0x08) Get Modem Firmware Version /// ///@{ @@ -643,7 +643,7 @@ TypedResult getModemFirmwareVersion(C::mip_interface& d ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_get_rssi (0x0F,0x05) Get Rssi [CPP] +///@defgroup rtk_get_rssi_cpp (0x0F,0x05) Get Rssi /// Get the RSSI and connected/disconnected status of modem /// ///@{ @@ -708,7 +708,7 @@ TypedResult getRssi(C::mip_interface& device, bool* validOut, int32_t* ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_service_status (0x0F,0x0A) Service Status [CPP] +///@defgroup rtk_service_status_cpp (0x0F,0x0A) Service Status /// The 3DMRTK will send this message to the server to indicate that the connection should remain open. The Server will respond with information and status. /// ///@{ @@ -808,7 +808,7 @@ TypedResult serviceStatus(C::mip_interface& device, uint32_t rese ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_prod_erase_storage (0x0F,0x20) Prod Erase Storage [CPP] +///@defgroup rtk_prod_erase_storage_cpp (0x0F,0x20) Prod Erase Storage /// This command will erase the selected media to a raw and uninitialized state. ALL DATA WILL BE LOST. /// This command is only available in calibration mode. /// @@ -848,7 +848,7 @@ TypedResult prodEraseStorage(C::mip_interface& device, MediaSe ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_led_control (0x0F,0x21) Led Control [CPP] +///@defgroup rtk_led_control_cpp (0x0F,0x21) Led Control /// This command allows direct control of the LED on the 3DM RTK. This command is only available in calibration mode or Production Test Mode. /// ///@{ @@ -890,7 +890,7 @@ TypedResult ledControl(C::mip_interface& device, const uint8_t* prim ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_rtk_modem_hard_reset (0x0F,0x22) Modem Hard Reset [CPP] +///@defgroup rtk_modem_hard_reset_cpp (0x0F,0x22) Modem Hard Reset /// This command will clear the modem flash. THIS MUST NOT BE DONE OFTEN AS IT CAN DAMAGE THE FLASH! /// This command is only available in calibration mode. /// diff --git a/src/cpp/mip/definitions/commands_system.hpp b/src/cpp/mip/definitions/commands_system.hpp index 323ac173d..b3d1303eb 100644 --- a/src/cpp/mip/definitions/commands_system.hpp +++ b/src/cpp/mip/definitions/commands_system.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace commands_system { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipCommands_cpp MIP Commands [CPP] +///@addtogroup MipCommands_cpp ///@{ -///@defgroup system_commands_cpp System Commands [CPP] +///@defgroup system_commands_cpp System Commands /// ///@{ @@ -54,7 +54,7 @@ static constexpr const uint8_t MIP_SYSTEM_COMMAND_COMM_MODE_GPS = 0x03; //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_system_comm_mode (0x7F,0x10) Comm Mode [CPP] +///@defgroup system_comm_mode_cpp (0x7F,0x10) Comm Mode /// Advanced specialized communication modes. /// /// This command allows the user to communicate directly with various subsystems which may be present in MIP devices (i.e. IMU, GNSS, etc.) diff --git a/src/cpp/mip/definitions/common.hpp b/src/cpp/mip/definitions/common.hpp index 1ba3eca87..da3afbe4c 100644 --- a/src/cpp/mip/definitions/common.hpp +++ b/src/cpp/mip/definitions/common.hpp @@ -2,6 +2,19 @@ #include +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_cpp +///@{ +/// +///@defgroup MipCommands_cpp +///@brief Contains all MIP command definitions. +/// +///@defgroup MipData_cpp +///@brief Contains all MIP data definitions. +/// +///@} +//////////////////////////////////////////////////////////////////////////////// + namespace mip { diff --git a/src/cpp/mip/definitions/data_filter.hpp b/src/cpp/mip/definitions/data_filter.hpp index d08d42c3b..833653706 100644 --- a/src/cpp/mip/definitions/data_filter.hpp +++ b/src/cpp/mip/definitions/data_filter.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace data_filter { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_cpp MIP Data [CPP] +///@addtogroup MipData_cpp ///@{ -///@defgroup filter_data_cpp Filter Data [CPP] +///@defgroup filter_data_cpp Filter Data /// ///@{ @@ -357,7 +357,7 @@ struct GnssAidStatusFlags : Bitfield //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_position_llh (0x82,0x01) Position Llh [CPP] +///@defgroup filter_position_llh_cpp (0x82,0x01) Position Llh /// Filter reported position in the WGS84 geodetic frame. /// ///@{ @@ -397,7 +397,7 @@ struct PositionLlh ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_velocity_ned (0x82,0x02) Velocity Ned [CPP] +///@defgroup filter_velocity_ned_cpp (0x82,0x02) Velocity Ned /// Filter reported velocity in the NED local-level frame. /// ///@{ @@ -437,7 +437,7 @@ struct VelocityNed ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_attitude_quaternion (0x82,0x03) Attitude Quaternion [CPP] +///@defgroup filter_attitude_quaternion_cpp (0x82,0x03) Attitude Quaternion /// 4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame. /// This quaternion satisfies the following relationship: /// @@ -483,7 +483,7 @@ struct AttitudeQuaternion ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_attitude_dcm (0x82,0x04) Attitude Dcm [CPP] +///@defgroup filter_attitude_dcm_cpp (0x82,0x04) Attitude Dcm /// 3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame. /// This matrix satisfies the following relationship: /// @@ -531,7 +531,7 @@ struct AttitudeDcm ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_euler_angles (0x82,0x05) Euler Angles [CPP] +///@defgroup filter_euler_angles_cpp (0x82,0x05) Euler Angles /// Filter reported Euler angles describing the orientation of the device with respect to the NED local-level frame. /// The Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order. /// @@ -572,7 +572,7 @@ struct EulerAngles ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gyro_bias (0x82,0x06) Gyro Bias [CPP] +///@defgroup filter_gyro_bias_cpp (0x82,0x06) Gyro Bias /// Filter reported gyro bias expressed in the sensor frame. /// ///@{ @@ -610,7 +610,7 @@ struct GyroBias ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_accel_bias (0x82,0x07) Accel Bias [CPP] +///@defgroup filter_accel_bias_cpp (0x82,0x07) Accel Bias /// Filter reported accelerometer bias expressed in the sensor frame. /// ///@{ @@ -648,7 +648,7 @@ struct AccelBias ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_position_llh_uncertainty (0x82,0x08) Position Llh Uncertainty [CPP] +///@defgroup filter_position_llh_uncertainty_cpp (0x82,0x08) Position Llh Uncertainty /// Filter reported 1-sigma position uncertainty in the NED local-level frame. /// ///@{ @@ -688,7 +688,7 @@ struct PositionLlhUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_velocity_ned_uncertainty (0x82,0x09) Velocity Ned Uncertainty [CPP] +///@defgroup filter_velocity_ned_uncertainty_cpp (0x82,0x09) Velocity Ned Uncertainty /// Filter reported 1-sigma velocity uncertainties in the NED local-level frame. /// ///@{ @@ -728,7 +728,7 @@ struct VelocityNedUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_euler_angles_uncertainty (0x82,0x0A) Euler Angles Uncertainty [CPP] +///@defgroup filter_euler_angles_uncertainty_cpp (0x82,0x0A) Euler Angles Uncertainty /// Filter reported 1-sigma Euler angle uncertainties. /// The uncertainties are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order. /// @@ -769,7 +769,7 @@ struct EulerAnglesUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gyro_bias_uncertainty (0x82,0x0B) Gyro Bias Uncertainty [CPP] +///@defgroup filter_gyro_bias_uncertainty_cpp (0x82,0x0B) Gyro Bias Uncertainty /// Filter reported 1-sigma gyro bias uncertainties expressed in the sensor frame. /// ///@{ @@ -807,7 +807,7 @@ struct GyroBiasUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_accel_bias_uncertainty (0x82,0x0C) Accel Bias Uncertainty [CPP] +///@defgroup filter_accel_bias_uncertainty_cpp (0x82,0x0C) Accel Bias Uncertainty /// Filter reported 1-sigma accelerometer bias uncertainties expressed in the sensor frame. /// ///@{ @@ -845,7 +845,7 @@ struct AccelBiasUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_timestamp (0x82,0x11) Timestamp [CPP] +///@defgroup filter_timestamp_cpp (0x82,0x11) Timestamp /// GPS timestamp of the Filter data /// /// Should the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time. @@ -890,7 +890,7 @@ struct Timestamp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_status (0x82,0x10) Status [CPP] +///@defgroup filter_status_cpp (0x82,0x10) Status /// Device-specific filter status indicators. /// ///@{ @@ -929,7 +929,7 @@ struct Status ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_linear_accel (0x82,0x0D) Linear Accel [CPP] +///@defgroup filter_linear_accel_cpp (0x82,0x0D) Linear Accel /// Filter-compensated linear acceleration expressed in the vehicle frame. /// Note: The estimated gravity has been removed from this data leaving only linear acceleration. /// @@ -968,7 +968,7 @@ struct LinearAccel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gravity_vector (0x82,0x13) Gravity Vector [CPP] +///@defgroup filter_gravity_vector_cpp (0x82,0x13) Gravity Vector /// Filter reported gravity vector expressed in the vehicle frame. /// ///@{ @@ -1006,7 +1006,7 @@ struct GravityVector ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_comp_accel (0x82,0x1C) Comp Accel [CPP] +///@defgroup filter_comp_accel_cpp (0x82,0x1C) Comp Accel /// Filter-compensated acceleration expressed in the vehicle frame. /// ///@{ @@ -1044,7 +1044,7 @@ struct CompAccel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_comp_angular_rate (0x82,0x0E) Comp Angular Rate [CPP] +///@defgroup filter_comp_angular_rate_cpp (0x82,0x0E) Comp Angular Rate /// Filter-compensated angular rate expressed in the vehicle frame. /// ///@{ @@ -1082,7 +1082,7 @@ struct CompAngularRate ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_quaternion_attitude_uncertainty (0x82,0x12) Quaternion Attitude Uncertainty [CPP] +///@defgroup filter_quaternion_attitude_uncertainty_cpp (0x82,0x12) Quaternion Attitude Uncertainty /// Filter reported quaternion uncertainties. /// ///@{ @@ -1120,7 +1120,7 @@ struct QuaternionAttitudeUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_wgs84_gravity_mag (0x82,0x0F) Wgs84 Gravity Mag [CPP] +///@defgroup filter_wgs84_gravity_mag_cpp (0x82,0x0F) Wgs84 Gravity Mag /// Filter reported WGS84 gravity magnitude. /// ///@{ @@ -1158,7 +1158,7 @@ struct Wgs84GravityMag ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_heading_update_state (0x82,0x14) Heading Update State [CPP] +///@defgroup filter_heading_update_state_cpp (0x82,0x14) Heading Update State /// Filter reported heading update state. /// /// Heading updates can be applied from the sources listed below. Note, some of these sources may be combined. @@ -1210,7 +1210,7 @@ struct HeadingUpdateState ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_magnetic_model (0x82,0x15) Magnetic Model [CPP] +///@defgroup filter_magnetic_model_cpp (0x82,0x15) Magnetic Model /// The World Magnetic Model is used for this data. Please refer to the device user manual for the current version of the model. /// A valid GNSS location is required for the model to be valid. /// @@ -1253,7 +1253,7 @@ struct MagneticModel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_accel_scale_factor (0x82,0x17) Accel Scale Factor [CPP] +///@defgroup filter_accel_scale_factor_cpp (0x82,0x17) Accel Scale Factor /// Filter reported accelerometer scale factor expressed in the sensor frame. /// ///@{ @@ -1291,7 +1291,7 @@ struct AccelScaleFactor ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_accel_scale_factor_uncertainty (0x82,0x19) Accel Scale Factor Uncertainty [CPP] +///@defgroup filter_accel_scale_factor_uncertainty_cpp (0x82,0x19) Accel Scale Factor Uncertainty /// Filter reported 1-sigma accelerometer scale factor uncertainty expressed in the sensor frame. /// ///@{ @@ -1329,7 +1329,7 @@ struct AccelScaleFactorUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gyro_scale_factor (0x82,0x16) Gyro Scale Factor [CPP] +///@defgroup filter_gyro_scale_factor_cpp (0x82,0x16) Gyro Scale Factor /// Filter reported gyro scale factor expressed in the sensor frame. /// ///@{ @@ -1367,7 +1367,7 @@ struct GyroScaleFactor ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gyro_scale_factor_uncertainty (0x82,0x18) Gyro Scale Factor Uncertainty [CPP] +///@defgroup filter_gyro_scale_factor_uncertainty_cpp (0x82,0x18) Gyro Scale Factor Uncertainty /// Filter reported 1-sigma gyro scale factor uncertainty expressed in the sensor frame. /// ///@{ @@ -1405,7 +1405,7 @@ struct GyroScaleFactorUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_mag_bias (0x82,0x1A) Mag Bias [CPP] +///@defgroup filter_mag_bias_cpp (0x82,0x1A) Mag Bias /// Filter reported magnetometer bias expressed in the sensor frame. /// ///@{ @@ -1443,7 +1443,7 @@ struct MagBias ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_mag_bias_uncertainty (0x82,0x1B) Mag Bias Uncertainty [CPP] +///@defgroup filter_mag_bias_uncertainty_cpp (0x82,0x1B) Mag Bias Uncertainty /// Filter reported 1-sigma magnetometer bias uncertainty expressed in the sensor frame. /// ///@{ @@ -1481,7 +1481,7 @@ struct MagBiasUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_standard_atmosphere (0x82,0x20) Standard Atmosphere [CPP] +///@defgroup filter_standard_atmosphere_cpp (0x82,0x20) Standard Atmosphere /// Filter reported standard atmosphere parameters. /// /// The US 1976 Standard Atmosphere Model is used. A valid GNSS location is required for the model to be valid. @@ -1525,7 +1525,7 @@ struct StandardAtmosphere ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_pressure_altitude (0x82,0x21) Pressure Altitude [CPP] +///@defgroup filter_pressure_altitude_cpp (0x82,0x21) Pressure Altitude /// Filter reported pressure altitude. /// /// The US 1976 Standard Atmosphere Model is used to calculate the pressure altitude in meters. @@ -1567,7 +1567,7 @@ struct PressureAltitude ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_density_altitude (0x82,0x22) Density Altitude [CPP] +///@defgroup filter_density_altitude_cpp (0x82,0x22) Density Altitude /// ///@{ @@ -1604,7 +1604,7 @@ struct DensityAltitude ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_antenna_offset_correction (0x82,0x30) Antenna Offset Correction [CPP] +///@defgroup filter_antenna_offset_correction_cpp (0x82,0x30) Antenna Offset Correction /// Filter reported GNSS antenna offset in vehicle frame. /// /// This offset added to any previously stored offset vector to compensate for errors in definition. @@ -1644,7 +1644,7 @@ struct AntennaOffsetCorrection ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_antenna_offset_correction_uncertainty (0x82,0x31) Antenna Offset Correction Uncertainty [CPP] +///@defgroup filter_antenna_offset_correction_uncertainty_cpp (0x82,0x31) Antenna Offset Correction Uncertainty /// Filter reported 1-sigma GNSS antenna offset uncertainties in vehicle frame. /// ///@{ @@ -1682,7 +1682,7 @@ struct AntennaOffsetCorrectionUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_multi_antenna_offset_correction (0x82,0x34) Multi Antenna Offset Correction [CPP] +///@defgroup filter_multi_antenna_offset_correction_cpp (0x82,0x34) Multi Antenna Offset Correction /// Filter reported GNSS antenna offset in vehicle frame. /// /// This offset added to any previously stored offset vector to compensate for errors in definition. @@ -1723,7 +1723,7 @@ struct MultiAntennaOffsetCorrection ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_multi_antenna_offset_correction_uncertainty (0x82,0x35) Multi Antenna Offset Correction Uncertainty [CPP] +///@defgroup filter_multi_antenna_offset_correction_uncertainty_cpp (0x82,0x35) Multi Antenna Offset Correction Uncertainty /// Filter reported 1-sigma GNSS antenna offset uncertainties in vehicle frame. /// ///@{ @@ -1762,7 +1762,7 @@ struct MultiAntennaOffsetCorrectionUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_magnetometer_offset (0x82,0x25) Magnetometer Offset [CPP] +///@defgroup filter_magnetometer_offset_cpp (0x82,0x25) Magnetometer Offset /// Filter reported magnetometer hard iron offset in sensor frame. /// /// This offset added to any previously stored hard iron offset vector to compensate for magnetometer in-run bias errors. @@ -1802,7 +1802,7 @@ struct MagnetometerOffset ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_magnetometer_matrix (0x82,0x26) Magnetometer Matrix [CPP] +///@defgroup filter_magnetometer_matrix_cpp (0x82,0x26) Magnetometer Matrix /// Filter reported magnetometer soft iron matrix in sensor frame. /// /// This matrix is post multiplied to any previously stored soft iron matrix to compensate for magnetometer in-run errors. @@ -1842,7 +1842,7 @@ struct MagnetometerMatrix ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_magnetometer_offset_uncertainty (0x82,0x28) Magnetometer Offset Uncertainty [CPP] +///@defgroup filter_magnetometer_offset_uncertainty_cpp (0x82,0x28) Magnetometer Offset Uncertainty /// Filter reported 1-sigma magnetometer hard iron offset uncertainties in sensor frame. /// ///@{ @@ -1880,7 +1880,7 @@ struct MagnetometerOffsetUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_magnetometer_matrix_uncertainty (0x82,0x29) Magnetometer Matrix Uncertainty [CPP] +///@defgroup filter_magnetometer_matrix_uncertainty_cpp (0x82,0x29) Magnetometer Matrix Uncertainty /// Filter reported 1-sigma magnetometer soft iron matrix uncertainties in sensor frame. /// ///@{ @@ -1918,7 +1918,7 @@ struct MagnetometerMatrixUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_magnetometer_covariance_matrix (0x82,0x2A) Magnetometer Covariance Matrix [CPP] +///@defgroup filter_magnetometer_covariance_matrix_cpp (0x82,0x2A) Magnetometer Covariance Matrix /// ///@{ @@ -1955,7 +1955,7 @@ struct MagnetometerCovarianceMatrix ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_magnetometer_residual_vector (0x82,0x2C) Magnetometer Residual Vector [CPP] +///@defgroup filter_magnetometer_residual_vector_cpp (0x82,0x2C) Magnetometer Residual Vector /// Filter reported magnetometer measurement residuals in vehicle frame. /// ///@{ @@ -1993,7 +1993,7 @@ struct MagnetometerResidualVector ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_clock_correction (0x82,0x32) Clock Correction [CPP] +///@defgroup filter_clock_correction_cpp (0x82,0x32) Clock Correction /// Filter reported GNSS receiver clock error parameters. /// ///@{ @@ -2033,7 +2033,7 @@ struct ClockCorrection ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_clock_correction_uncertainty (0x82,0x33) Clock Correction Uncertainty [CPP] +///@defgroup filter_clock_correction_uncertainty_cpp (0x82,0x33) Clock Correction Uncertainty /// Filter reported 1-sigma GNSS receiver clock error parameters. /// ///@{ @@ -2073,7 +2073,7 @@ struct ClockCorrectionUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gnss_pos_aid_status (0x82,0x43) Gnss Pos Aid Status [CPP] +///@defgroup filter_gnss_pos_aid_status_cpp (0x82,0x43) Gnss Pos Aid Status /// Filter reported GNSS position aiding status /// ///@{ @@ -2113,7 +2113,7 @@ struct GnssPosAidStatus ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gnss_att_aid_status (0x82,0x44) Gnss Att Aid Status [CPP] +///@defgroup filter_gnss_att_aid_status_cpp (0x82,0x44) Gnss Att Aid Status /// Filter reported dual antenna GNSS attitude aiding status /// ///@{ @@ -2152,7 +2152,7 @@ struct GnssAttAidStatus ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_head_aid_status (0x82,0x45) Head Aid Status [CPP] +///@defgroup filter_head_aid_status_cpp (0x82,0x45) Head Aid Status /// Filter reported GNSS heading aiding status /// ///@{ @@ -2197,7 +2197,7 @@ struct HeadAidStatus ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_rel_pos_ned (0x82,0x42) Rel Pos Ned [CPP] +///@defgroup filter_rel_pos_ned_cpp (0x82,0x42) Rel Pos Ned /// Filter reported relative position, with respect to configured reference position /// ///@{ @@ -2235,7 +2235,7 @@ struct RelPosNed ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_ecef_pos (0x82,0x40) Ecef Pos [CPP] +///@defgroup filter_ecef_pos_cpp (0x82,0x40) Ecef Pos /// Filter reported ECEF position /// ///@{ @@ -2273,7 +2273,7 @@ struct EcefPos ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_ecef_vel (0x82,0x41) Ecef Vel [CPP] +///@defgroup filter_ecef_vel_cpp (0x82,0x41) Ecef Vel /// Filter reported ECEF velocity /// ///@{ @@ -2311,7 +2311,7 @@ struct EcefVel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_ecef_pos_uncertainty (0x82,0x36) Ecef Pos Uncertainty [CPP] +///@defgroup filter_ecef_pos_uncertainty_cpp (0x82,0x36) Ecef Pos Uncertainty /// Filter reported 1-sigma position uncertainty in the ECEF frame. /// ///@{ @@ -2349,7 +2349,7 @@ struct EcefPosUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_ecef_vel_uncertainty (0x82,0x37) Ecef Vel Uncertainty [CPP] +///@defgroup filter_ecef_vel_uncertainty_cpp (0x82,0x37) Ecef Vel Uncertainty /// Filter reported 1-sigma velocity uncertainties in the ECEF frame. /// ///@{ @@ -2387,7 +2387,7 @@ struct EcefVelUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_aiding_measurement_summary (0x82,0x46) Aiding Measurement Summary [CPP] +///@defgroup filter_aiding_measurement_summary_cpp (0x82,0x46) Aiding Measurement Summary /// Filter reported aiding measurement summary. This message contains a summary of the specified aiding measurement over the previous measurement interval ending at the specified time. /// ///@{ @@ -2427,7 +2427,7 @@ struct AidingMeasurementSummary ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_odometer_scale_factor_error (0x82,0x47) Odometer Scale Factor Error [CPP] +///@defgroup filter_odometer_scale_factor_error_cpp (0x82,0x47) Odometer Scale Factor Error /// Filter reported odometer scale factor error. The total scale factor estimate is the user indicated scale factor, plus the user indicated scale factor times the scale factor error. /// ///@{ @@ -2465,7 +2465,7 @@ struct OdometerScaleFactorError ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_odometer_scale_factor_error_uncertainty (0x82,0x48) Odometer Scale Factor Error Uncertainty [CPP] +///@defgroup filter_odometer_scale_factor_error_uncertainty_cpp (0x82,0x48) Odometer Scale Factor Error Uncertainty /// Filter reported odometer scale factor error uncertainty. /// ///@{ @@ -2503,7 +2503,7 @@ struct OdometerScaleFactorErrorUncertainty ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_gnss_dual_antenna_status (0x82,0x49) Gnss Dual Antenna Status [CPP] +///@defgroup filter_gnss_dual_antenna_status_cpp (0x82,0x49) Gnss Dual Antenna Status /// Summary information for status of GNSS dual antenna heading estimate. /// ///@{ @@ -2582,7 +2582,7 @@ struct GnssDualAntennaStatus ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_aiding_frame_config_error (0x82,0x50) Aiding Frame Config Error [CPP] +///@defgroup filter_aiding_frame_config_error_cpp (0x82,0x50) Aiding Frame Config Error /// Filter reported aiding source frame configuration error /// /// These estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ). @@ -2623,7 +2623,7 @@ struct AidingFrameConfigError ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_filter_aiding_frame_config_error_uncertainty (0x82,0x51) Aiding Frame Config Error Uncertainty [CPP] +///@defgroup filter_aiding_frame_config_error_uncertainty_cpp (0x82,0x51) Aiding Frame Config Error Uncertainty /// Filter reported aiding source frame configuration error uncertainty /// /// These estimates are used to compensate for small errors to the user-supplied aiding frame configurations (set with (0x13, 0x01) command ). diff --git a/src/cpp/mip/definitions/data_gnss.hpp b/src/cpp/mip/definitions/data_gnss.hpp index 06406b600..24026d7e3 100644 --- a/src/cpp/mip/definitions/data_gnss.hpp +++ b/src/cpp/mip/definitions/data_gnss.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace data_gnss { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_cpp MIP Data [CPP] +///@addtogroup MipData_cpp ///@{ -///@defgroup gnss_data_cpp Gnss Data [CPP] +///@defgroup gnss_data_cpp Gnss Data /// ///@{ @@ -167,7 +167,7 @@ static constexpr const uint32_t GNSS_SV_INFO_MAX_SV_NUMBER = 32; //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_pos_llh (0x81,0x03) Pos Llh [CPP] +///@defgroup gnss_pos_llh_cpp (0x81,0x03) Pos Llh /// GNSS reported position in the WGS84 geodetic frame /// ///@{ @@ -249,7 +249,7 @@ struct PosLlh ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_pos_ecef (0x81,0x04) Pos Ecef [CPP] +///@defgroup gnss_pos_ecef_cpp (0x81,0x04) Pos Ecef /// GNSS reported position in the Earth-centered, Earth-Fixed (ECEF) frame /// ///@{ @@ -318,7 +318,7 @@ struct PosEcef ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_vel_ned (0x81,0x05) Vel Ned [CPP] +///@defgroup gnss_vel_ned_cpp (0x81,0x05) Vel Ned /// GNSS reported velocity in the NED frame /// ///@{ @@ -403,7 +403,7 @@ struct VelNed ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_vel_ecef (0x81,0x06) Vel Ecef [CPP] +///@defgroup gnss_vel_ecef_cpp (0x81,0x06) Vel Ecef /// GNSS reported velocity in the Earth-centered, Earth-Fixed (ECEF) frame /// ///@{ @@ -472,7 +472,7 @@ struct VelEcef ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_dop (0x81,0x07) Dop [CPP] +///@defgroup gnss_dop_cpp (0x81,0x07) Dop /// GNSS reported dilution of precision information. /// ///@{ @@ -561,7 +561,7 @@ struct Dop ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_utc_time (0x81,0x08) Utc Time [CPP] +///@defgroup gnss_utc_time_cpp (0x81,0x08) Utc Time /// GNSS reported Coordinated Universal Time /// ///@{ @@ -635,7 +635,7 @@ struct UtcTime ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_gps_time (0x81,0x09) Gps Time [CPP] +///@defgroup gnss_gps_time_cpp (0x81,0x09) Gps Time /// GNSS reported GPS Time /// ///@{ @@ -704,7 +704,7 @@ struct GpsTime ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_clock_info (0x81,0x0A) Clock Info [CPP] +///@defgroup gnss_clock_info_cpp (0x81,0x0A) Clock Info /// GNSS reported receiver clock parameters /// ///@{ @@ -777,7 +777,7 @@ struct ClockInfo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_fix_info (0x81,0x0B) Fix Info [CPP] +///@defgroup gnss_fix_info_cpp (0x81,0x0B) Fix Info /// GNSS reported position fix type /// ///@{ @@ -889,7 +889,7 @@ struct FixInfo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_sv_info (0x81,0x0C) Sv Info [CPP] +///@defgroup gnss_sv_info_cpp (0x81,0x0C) Sv Info /// GNSS reported space vehicle information /// /// When enabled, these fields will arrive in separate MIP packets @@ -1003,7 +1003,7 @@ struct SvInfo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_hw_status (0x81,0x0D) Hw Status [CPP] +///@defgroup gnss_hw_status_cpp (0x81,0x0D) Hw Status /// GNSS reported hardware status /// ///@{ @@ -1099,7 +1099,7 @@ struct HwStatus ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_dgps_info (0x81,0x0E) Dgps Info [CPP] +///@defgroup gnss_dgps_info_cpp (0x81,0x0E) Dgps Info /// GNSS reported DGNSS status /// ///
Possible Base Station Status Values:
@@ -1188,7 +1188,7 @@ struct DgpsInfo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_dgps_channel (0x81,0x0F) Dgps Channel [CPP] +///@defgroup gnss_dgps_channel_cpp (0x81,0x0F) Dgps Channel /// GNSS reported DGPS Channel Status status /// /// When enabled, a separate field for each active space vehicle will be sent in the packet. @@ -1267,7 +1267,7 @@ struct DgpsChannel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_clock_info_2 (0x81,0x10) Clock Info 2 [CPP] +///@defgroup gnss_clock_info_2_cpp (0x81,0x10) Clock Info 2 /// GNSS reported receiver clock parameters /// /// This supersedes MIP_DATA_DESC_GNSS_CLOCK_INFO with additional information. @@ -1346,7 +1346,7 @@ struct ClockInfo2 ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_gps_leap_seconds (0x81,0x11) Gps Leap Seconds [CPP] +///@defgroup gnss_gps_leap_seconds_cpp (0x81,0x11) Gps Leap Seconds /// GNSS reported leap seconds (difference between GPS and UTC Time) /// ///@{ @@ -1408,7 +1408,7 @@ struct GpsLeapSeconds ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_sbas_info (0x81,0x12) Sbas Info [CPP] +///@defgroup gnss_sbas_info_cpp (0x81,0x12) Sbas Info /// GNSS SBAS status /// ///@{ @@ -1526,7 +1526,7 @@ struct SbasInfo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_sbas_correction (0x81,0x13) Sbas Correction [CPP] +///@defgroup gnss_sbas_correction_cpp (0x81,0x13) Sbas Correction /// GNSS calculated SBAS Correction /// /// UDREI - the variance of a normal distribution associated with the user differential range errors for a @@ -1627,7 +1627,7 @@ struct SbasCorrection ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_rf_error_detection (0x81,0x14) Rf Error Detection [CPP] +///@defgroup gnss_rf_error_detection_cpp (0x81,0x14) Rf Error Detection /// GNSS Error Detection subsystem status /// ///@{ @@ -1725,7 +1725,7 @@ struct RfErrorDetection ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_base_station_info (0x81,0x30) Base Station Info [CPP] +///@defgroup gnss_base_station_info_cpp (0x81,0x30) Base Station Info /// RTCM reported base station information (sourced from RTCM Message 1005 or 1006) /// /// Valid Flag Mapping: @@ -1860,7 +1860,7 @@ struct BaseStationInfo ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_rtk_corrections_status (0x81,0x31) Rtk Corrections Status [CPP] +///@defgroup gnss_rtk_corrections_status_cpp (0x81,0x31) Rtk Corrections Status /// ///@{ @@ -2001,7 +2001,7 @@ struct RtkCorrectionsStatus ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_satellite_status (0x81,0x20) Satellite Status [CPP] +///@defgroup gnss_satellite_status_cpp (0x81,0x20) Satellite Status /// Status information for a GNSS satellite. /// ///@{ @@ -2092,7 +2092,7 @@ struct SatelliteStatus ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_raw (0x81,0x22) Raw [CPP] +///@defgroup gnss_raw_cpp (0x81,0x22) Raw /// GNSS Raw observation. /// ///@{ @@ -2229,7 +2229,7 @@ struct Raw ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_gps_ephemeris (0x81,0x61) Gps Ephemeris [CPP] +///@defgroup gnss_gps_ephemeris_cpp (0x81,0x61) Gps Ephemeris /// GPS Ephemeris Data /// ///@{ @@ -2332,7 +2332,7 @@ struct GpsEphemeris ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_galileo_ephemeris (0x81,0x63) Galileo Ephemeris [CPP] +///@defgroup gnss_galileo_ephemeris_cpp (0x81,0x63) Galileo Ephemeris /// Galileo Ephemeris Data /// ///@{ @@ -2435,7 +2435,7 @@ struct GalileoEphemeris ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_glo_ephemeris (0x81,0x62) Glo Ephemeris [CPP] +///@defgroup gnss_glo_ephemeris_cpp (0x81,0x62) Glo Ephemeris /// Glonass Ephemeris Data /// ///@{ @@ -2523,7 +2523,7 @@ struct GloEphemeris ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_gps_iono_corr (0x81,0x71) Gps Iono Corr [CPP] +///@defgroup gnss_gps_iono_corr_cpp (0x81,0x71) Gps Iono Corr /// Ionospheric Correction Terms for GNSS /// ///@{ @@ -2600,7 +2600,7 @@ struct GpsIonoCorr ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_gnss_galileo_iono_corr (0x81,0x73) Galileo Iono Corr [CPP] +///@defgroup gnss_galileo_iono_corr_cpp (0x81,0x73) Galileo Iono Corr /// Ionospheric Correction Terms for Galileo /// ///@{ diff --git a/src/cpp/mip/definitions/data_sensor.hpp b/src/cpp/mip/definitions/data_sensor.hpp index 4e1a28bd2..bacb1c96b 100644 --- a/src/cpp/mip/definitions/data_sensor.hpp +++ b/src/cpp/mip/definitions/data_sensor.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace data_sensor { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_cpp MIP Data [CPP] +///@addtogroup MipData_cpp ///@{ -///@defgroup sensor_data_cpp Sensor Data [CPP] +///@defgroup sensor_data_cpp Sensor Data /// ///@{ @@ -69,7 +69,7 @@ enum //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_raw_accel (0x80,0x01) Raw Accel [CPP] +///@defgroup sensor_raw_accel_cpp (0x80,0x01) Raw Accel /// Three element vector representing the sensed acceleration. /// This quantity is temperature compensated and expressed in the sensor body frame. /// @@ -107,7 +107,7 @@ struct RawAccel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_raw_gyro (0x80,0x02) Raw Gyro [CPP] +///@defgroup sensor_raw_gyro_cpp (0x80,0x02) Raw Gyro /// Three element vector representing the sensed angular rate. /// This quantity is temperature compensated and expressed in the sensor body frame. /// @@ -145,7 +145,7 @@ struct RawGyro ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_raw_mag (0x80,0x03) Raw Mag [CPP] +///@defgroup sensor_raw_mag_cpp (0x80,0x03) Raw Mag /// Three element vector representing the sensed magnetic field. /// This quantity is temperature compensated and expressed in the vehicle frame. /// @@ -183,7 +183,7 @@ struct RawMag ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_raw_pressure (0x80,0x16) Raw Pressure [CPP] +///@defgroup sensor_raw_pressure_cpp (0x80,0x16) Raw Pressure /// Scalar value representing the sensed ambient pressure. /// This quantity is temperature compensated. /// @@ -221,7 +221,7 @@ struct RawPressure ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_scaled_accel (0x80,0x04) Scaled Accel [CPP] +///@defgroup sensor_scaled_accel_cpp (0x80,0x04) Scaled Accel /// 3-element vector representing the sensed acceleration. /// This quantity is temperature compensated and expressed in the vehicle frame. /// @@ -259,7 +259,7 @@ struct ScaledAccel ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_scaled_gyro (0x80,0x05) Scaled Gyro [CPP] +///@defgroup sensor_scaled_gyro_cpp (0x80,0x05) Scaled Gyro /// 3-element vector representing the sensed angular rate. /// This quantity is temperature compensated and expressed in the vehicle frame. /// @@ -297,7 +297,7 @@ struct ScaledGyro ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_scaled_mag (0x80,0x06) Scaled Mag [CPP] +///@defgroup sensor_scaled_mag_cpp (0x80,0x06) Scaled Mag /// 3-element vector representing the sensed magnetic field. /// This quantity is temperature compensated and expressed in the vehicle frame. /// @@ -335,7 +335,7 @@ struct ScaledMag ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_scaled_pressure (0x80,0x17) Scaled Pressure [CPP] +///@defgroup sensor_scaled_pressure_cpp (0x80,0x17) Scaled Pressure /// Scalar value representing the sensed ambient pressure. /// ///@{ @@ -372,7 +372,7 @@ struct ScaledPressure ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_delta_theta (0x80,0x07) Delta Theta [CPP] +///@defgroup sensor_delta_theta_cpp (0x80,0x07) Delta Theta /// 3-element vector representing the time integral of angular rate. /// This quantity is the integral of sensed angular rate over the period set by the IMU message format. It is expressed in the vehicle frame. /// @@ -410,7 +410,7 @@ struct DeltaTheta ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_delta_velocity (0x80,0x08) Delta Velocity [CPP] +///@defgroup sensor_delta_velocity_cpp (0x80,0x08) Delta Velocity /// 3-element vector representing the time integral of acceleration. /// This quantity is the integral of sensed acceleration over the period set by the IMU message format. It is expressed in the vehicle frame. /// @@ -448,7 +448,7 @@ struct DeltaVelocity ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_comp_orientation_matrix (0x80,0x09) Comp Orientation Matrix [CPP] +///@defgroup sensor_comp_orientation_matrix_cpp (0x80,0x09) Comp Orientation Matrix /// 3x3 Direction Cosine Matrix EQSTART M_{ned}^{veh} EQEND describing the orientation of the device with respect to the NED local-level frame. /// This matrix satisfies the following relationship: /// @@ -495,7 +495,7 @@ struct CompOrientationMatrix ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_comp_quaternion (0x80,0x0A) Comp Quaternion [CPP] +///@defgroup sensor_comp_quaternion_cpp (0x80,0x0A) Comp Quaternion /// 4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame. /// This quaternion satisfies the following relationship: /// @@ -540,7 +540,7 @@ struct CompQuaternion ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_comp_euler_angles (0x80,0x0C) Comp Euler Angles [CPP] +///@defgroup sensor_comp_euler_angles_cpp (0x80,0x0C) Comp Euler Angles /// Euler angles describing the orientation of the device with respect to the NED local-level frame. /// The Euler angles are reported in 3-2-1 (Yaw-Pitch-Roll, AKA Aircraft) order. /// @@ -580,7 +580,7 @@ struct CompEulerAngles ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_comp_orientation_update_matrix (0x80,0x0B) Comp Orientation Update Matrix [CPP] +///@defgroup sensor_comp_orientation_update_matrix_cpp (0x80,0x0B) Comp Orientation Update Matrix /// DEPRECATED! /// ///@{ @@ -617,7 +617,7 @@ struct CompOrientationUpdateMatrix ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_orientation_raw_temp (0x80,0x0D) Orientation Raw Temp [CPP] +///@defgroup sensor_orientation_raw_temp_cpp (0x80,0x0D) Orientation Raw Temp /// DEPRECATED! /// ///@{ @@ -654,7 +654,7 @@ struct OrientationRawTemp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_internal_timestamp (0x80,0x0E) Internal Timestamp [CPP] +///@defgroup sensor_internal_timestamp_cpp (0x80,0x0E) Internal Timestamp /// DEPRECATED! /// ///@{ @@ -691,7 +691,7 @@ struct InternalTimestamp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_pps_timestamp (0x80,0x0F) Pps Timestamp [CPP] +///@defgroup sensor_pps_timestamp_cpp (0x80,0x0F) Pps Timestamp /// DEPRECATED! /// ///@{ @@ -729,7 +729,7 @@ struct PpsTimestamp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_gps_timestamp (0x80,0x12) Gps Timestamp [CPP] +///@defgroup sensor_gps_timestamp_cpp (0x80,0x12) Gps Timestamp /// GPS timestamp of the SENSOR data /// /// Should the PPS become unavailable, the device will revert to its internal clock, which will cause the reported time to drift from true GPS time. @@ -810,7 +810,7 @@ struct GpsTimestamp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_temperature_abs (0x80,0x14) Temperature Abs [CPP] +///@defgroup sensor_temperature_abs_cpp (0x80,0x14) Temperature Abs /// SENSOR reported temperature statistics /// /// Temperature may originate from the MEMS sensors, or be calculated in combination with board temperature sensors. @@ -853,7 +853,7 @@ struct TemperatureAbs ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_up_vector (0x80,0x11) Up Vector [CPP] +///@defgroup sensor_up_vector_cpp (0x80,0x11) Up Vector /// Gyro-stabilized 3-element vector representing the complementary filter's estimated vertical direction. /// This quantity is expressed in the vehicle frame. /// @@ -896,7 +896,7 @@ struct UpVector ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_north_vector (0x80,0x10) North Vector [CPP] +///@defgroup sensor_north_vector_cpp (0x80,0x10) North Vector /// Gyro-stabilized 3-element vector representing the complementary filter's estimate of magnetic north. /// This quantity is expressed in the vehicle frame. /// @@ -936,7 +936,7 @@ struct NorthVector ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_overrange_status (0x80,0x18) Overrange Status [CPP] +///@defgroup sensor_overrange_status_cpp (0x80,0x18) Overrange Status /// ///@{ @@ -1023,7 +1023,7 @@ struct OverrangeStatus ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_sensor_odometer_data (0x80,0x40) Odometer Data [CPP] +///@defgroup sensor_odometer_data_cpp (0x80,0x40) Odometer Data /// ///@{ diff --git a/src/cpp/mip/definitions/data_shared.hpp b/src/cpp/mip/definitions/data_shared.hpp index 6e3a0c7e5..5208a4122 100644 --- a/src/cpp/mip/definitions/data_shared.hpp +++ b/src/cpp/mip/definitions/data_shared.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace data_shared { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_cpp MIP Data [CPP] +///@addtogroup MipData_cpp ///@{ -///@defgroup shared_data_cpp Shared Data [CPP] +///@defgroup shared_data_cpp Shared Data /// ///@{ @@ -54,7 +54,7 @@ static constexpr const uint8_t MIP_DATA_DESC_SHARED_START = 0xD0; //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_shared_event_source (0xFF,0xD0) Event Source [CPP] +///@defgroup shared_event_source_cpp (0xFF,0xD0) Event Source /// Identifies which event trigger caused this packet to be emitted. /// /// Generally this is used to determine whether a packet was emitted @@ -94,7 +94,7 @@ struct EventSource ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_shared_ticks (0xFF,0xD1) Ticks [CPP] +///@defgroup shared_ticks_cpp (0xFF,0xD1) Ticks /// Time since powerup in multiples of the base rate. /// /// The counter will wrap around to 0 after approximately 50 days. @@ -134,7 +134,7 @@ struct Ticks ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_shared_delta_ticks (0xFF,0xD2) Delta Ticks [CPP] +///@defgroup shared_delta_ticks_cpp (0xFF,0xD2) Delta Ticks /// Ticks since the last output of this field. /// /// This field can be used to track the amount of time passed between @@ -175,7 +175,7 @@ struct DeltaTicks ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_shared_gps_timestamp (0xFF,0xD3) Gps Timestamp [CPP] +///@defgroup shared_gps_timestamp_cpp (0xFF,0xD3) Gps Timestamp /// Outputs the current GPS system time in time-of-week and week number format. /// /// For events, this is the time of the event trigger. @@ -247,7 +247,7 @@ struct GpsTimestamp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_shared_delta_time (0xFF,0xD4) Delta Time [CPP] +///@defgroup shared_delta_time_cpp (0xFF,0xD4) Delta Time /// Time in the synchronized clock domain since the last output of this field within the same descriptor set and event instance. /// /// This can be used to track the amount of time passed between @@ -293,7 +293,7 @@ struct DeltaTime ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_shared_reference_timestamp (0xFF,0xD5) Reference Timestamp [CPP] +///@defgroup shared_reference_timestamp_cpp (0xFF,0xD5) Reference Timestamp /// Internal reference timestamp. /// /// This timestamp represents the time at which the corresponding @@ -337,7 +337,7 @@ struct ReferenceTimestamp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_shared_reference_time_delta (0xFF,0xD6) Reference Time Delta [CPP] +///@defgroup shared_reference_time_delta_cpp (0xFF,0xD6) Reference Time Delta /// Delta time since the last packet. /// /// Difference between the time as reported by the shared reference time field, 0xD5, @@ -383,7 +383,7 @@ struct ReferenceTimeDelta ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_shared_external_timestamp (0xFF,0xD7) External Timestamp [CPP] +///@defgroup shared_external_timestamp_cpp (0xFF,0xD7) External Timestamp /// External timestamp in nanoseconds. /// /// This timestamp represents the time at which the corresponding @@ -453,7 +453,7 @@ struct ExternalTimestamp ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_shared_external_time_delta (0xFF,0xD8) External Time Delta [CPP] +///@defgroup shared_external_time_delta_cpp (0xFF,0xD8) External Time Delta /// Delta time since the last packet containing delta external (0xFF,0xD4) or delta gps time (0xFF,0xD8). /// /// Difference between the time as reported by the shared external time field, 0xD7, diff --git a/src/cpp/mip/definitions/data_system.hpp b/src/cpp/mip/definitions/data_system.hpp index 36085aef6..8ddf5d150 100644 --- a/src/cpp/mip/definitions/data_system.hpp +++ b/src/cpp/mip/definitions/data_system.hpp @@ -16,9 +16,9 @@ struct mip_interface; namespace data_system { //////////////////////////////////////////////////////////////////////////////// -///@addtogroup MipData_cpp MIP Data [CPP] +///@addtogroup MipData_cpp ///@{ -///@defgroup system_data_cpp System Data [CPP] +///@defgroup system_data_cpp System Data /// ///@{ @@ -47,7 +47,7 @@ enum //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_system_built_in_test (0xA0,0x01) Built In Test [CPP] +///@defgroup system_built_in_test_cpp (0xA0,0x01) Built In Test /// Contains the continuous built-in-test (BIT) results. /// /// Due to the large size of this field, it is recommended to stream it at @@ -102,7 +102,7 @@ struct BuiltInTest ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_system_time_sync_status (0xA0,0x02) Time Sync Status [CPP] +///@defgroup system_time_sync_status_cpp (0xA0,0x02) Time Sync Status /// Indicates whether a sync has been achieved using the PPS signal. /// ///@{ @@ -140,7 +140,7 @@ struct TimeSyncStatus ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_system_gpio_state (0xA0,0x03) Gpio State [CPP] +///@defgroup system_gpio_state_cpp (0xA0,0x03) Gpio State /// Indicates the state of all of the user GPIO pins. /// /// This message can be used to correlate external signals @@ -195,7 +195,7 @@ struct GpioState ///@} /// //////////////////////////////////////////////////////////////////////////////// -///@defgroup cpp_system_gpio_analog_value (0xA0,0x04) Gpio Analog Value [CPP] +///@defgroup system_gpio_analog_value_cpp (0xA0,0x04) Gpio Analog Value /// Indicates the analog value of the given user GPIO. /// The pin must be configured for analog input. /// diff --git a/src/cpp/mip/mip.hpp b/src/cpp/mip/mip.hpp index df6a9d389..7eef6f48d 100644 --- a/src/cpp/mip/mip.hpp +++ b/src/cpp/mip/mip.hpp @@ -3,13 +3,18 @@ #include "mip_interface.hpp" //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_cpp MIP C++ API +///@addtogroup mip +///@{ +/// +//////////////////////////////////////////////////////////////////////////////// +///@defgroup mip_cpp C++ API /// ///@brief This module contains functions and classes for communicating with a /// MIP device in C++. /// ///@see mip namespace /// +///@} //////////////////////////////////////////////////////////////////////////////// ///@brief A collection of C++ classes and functions covering the full mip api. @@ -19,4 +24,3 @@ namespace mip { } // namespace mip - diff --git a/src/cpp/mip/mip_packet.hpp b/src/cpp/mip/mip_packet.hpp index c5301a016..702d7e00e 100644 --- a/src/cpp/mip/mip_packet.hpp +++ b/src/cpp/mip/mip_packet.hpp @@ -252,6 +252,8 @@ class PacketView : public C::mip_packet_view template class SizedPacketBuf : public PacketView { + static_assert(BufferSize >= PACKET_LENGTH_MIN, "BufferSize must be at least PACKET_LENGTH_MIN bytes"); + public: SizedPacketBuf(uint8_t descriptorSet=INVALID_DESCRIPTOR_SET) : PacketView(mData, sizeof(mData), descriptorSet) {} From 0798a32756987d5848cebb99c68b8196763cf590 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Mon, 7 Oct 2024 16:28:43 -0400 Subject: [PATCH 136/147] Fix MICROSTRAIN_BUILD_TESTS in readme. --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index b18cb80c1..ab500d1ed 100644 --- a/README.md +++ b/README.md @@ -126,17 +126,17 @@ How to Build The following options may be specified when configuring the build with CMake (e.g. `cmake .. -DOPTION=VALUE`): | CMake Option | Default | Description | -| ------------------------------------- |----------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +|---------------------------------------|----------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| | MICROSTRAIN_ENABLE_LOGGING | ON | Builds logging functionality into the library. The user is responsible for configuring a logging callback. | | MICROSTRAIN_LOGGING_MAX_LEVEL | MICROSTRAIN_LOG_LEVEL_WARN | Max log level the SDK is allowed to log. If this is defined, any log level logged at a higher level than this will result in a noop regardless of runtime configuration. Useful if you want some logs, but do not want the overhead compiled into the code. | -| MICROSTRAIN_TIMESTAMP_TYPE | uint64_t | Overrides the default timestamp type. See [Timestamps](https://lord-microstrain.github.io/mip_sdk_documentation/latest/timestamps.html) in the documentation. | +| MICROSTRAIN_TIMESTAMP_TYPE | uint64_t | Overrides the default timestamp type. See [Timestamps](https://lord-microstrain.github.io/mip_sdk_documentation/latest/timestamps.html) in the documentation. | | MICROSTRAIN_ENABLE_CPP | ON | Causes the src/cpp directory to be included in the build. Disable to turn off the C++ api. | | MICROSTRAIN_ENABLE_EXTRAS | ON | Builds some higher level utility classes and functions that may use dynamic memory. | | MICROSTRAIN_ENABLE_SERIAL | ON | Builds the included serial port library. | | MICROSTRAIN_ENABLE_TCP | ON | Builds the included socket library (default enabled). | | MICROSTRAIN_BUILD_PACKAGE | OFF | Adds a `package` target to the project that will build a `.deb`, `.rpm`, or `.zip` file containing the library | | MICROSTRAIN_BUILD_EXAMPLES | OFF | If enabled, the example projects will be built. | -| MICROSTRAIN_BUILD_TESTING | OFF | If enabled, the test programs in the /test directory will be compiled and linked. Run the tests with `ctest`. | +| MICROSTRAIN_BUILD_TESTS | OFF | If enabled, the test programs in the /test directory will be compiled and linked. Run the tests with `ctest`. | | MICROSTRAIN_BUILD_DOCUMENTATION | OFF | If enabled, the documentation will be built with doxygen. You must have doxygen installed. | | MICROSTRAIN_BUILD_DOCUMENTATION_FULL | OFF | Builds internal documentation. | | MICROSTRAIN_BUILD_DOCUMENTATION_QUIET | ON | Suppress standard doxygen output. | From b39113c5f3eadca1dfa0b21acab94714ddff7b89 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Tue, 15 Oct 2024 09:39:08 -0400 Subject: [PATCH 137/147] Updated docker build script to use existing image for docs packaging --- .devcontainer/docker_build.sh | 16 +++++++--------- Jenkinsfile | 2 +- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/.devcontainer/docker_build.sh b/.devcontainer/docker_build.sh index a2d94caad..1f6de92e6 100755 --- a/.devcontainer/docker_build.sh +++ b/.devcontainer/docker_build.sh @@ -36,14 +36,7 @@ script_dir="$(cd "$(dirname "${BASH_SOURCE[0]}")" &> /dev/null && pwd)" project_dir="${script_dir}/.." docker_project_dir="/home/microstrain/mipsdk" dockerfile="${script_dir}/Dockerfile.${os}" - -if [ ${build_docs} = true ]; then - build_dir_name="build_docs" - image_name="microstrain/mipsdk_docs_builder:${arch}" -else - build_dir_name="build_${os}_${arch}" - image_name="microstrain/mipsdk_${os}_builder:${arch}" -fi +image_name="microstrain/mipsdk_${os}_builder:${arch}" # Build the docker image @@ -61,9 +54,14 @@ if [ "${ISHUDSONBUILD}" != "True" ]; then fi if [ ${build_docs} = true ]; then - configure_flags="-DMICROSTRAIN_BUILD_DOCUMENTATION=ON" + build_dir_name="build_docs" + configure_flags="\ + -DMICROSTRAIN_BUILD_DOCUMENTATION=ON \ + -MICROSTRAIN_BUILD_DOCUMENTATION_QUIET=OFF \ + -DCMAKE_BUILD_TYPE=RELEASE" build_target="package_docs" else + build_dir_name="build_${os}_${arch}" configure_flags="\ -DMICROSTRAIN_BUILD_EXAMPLES=ON \ -DMICROSTRAIN_BUILD_PACKAGE=ON \ diff --git a/Jenkinsfile b/Jenkinsfile index 495092cf9..d3c420900 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -48,7 +48,7 @@ pipeline { script { checkoutRepo() env.setProperty('BRANCH_NAME', branchName()) - sh "./.devcontainer/docker_build.sh --docs" + sh "./.devcontainer/docker_build.sh --os ubuntu --arch amd64 --docs" archiveArtifacts artifacts: 'build_docs/mipsdk_*' } } From 6b1d9ea6d97397748426f6761837407ac714cffe Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Tue, 15 Oct 2024 09:43:01 -0400 Subject: [PATCH 138/147] Fixed build script typo --- .devcontainer/docker_build.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.devcontainer/docker_build.sh b/.devcontainer/docker_build.sh index 1f6de92e6..00dd2b18c 100755 --- a/.devcontainer/docker_build.sh +++ b/.devcontainer/docker_build.sh @@ -57,7 +57,7 @@ if [ ${build_docs} = true ]; then build_dir_name="build_docs" configure_flags="\ -DMICROSTRAIN_BUILD_DOCUMENTATION=ON \ - -MICROSTRAIN_BUILD_DOCUMENTATION_QUIET=OFF \ + -DMICROSTRAIN_BUILD_DOCUMENTATION_QUIET=OFF \ -DCMAKE_BUILD_TYPE=RELEASE" build_target="package_docs" else From d19374f490801706b3f1612dcff842c1fef000ec Mon Sep 17 00:00:00 2001 From: Robert Christensen Date: Mon, 28 Oct 2024 14:45:43 -0400 Subject: [PATCH 139/147] Tweak: make Span copyable/movable by un-const-ing data pointer and count --- src/cpp/microstrain/common/span.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/cpp/microstrain/common/span.hpp b/src/cpp/microstrain/common/span.hpp index f211ce99e..3c3593f39 100644 --- a/src/cpp/microstrain/common/span.hpp +++ b/src/cpp/microstrain/common/span.hpp @@ -38,7 +38,7 @@ struct Span using const_pointer = const T*; using const_reference = const T&; - Span(pointer ptr) : m_ptr(ptr) {} + constexpr Span(pointer ptr) : m_ptr(ptr) {} constexpr pointer begin() const noexcept { return m_ptr; } constexpr pointer end() const noexcept { return m_ptr+extent; } @@ -60,7 +60,7 @@ struct Span [[nodiscard]] constexpr Span subspan() const { return {m_ptr+Offset}; } private: - const pointer m_ptr = nullptr; + pointer m_ptr = nullptr; }; @@ -100,8 +100,8 @@ struct Span [[nodiscard]] constexpr Span subspan() const { return {m_ptr+Offset, Count}; } private: - pointer const m_ptr = nullptr; - size_t const m_cnt = 0; + pointer m_ptr = nullptr; + size_t m_cnt = 0; }; From 14403bd1b2a91d29630879c36bba01a15bdce8a4 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 1 Nov 2024 12:45:14 -0400 Subject: [PATCH 140/147] Updates per PR feedback (WIP). --- docs/miscellaneous.md | 4 ++-- docs/serialization.md | 2 +- examples/mip_packet_example.cpp | 16 ++++++++-------- src/c/mip/mip_cmdqueue.h | 6 +++--- src/c/mip/mip_dispatch.h | 6 +++--- src/c/mip/mip_packet.h | 1 + src/cpp/mip/mip_packet.hpp | 2 +- 7 files changed, 19 insertions(+), 18 deletions(-) diff --git a/docs/miscellaneous.md b/docs/miscellaneous.md index 6dc371978..5c90128b5 100644 --- a/docs/miscellaneous.md +++ b/docs/miscellaneous.md @@ -6,9 +6,9 @@ Known Issues and Workarounds {#known_issues} ### suppress_ack parameters are not supported -Some commands accept a parameter named `suppress_ack` which acts to prevent +Some commands accept a parameter named `suppress_ack` which prevents the standard ack/nack reply from being returned by the device, e.g. the -3DM Poll Data command. Use of this parameter is not directly supported by the MIP SDK +3DM Poll Data command. Use of this parameter is not fully supported by the MIP SDK and will cause the command to appear to time out after a short delay. If you wish to use this feature, (i.e. just send the command without waiting for an ACK/NACK), diff --git a/docs/serialization.md b/docs/serialization.md index f52d63316..1b87d6651 100644 --- a/docs/serialization.md +++ b/docs/serialization.md @@ -10,7 +10,7 @@ To (de)serialize a buffer, follow these steps: 1. Create a serializer and initialize it via @ref microstrain_serializer_init_insertion or @ref microstrain_serializer_init_extraction, depending on whether you're writing or reading data. -2. Call `microstrain_insert_*` or `microstrain_extract_*` for each parameter. E.g. @ref microstrain_extract_u32. +2. Call `microstrain_insert_*` or `microstrain_extract_*` for each parameter. E.g. [microstrain_extract_u32](@ref mip::C::microstrain_extract_u32]. 3. Call @ref microstrain_serializer_is_ok to check if all the data was written/read successfully (i.e. fit in the buffer). Alternatively, to verify if exactly buffer_size bytes were read/written, use @ref microstrain_serializer_is_complete. 4. Transmit the written buffer or use the deserialized parameters. diff --git a/examples/mip_packet_example.cpp b/examples/mip_packet_example.cpp index ad91b0977..e0f740eb6 100644 --- a/examples/mip_packet_example.cpp +++ b/examples/mip_packet_example.cpp @@ -35,7 +35,7 @@ void print_packet(const mip::PacketView& packet, const char* name) ); // Print each byte in the packet, including header and checksum. - for(size_t i=0; i buffer) { C::mip_packet_from_buffer(this, const_cast(buffer.data()), buffer.size()); } // From bfcabb2eecab59ca4a139f6f86c0ea421de770e0 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Fri, 1 Nov 2024 16:59:00 -0400 Subject: [PATCH 141/147] Fix documentation for many C functions and clean up C group names. --- docs/mip_parser.md | 2 +- docs/serialization.md | 2 +- src/c/mip/mip_all.h | 2 +- src/c/mip/mip_cmdqueue.c | 12 ++++++++++++ src/c/mip/mip_cmdqueue.h | 20 +++++++------------- src/c/mip/mip_descriptors.c | 5 +++++ src/c/mip/mip_device_models.h | 3 +-- src/c/mip/mip_dispatch.c | 3 +++ src/c/mip/mip_dispatch.h | 14 +++++++++++--- src/c/mip/mip_field.c | 14 +++++++++++++- src/c/mip/mip_field.h | 8 ++++---- src/c/mip/mip_interface.c | 15 ++++++++++++++- src/c/mip/mip_packet.c | 12 ++++++++++++ src/c/mip/mip_packet.h | 6 +++--- src/c/mip/mip_parser.c | 13 +++++++++++++ src/c/mip/mip_parser.h | 2 +- src/c/mip/mip_serialization.c | 13 +++++++++++++ src/cpp/mip/definitions/common.hpp | 4 ++-- src/cpp/mip/mip_field.hpp | 14 +++++++------- src/cpp/mip/mip_packet.hpp | 2 +- 20 files changed, 125 insertions(+), 41 deletions(-) diff --git a/docs/mip_parser.md b/docs/mip_parser.md index 8f96025cf..523968cdf 100644 --- a/docs/mip_parser.md +++ b/docs/mip_parser.md @@ -81,7 +81,7 @@ As an example, for a 115200 baud serial link a timeout of 30 ms would be about right. You can use the mip_timeout_from_baudrate() function to compute an appropriate timeout. -See ["mip_timestamp (C)"](@ref mip_timestamp) or [mip::Timestamp (C++)](@ref mip::Timestamp) +See ["microstrain_embedded_timestamp (C)"](@ref microstrain::C::microstrain_embedded_timestamp) or microstrain::EmbeddedTimestamp (C++) The Packet Parsing Process {#parsing_process} -------------------------- diff --git a/docs/serialization.md b/docs/serialization.md index 1b87d6651..5eb37e7db 100644 --- a/docs/serialization.md +++ b/docs/serialization.md @@ -10,7 +10,7 @@ To (de)serialize a buffer, follow these steps: 1. Create a serializer and initialize it via @ref microstrain_serializer_init_insertion or @ref microstrain_serializer_init_extraction, depending on whether you're writing or reading data. -2. Call `microstrain_insert_*` or `microstrain_extract_*` for each parameter. E.g. [microstrain_extract_u32](@ref mip::C::microstrain_extract_u32]. +2. Call `microstrain_insert_*` or `microstrain_extract_*` for each parameter. E.g. [microstrain_extract_u32](@ref microstrain::C::microstrain_extract_u32). 3. Call @ref microstrain_serializer_is_ok to check if all the data was written/read successfully (i.e. fit in the buffer). Alternatively, to verify if exactly buffer_size bytes were read/written, use @ref microstrain_serializer_is_complete. 4. Transmit the written buffer or use the deserialized parameters. diff --git a/src/c/mip/mip_all.h b/src/c/mip/mip_all.h index 6e51c5fd8..7b535c1eb 100644 --- a/src/c/mip/mip_all.h +++ b/src/c/mip/mip_all.h @@ -4,7 +4,7 @@ ///@defgroup mip MIP ///@{ /// -///@defgroup mip_c C API +///@defgroup mip_c MIP C API ///@brief This module contains functions and classes for communicating with a /// MIP device in %C. /// diff --git a/src/c/mip/mip_cmdqueue.c b/src/c/mip/mip_cmdqueue.c index 8f1adcc76..8b225b355 100644 --- a/src/c/mip/mip_cmdqueue.c +++ b/src/c/mip/mip_cmdqueue.c @@ -13,6 +13,12 @@ #define MIP_INDEX_REPLY_DESCRIPTOR 0 #define MIP_INDEX_REPLY_ACK_CODE 1 +#ifdef __cplusplus +namespace mip { +namespace C { +extern "C" { +#endif + //////////////////////////////////////////////////////////////////////////////// ///@brief Initialize a pending command with no reponse data or additional time. @@ -556,3 +562,9 @@ uint16_t mip_cmd_queue_diagnostic_cmd_errors(const mip_cmd_queue* queue) } #endif // MIP_ENABLE_DIAGNOSTICS + +#ifdef __cplusplus +} // extern "C" +} // namespace C +} // namespace mip +#endif diff --git a/src/c/mip/mip_cmdqueue.h b/src/c/mip/mip_cmdqueue.h index 7941a596e..35b7b6fb7 100644 --- a/src/c/mip/mip_cmdqueue.h +++ b/src/c/mip/mip_cmdqueue.h @@ -14,19 +14,16 @@ extern "C" { #endif //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_c -///@{ - -//////////////////////////////////////////////////////////////////////////////// -///@defgroup MipCommandHandling_c Mip Command Handling +///@defgroup MipCommandHandling_c Mip Command Handling +///@ingroup mip_c /// -///@brief Functions for handling command responses. +///@brief Functions for processing command responses. /// ///@{ //////////////////////////////////////////////////////////////////////////////// -///@defgroup PendingCommand_c Mip Pending Command Functions +///@defgroup MipPendingCommand_c Pending Mip Commands /// ///@{ @@ -37,7 +34,6 @@ extern "C" { /// considered an internal implementation detail. Avoid accessing them directly /// as they are subject to change in future versions of this software. /// - typedef struct mip_pending_cmd { struct mip_pending_cmd* _next; ///<@private Next command in the queue. @@ -72,7 +68,7 @@ bool mip_pending_cmd_check_timeout(const mip_pending_cmd* cmd, mip_timestamp now ///@} //////////////////////////////////////////////////////////////////////////////// -///@defgroup CommandQueue_c Mip Command Queue Functions +///@defgroup MipCommandQueue_c Mip Command Queue /// ///@note This should be considered an "opaque" structure; its members should be /// considered an internal implementation detail. Avoid accessing them directly @@ -89,11 +85,10 @@ bool mip_pending_cmd_check_timeout(const mip_pending_cmd* cmd, mip_timestamp now /// considered an internal implementation detail. Avoid accessing them directly /// as they are subject to change in future versions of this software. /// - typedef struct mip_cmd_queue { - mip_pending_cmd* _first_pending_cmd; - mip_timeout _base_timeout; + mip_pending_cmd* _first_pending_cmd; ///<@private Pointer to the first pending command, if any. + mip_timeout _base_timeout; ///<@private Base command timeout. #ifdef MIP_ENABLE_DIAGNOSTICS uint16_t _diag_cmds_queued; ///<@private Number of queued commands. @@ -130,7 +125,6 @@ uint16_t mip_cmd_queue_diagnostic_cmd_timeouts(const mip_cmd_queue* queue); uint16_t mip_cmd_queue_diagnostic_cmd_errors(const mip_cmd_queue* queue); #endif // MIP_ENABLE_DIAGNOSTICS -///@} ///@} ///@} //////////////////////////////////////////////////////////////////////////////// diff --git a/src/c/mip/mip_descriptors.c b/src/c/mip/mip_descriptors.c index 51a3d99d6..b4a754615 100644 --- a/src/c/mip/mip_descriptors.c +++ b/src/c/mip/mip_descriptors.c @@ -8,6 +8,9 @@ namespace mip { extern "C" { #endif // __cplusplus +//////////////////////////////////////////////////////////////////////////////// +///@addtogroup mip_c +///@{ //////////////////////////////////////////////////////////////////////////////// ///@brief Determines if the descriptor set is valid. @@ -163,6 +166,8 @@ void extract_mip_function_selector(microstrain_serializer* serializer, enum mip_ *self = (enum mip_function_selector)tmp; } +///@} +//////////////////////////////////////////////////////////////////////////////// #ifdef __cplusplus } // extern "C" diff --git a/src/c/mip/mip_device_models.h b/src/c/mip/mip_device_models.h index 2fb5f4f27..5f9769e24 100644 --- a/src/c/mip/mip_device_models.h +++ b/src/c/mip/mip_device_models.h @@ -2,8 +2,7 @@ #ifdef __cplusplus namespace mip { -namespace C -{ +namespace C { extern "C" { #endif // __cplusplus diff --git a/src/c/mip/mip_dispatch.c b/src/c/mip/mip_dispatch.c index 0d3ba1d26..58c551071 100644 --- a/src/c/mip/mip_dispatch.c +++ b/src/c/mip/mip_dispatch.c @@ -10,8 +10,10 @@ #ifdef __cplusplus namespace mip { namespace C { +extern "C" { #endif + //////////////////////////////////////////////////////////////////////////////// ///@brief Type of dispatch callback. /// @@ -363,6 +365,7 @@ void mip_dispatcher_dispatch_packet(mip_dispatcher* self, const mip_packet_view* } #ifdef __cplusplus +} // extern "C" } // namespace C } // namespace mip #endif diff --git a/src/c/mip/mip_dispatch.h b/src/c/mip/mip_dispatch.h index f4cfc46d9..ed956e629 100644 --- a/src/c/mip/mip_dispatch.h +++ b/src/c/mip/mip_dispatch.h @@ -21,10 +21,16 @@ extern "C" { //////////////////////////////////////////////////////////////////////////////// -///@defgroup MipDispatch_c Mip Data Dispatch System +///@defgroup MipDispatch_c Data Dispatch /// ///@brief System for issuing callbacks from MIP packets or fields. /// +/// The user's application may register handlers in the dispatcher to receive +/// callbacks for reception of various types of data. Packets, fields, and +/// deserialized data callbacks may be registered. +/// +///@see mip_dispatch +/// ///@{ @@ -69,7 +75,7 @@ enum { }; //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_dispatch_handler Mip Data Dispatch Handler +///@defgroup MipDispatchHandler_c Dispatch Handler /// /// This represents a binding between a MIP descriptor pair and a callback /// function. @@ -112,7 +118,9 @@ bool mip_dispatch_handler_is_enabled(mip_dispatch_handler* handler); ///@} //////////////////////////////////////////////////////////////////////////////// -///@defgroup MipDispatcher Mip Data Dispatcher +///@defgroup MipDispatcher_c Mip Dispatcher +/// +/// This is included in the Mip Interface to allow the registration of callbacks. /// ///@{ diff --git a/src/c/mip/mip_field.c b/src/c/mip/mip_field.c index ce66d6b8d..99e39efe8 100644 --- a/src/c/mip/mip_field.c +++ b/src/c/mip/mip_field.c @@ -9,9 +9,15 @@ #include +#ifdef __cplusplus +namespace mip { +namespace C { +extern "C" { +#endif + //////////////////////////////////////////////////////////////////////////////// -///@brief Constructs a %mip_field given the parameters. +///@brief Constructs a field view given the parameters. /// ///@param field ///@param descriptor_set @@ -233,3 +239,9 @@ bool mip_field_next_in_packet(mip_field_view* field, const mip_packet_view* pack return mip_field_is_valid(field); } + +#ifdef __cplusplus +} // extern "C" +} // namespace C +} // namespace mip +#endif diff --git a/src/c/mip/mip_field.h b/src/c/mip/mip_field.h index 1ea259aa1..dbc8b4c4a 100644 --- a/src/c/mip/mip_field.h +++ b/src/c/mip/mip_field.h @@ -16,7 +16,7 @@ extern "C" { ///@{ //////////////////////////////////////////////////////////////////////////////// -///@defgroup mip_field_c Mip Fields +///@defgroup MipFields_c Mip Fields /// ///@brief Functions for processing received MIP fields. /// @@ -42,7 +42,7 @@ extern "C" { /// /// This structure references the original packet data and does not contain a /// copy of the field payload. Therefore, the data buffer must exist as long as -/// there are %mip_field instances which reference it (even if the field payload +/// there are instances which reference it (even if the field payload /// itself is not used directly). /// ///@note This should be considered an "opaque" structure; its members should be @@ -62,7 +62,7 @@ typedef struct mip_field_view void mip_field_init(mip_field_view* field, uint8_t descriptor_set, uint8_t field_descriptor, const uint8_t* payload, uint8_t payload_length); //////////////////////////////////////////////////////////////////////////////// -///@defgroup FieldAccess Field Accessors [C] +///@defgroup MipFieldAccess_c Mip Field Accessors /// ///@brief Functions for inspecting a MIP field. /// @@ -77,7 +77,7 @@ bool mip_field_is_valid(const mip_field_view* field); ///@} //////////////////////////////////////////////////////////////////////////////// -///@defgroup FieldIteration_c Field Iteration [C] +///@defgroup MipFieldIteration_c Mip Field Iteration /// ///@brief Functions for iterating over fields in a MIP packet. /// diff --git a/src/c/mip/mip_interface.c b/src/c/mip/mip_interface.c index 05d0a39ce..03740d269 100644 --- a/src/c/mip/mip_interface.c +++ b/src/c/mip/mip_interface.c @@ -9,6 +9,12 @@ #include +#ifdef __cplusplus +namespace mip { +namespace C { +extern "C" { +#endif + //////////////////////////////////////////////////////////////////////////////// ///@typedef mip::C::mip_send_callback /// @@ -729,4 +735,11 @@ void mip_interface_register_extractor( { mip_dispatch_handler_init_extractor(handler, descriptor_set, field_descriptor, extractor, field_ptr); mip_dispatcher_add_handler(&device->_dispatcher, handler); -} \ No newline at end of file +} + + +#ifdef __cplusplus +} // extern "C" +} // namespace C +} // namespace mip +#endif diff --git a/src/c/mip/mip_packet.c b/src/c/mip/mip_packet.c index d5d3c9353..e387270e0 100644 --- a/src/c/mip/mip_packet.c +++ b/src/c/mip/mip_packet.c @@ -9,6 +9,12 @@ #include #include +#ifdef __cplusplus +namespace mip { +namespace C { +extern "C" { +#endif + // // Initialization @@ -465,3 +471,9 @@ void mip_packet_reset(mip_packet_view* packet, uint8_t descriptor_set) mip_packet_create(packet, mip_packet_buffer(packet), mip_packet_buffer_size(packet), descriptor_set); } + +#ifdef __cplusplus +} // extern "C" +} // namespace C +} // namespace mip +#endif diff --git a/src/c/mip/mip_packet.h b/src/c/mip/mip_packet.h index 5f565a201..1c0306c8f 100644 --- a/src/c/mip/mip_packet.h +++ b/src/c/mip/mip_packet.h @@ -55,7 +55,7 @@ typedef struct mip_packet_view //////////////////////////////////////////////////////////////////////////////// -///@defgroup PacketBuilding Packet Building +///@defgroup MipPacketBuilding_c Packet Building /// ///@brief Functions for building new MIP packets. /// @@ -78,7 +78,7 @@ void mip_packet_reset(mip_packet_view* packet, uint8_t descriptor_set); ///@} //////////////////////////////////////////////////////////////////////////////// -///@defgroup Accessors_c Accessors +///@defgroup MipPacketAccessors_c Packet Inspection /// ///@brief Functions for accessing information about an existing MIP packet. /// @@ -90,7 +90,7 @@ void mip_packet_reset(mip_packet_view* packet, uint8_t descriptor_set); /// calls it, e.g. mip_packet_is_valid()), these functions may also be used on /// packets which are under construction via the PacketBuilding functions. /// -///@caution Do not call the packet-building functions unless you know the +///@warning Do not call the packet-building functions unless you know the /// input buffer is not const. /// ///@{ diff --git a/src/c/mip/mip_parser.c b/src/c/mip/mip_parser.c index e9c934db5..f1b7f86ae 100644 --- a/src/c/mip/mip_parser.c +++ b/src/c/mip/mip_parser.c @@ -5,6 +5,12 @@ #include +#ifdef __cplusplus +namespace mip { +namespace C { +extern "C" { +#endif + #define MIPPARSER_RESET_LENGTH 1 @@ -482,3 +488,10 @@ mip_timeout mip_timeout_from_baudrate(uint32_t baudrate) // timeout [ms] = (packet_time [s]) * (1000 [ms/s]) * tolerance return num_symbols * 1500 / baudrate; } + + +#ifdef __cplusplus +} // extern "C" +} // namespace C +} // namespace mip +#endif diff --git a/src/c/mip/mip_parser.h b/src/c/mip/mip_parser.h index 830469f3f..7499528e4 100644 --- a/src/c/mip/mip_parser.h +++ b/src/c/mip/mip_parser.h @@ -13,7 +13,7 @@ extern "C" { #endif //////////////////////////////////////////////////////////////////////////////// -///@addtogroup mip_c MIP C API +///@addtogroup mip_c /// ///@brief This module contains all of the C submodules. /// diff --git a/src/c/mip/mip_serialization.c b/src/c/mip/mip_serialization.c index 58a855c5f..83e97964f 100644 --- a/src/c/mip/mip_serialization.c +++ b/src/c/mip/mip_serialization.c @@ -4,6 +4,12 @@ #include +#ifdef __cplusplus +namespace mip { +namespace C { +extern "C" { +#endif + //////////////////////////////////////////////////////////////////////////////// ///@brief Initialize a serialization struct for creation of a new field at the @@ -65,3 +71,10 @@ void microstrain_serializer_init_from_field(mip_serializer* serializer, const mi { microstrain_serializer_init_extraction(serializer, mip_field_payload(field), mip_field_payload_length(field)); } + + +#ifdef __cplusplus +} // extern "C" +} // namespace C +} // namespace mip +#endif diff --git a/src/cpp/mip/definitions/common.hpp b/src/cpp/mip/definitions/common.hpp index da3afbe4c..dd8de08c1 100644 --- a/src/cpp/mip/definitions/common.hpp +++ b/src/cpp/mip/definitions/common.hpp @@ -6,10 +6,10 @@ ///@addtogroup mip_cpp ///@{ /// -///@defgroup MipCommands_cpp +///@defgroup MipCommands_cpp Mip Commands ///@brief Contains all MIP command definitions. /// -///@defgroup MipData_cpp +///@defgroup MipData_cpp Mip Data ///@brief Contains all MIP data definitions. /// ///@} diff --git a/src/cpp/mip/mip_field.hpp b/src/cpp/mip/mip_field.hpp index a7950563e..ddc3332f3 100644 --- a/src/cpp/mip/mip_field.hpp +++ b/src/cpp/mip/mip_field.hpp @@ -40,15 +40,15 @@ class FieldView : public C::mip_field_view // C function wrappers // - ///@copydoc mip_field_descriptor_set + ///@copydoc mip::C::mip_field_descriptor_set uint8_t descriptorSet() const { return C::mip_field_descriptor_set(this); } - ///@copydoc mip_field_field_descriptor + ///@copydoc mip::C::mip_field_field_descriptor uint8_t fieldDescriptor() const { return C::mip_field_field_descriptor(this); } ///@brief Returns the descriptor set and field descriptor. CompositeDescriptor descriptor() const { return {descriptorSet(), fieldDescriptor()}; } - ///@copydoc mip_field_payload_length + ///@copydoc mip::C::mip_field_payload_length uint8_t payloadLength() const { return C::mip_field_payload_length(this); } - ///@copydoc mip_field_payload + ///@copydoc mip::C::mip_field_payload const uint8_t* payload() const { return C::mip_field_payload(this); } ///@brief Index the payload at the given location. @@ -60,12 +60,12 @@ class FieldView : public C::mip_field_view microstrain::Span payloadSpan() const { return {payload(), payloadLength()}; } - ///@copydoc mip_field_is_valid + ///@copydoc mip::C::mip_field_is_valid bool isValid() const { return C::mip_field_is_valid(this); } - ///@copybrief mip_field_next_after + ///@copybrief mip::C::mip_field_next_after FieldView nextAfter() const { return C::mip_field_next_after(this); } - ///@copybrief mip_field_next + ///@copybrief mip::C::mip_field_next bool next() { return C::mip_field_next(this); } // diff --git a/src/cpp/mip/mip_packet.hpp b/src/cpp/mip/mip_packet.hpp index c29704300..e94f6246a 100644 --- a/src/cpp/mip/mip_packet.hpp +++ b/src/cpp/mip/mip_packet.hpp @@ -44,7 +44,7 @@ class PacketView : public C::mip_packet_view public: ///@copydoc mip::C::mip_packet_create PacketView(uint8_t* buffer, size_t bufferSize, uint8_t descriptorSet) { C::mip_packet_create(this, buffer, bufferSize, descriptorSet); } - ///@copydoc mip_packet_from_buffer + ///@copydoc mip::C::mip_packet_from_buffer PacketView(const uint8_t* buffer, size_t length) { C::mip_packet_from_buffer(this, const_cast(buffer), length); } /// Constructs a C++ %PacketRef class from the base C object. PacketView(const C::mip_packet_view* other) { std::memcpy(static_cast(this), other, sizeof(*this)); } From 821a2f71ea2c576ff74c1c6e4b7a6cc9ee3ce4c0 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 5 Nov 2024 11:39:30 -0500 Subject: [PATCH 142/147] Rename CSV example to PrettyPrinter. --- examples/CMakeLists.txt | 4 ++-- examples/{CSV/csv.cpp => PrettyPrinter/pretty_printer.cpp} | 0 examples/{CSV => PrettyPrinter}/stringify.cpp | 0 examples/{CSV => PrettyPrinter}/stringify.hpp | 0 4 files changed, 2 insertions(+), 2 deletions(-) rename examples/{CSV/csv.cpp => PrettyPrinter/pretty_printer.cpp} (100%) rename examples/{CSV => PrettyPrinter}/stringify.cpp (100%) rename examples/{CSV => PrettyPrinter}/stringify.hpp (100%) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 62e60efc2..1a88e06d0 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -75,8 +75,8 @@ if(MICROSTRAIN_ENABLE_CPP) target_link_libraries(Threads PUBLIC pthread) endif() if(MIP_ENABLE_METADATA) - add_mip_example(CsvExample "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/CSV/csv.cpp;${EXAMPLE_DIR}/CSV/stringify.cpp;${EXAMPLE_DIR}/CSV/stringify.hpp") - target_link_libraries(CsvExample PRIVATE ${MIP_METADATA_LIBRARY}) + add_mip_example(PrettyPrinter "${EXAMPLE_SOURCES};${EXAMPLE_DIR}/PrettyPrinter/pretty_printer.cpp;${EXAMPLE_DIR}/PrettyPrinter/stringify.cpp;${EXAMPLE_DIR}/PrettyPrinter/stringify.hpp") + target_link_libraries(PrettyPrinter PRIVATE ${MIP_METADATA_LIBRARY}) endif() # Product-specific examples diff --git a/examples/CSV/csv.cpp b/examples/PrettyPrinter/pretty_printer.cpp similarity index 100% rename from examples/CSV/csv.cpp rename to examples/PrettyPrinter/pretty_printer.cpp diff --git a/examples/CSV/stringify.cpp b/examples/PrettyPrinter/stringify.cpp similarity index 100% rename from examples/CSV/stringify.cpp rename to examples/PrettyPrinter/stringify.cpp diff --git a/examples/CSV/stringify.hpp b/examples/PrettyPrinter/stringify.hpp similarity index 100% rename from examples/CSV/stringify.hpp rename to examples/PrettyPrinter/stringify.hpp From b1b187dda641eff3f78187d2d16411772d39f083 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 5 Nov 2024 11:58:42 -0500 Subject: [PATCH 143/147] Update Changelog. --- CHANGELOG.md | 30 ++++++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 836aaa4e8..bcba0cdeb 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -24,6 +24,36 @@ Forthcoming ### Interface Changes ### Bug Fixes +v3.0.0 +------ + +### New Features +* Metadata for C++ template programming (beta) +* Pretty-printing example (beta) +* Packet processing examples +* `microstrain::Span` implementation of `std::span` (interchangeable, see readme/documentation) +* Improved serialization system in c++ + +### Interface Changes +* Reorganized directory structure and libraries + * Separated base ‘microstrain’ library from ‘mip’ library + * Separated C and C++ code + * Migration: + * #include .h files for C and .hpp files for C++. + * Add these include paths to your project: + * `src/c` + * `src/cpp` + * Include files as `#include ` or `#include `, or .hpp for c++. + * Most files have just been moved, but a few things have been broken out into new files +* Introduced microstrain namespace + * Used for common code that’s not mip-specific + * Which namespace to use depends on the location of the corresponding #include file +* Renamed some CMake variables (see readme) + +### Bug Fixes +* Revamped C++ serialization system to avoid huge error messages due to large number of insert/extract overloads. +* Improved CMake scripts +* Cleaned up warnings v2.0.0 ------ From fd99dac8146d1ee968b2773087498684bb7986b6 Mon Sep 17 00:00:00 2001 From: Nick DaCosta Date: Tue, 5 Nov 2024 12:18:04 -0500 Subject: [PATCH 144/147] Changed 'catch-all' interface libraries to lists Remove microstrain-all and mip-all interface libraries in favor of cache list of library modules --- CMakeLists.txt | 15 +++++---------- src/c/microstrain/CMakeLists.txt | 3 ++- src/c/microstrain/common/CMakeLists.txt | 2 +- src/c/microstrain/connections/CMakeLists.txt | 3 ++- .../microstrain/connections/serial/CMakeLists.txt | 2 +- src/c/microstrain/connections/tcp/CMakeLists.txt | 2 +- src/c/mip/CMakeLists.txt | 2 +- src/cpp/microstrain/CMakeLists.txt | 2 ++ src/cpp/microstrain/connections/CMakeLists.txt | 2 ++ .../connections/recording/CMakeLists.txt | 2 +- src/cpp/microstrain/extras/CMakeLists.txt | 2 +- src/cpp/mip/CMakeLists.txt | 2 ++ src/cpp/mip/extras/CMakeLists.txt | 2 +- src/cpp/mip/metadata/CMakeLists.txt | 2 +- 14 files changed, 23 insertions(+), 20 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e0b793d07..3e084c1cf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -96,17 +96,10 @@ else() set(MICROSTRAIN_PRIVATE_COMPILE_DEFINITIONS "") endif() -# Create "catch-all" interface libraries -set(MICROSTRAIN_LIBRARIES "microstrain_all" CACHE INTERNAL "Interface library to make linking all desired MicroStrain libraries easier") -add_library(${MICROSTRAIN_LIBRARIES} INTERFACE) - -set(MIP_LIBRARIES "mip_all" CACHE INTERNAL "Interface library to make linking all desired MIP libraries easier") -add_library(${MIP_LIBRARIES} INTERFACE) - # Suppress warnings due to adding files with target_sources. cmake_policy(SET CMP0076 NEW) -# Supress warnings due to linking libraries across directories +# Suppress warnings due to linking libraries across directories cmake_policy(SET CMP0079 NEW) @@ -126,8 +119,10 @@ if(MICROSTRAIN_ENABLE_CPP) #target_compile_definitions(${MICROSTRAIN_COMMON_LIBRARY} PUBLIC "MICROSTRAIN_ENABLE_CPP_C_NAMESPACE=${MICROSTRAIN_ENABLE_CPP_C_NAMESPACE}") endif() -# Link the MicroStrain SDK to allow for linkage of only the MIP SDK -target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MICROSTRAIN_LIBRARIES}) +# Create list of requested libraries for easier linking +# Use the PARENT_SCOPE option when adding new modules and make sure it propagates up all levels +set(MICROSTRAIN_LIBRARIES ${MICROSTRAIN_LIBRARIES_TMP} CACHE STRING "List of all requested MicroStrain libraries to make linking easier" FORCE) +set(MIP_LIBRARIES ${MIP_LIBRARIES_TMP} CACHE STRING "List of all requested MIP libraries to make linking easier" FORCE) # # Libraries diff --git a/src/c/microstrain/CMakeLists.txt b/src/c/microstrain/CMakeLists.txt index e501bfb7a..f4f9df9ca 100644 --- a/src/c/microstrain/CMakeLists.txt +++ b/src/c/microstrain/CMakeLists.txt @@ -1,3 +1,4 @@ - add_subdirectory(common) add_subdirectory(connections) + +set(MICROSTRAIN_LIBRARIES_TMP ${MICROSTRAIN_LIBRARIES_TMP} PARENT_SCOPE) diff --git a/src/c/microstrain/common/CMakeLists.txt b/src/c/microstrain/common/CMakeLists.txt index 033fb90fe..636332629 100644 --- a/src/c/microstrain/common/CMakeLists.txt +++ b/src/c/microstrain/common/CMakeLists.txt @@ -33,7 +33,7 @@ endif() target_include_directories(${MICROSTRAIN_COMMON_LIBRARY} INTERFACE ${MICROSTRAIN_SRC_C_DIR}) -target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_COMMON_LIBRARY}) +set(MICROSTRAIN_LIBRARIES_TMP ${MICROSTRAIN_LIBRARIES_TMP} ${MICROSTRAIN_COMMON_LIBRARY} PARENT_SCOPE) # # Installation diff --git a/src/c/microstrain/connections/CMakeLists.txt b/src/c/microstrain/connections/CMakeLists.txt index cf2e19efa..6809db709 100644 --- a/src/c/microstrain/connections/CMakeLists.txt +++ b/src/c/microstrain/connections/CMakeLists.txt @@ -1,4 +1,3 @@ - if(MICROSTRAIN_ENABLE_SERIAL) add_subdirectory(serial) endif() @@ -6,3 +5,5 @@ endif() if(MICROSTRAIN_ENABLE_TCP) add_subdirectory(tcp) endif() + +set(MICROSTRAIN_LIBRARIES_TMP ${MICROSTRAIN_LIBRARIES_TMP} PARENT_SCOPE) diff --git a/src/c/microstrain/connections/serial/CMakeLists.txt b/src/c/microstrain/connections/serial/CMakeLists.txt index 6b505a7c4..40293fe01 100644 --- a/src/c/microstrain/connections/serial/CMakeLists.txt +++ b/src/c/microstrain/connections/serial/CMakeLists.txt @@ -17,7 +17,7 @@ target_compile_definitions(${MICROSTRAIN_SERIAL_LIBRARY} target_compile_options(${MICROSTRAIN_SERIAL_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) -target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_SERIAL_LIBRARY}) +set(MICROSTRAIN_LIBRARIES_TMP ${MICROSTRAIN_LIBRARIES_TMP} ${MICROSTRAIN_SERIAL_LIBRARY} PARENT_SCOPE) # # Installation diff --git a/src/c/microstrain/connections/tcp/CMakeLists.txt b/src/c/microstrain/connections/tcp/CMakeLists.txt index 6eedc41b6..b0993c131 100644 --- a/src/c/microstrain/connections/tcp/CMakeLists.txt +++ b/src/c/microstrain/connections/tcp/CMakeLists.txt @@ -21,7 +21,7 @@ if(WIN32) target_link_libraries(${MICROSTRAIN_SOCKET_LIBRARY} PUBLIC "ws2_32") endif() -target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_SOCKET_LIBRARY}) +set(MICROSTRAIN_LIBRARIES_TMP ${MICROSTRAIN_LIBRARIES_TMP} ${MICROSTRAIN_SOCKET_LIBRARY} PARENT_SCOPE) # # Installation diff --git a/src/c/mip/CMakeLists.txt b/src/c/mip/CMakeLists.txt index 6d6437885..8ebf6c710 100644 --- a/src/c/mip/CMakeLists.txt +++ b/src/c/mip/CMakeLists.txt @@ -96,7 +96,7 @@ endif() target_sources(${MIP_LIBRARY} PRIVATE ${MIP_DEF_SOURCES}) -target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_LIBRARY}) +set(MIP_LIBRARIES_TMP ${MIP_LIBRARIES_TMP} ${MIP_LIBRARY} PARENT_SCOPE) # # Installation diff --git a/src/cpp/microstrain/CMakeLists.txt b/src/cpp/microstrain/CMakeLists.txt index cd94d5325..74e9b1d60 100644 --- a/src/cpp/microstrain/CMakeLists.txt +++ b/src/cpp/microstrain/CMakeLists.txt @@ -4,3 +4,5 @@ add_subdirectory(connections) if(MICROSTRAIN_ENABLE_EXTRAS) add_subdirectory(extras) endif() + +set(MICROSTRAIN_LIBRARIES_TMP ${MICROSTRAIN_LIBRARIES_TMP} PARENT_SCOPE) diff --git a/src/cpp/microstrain/connections/CMakeLists.txt b/src/cpp/microstrain/connections/CMakeLists.txt index a24319196..4c46c8b44 100644 --- a/src/cpp/microstrain/connections/CMakeLists.txt +++ b/src/cpp/microstrain/connections/CMakeLists.txt @@ -10,3 +10,5 @@ endif() if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) add_subdirectory(recording) endif() + +set(MICROSTRAIN_LIBRARIES_TMP ${MICROSTRAIN_LIBRARIES_TMP} PARENT_SCOPE) diff --git a/src/cpp/microstrain/connections/recording/CMakeLists.txt b/src/cpp/microstrain/connections/recording/CMakeLists.txt index c63eabd54..161d5a603 100644 --- a/src/cpp/microstrain/connections/recording/CMakeLists.txt +++ b/src/cpp/microstrain/connections/recording/CMakeLists.txt @@ -13,7 +13,7 @@ target_link_libraries(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} PUBLIC ${MICRO target_compile_options(${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) -target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY}) +set(MICROSTRAIN_LIBRARIES_TMP ${MICROSTRAIN_LIBRARIES_TMP} ${MICROSTRAIN_RECORDING_CONNECTION_LIBRARY} PARENT_SCOPE) # # Installation diff --git a/src/cpp/microstrain/extras/CMakeLists.txt b/src/cpp/microstrain/extras/CMakeLists.txt index a7205c431..f81dddf12 100644 --- a/src/cpp/microstrain/extras/CMakeLists.txt +++ b/src/cpp/microstrain/extras/CMakeLists.txt @@ -18,7 +18,7 @@ target_compile_definitions(${MICROSTRAIN_EXTRAS_LIBRARY} target_compile_options(${MICROSTRAIN_EXTRAS_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) -target_link_libraries(${MICROSTRAIN_LIBRARIES} INTERFACE ${MICROSTRAIN_EXTRAS_LIBRARY}) +set(MICROSTRAIN_LIBRARIES_TMP ${MICROSTRAIN_LIBRARIES_TMP} ${MICROSTRAIN_EXTRAS_LIBRARY} PARENT_SCOPE) # # Installation diff --git a/src/cpp/mip/CMakeLists.txt b/src/cpp/mip/CMakeLists.txt index d3affcf04..53c44a3a3 100644 --- a/src/cpp/mip/CMakeLists.txt +++ b/src/cpp/mip/CMakeLists.txt @@ -43,6 +43,8 @@ if(MIP_ENABLE_EXTRAS) add_subdirectory(extras) endif() +set(MIP_LIBRARIES_TMP ${MIP_LIBRARIES_TMP} PARENT_SCOPE) + # # Installation # diff --git a/src/cpp/mip/extras/CMakeLists.txt b/src/cpp/mip/extras/CMakeLists.txt index a638a321f..679c89ac1 100644 --- a/src/cpp/mip/extras/CMakeLists.txt +++ b/src/cpp/mip/extras/CMakeLists.txt @@ -19,7 +19,7 @@ target_compile_definitions(${MIP_EXTRAS_LIBRARY} target_compile_options(${MIP_EXTRAS_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) -target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_EXTRAS_LIBRARY}) +set(MIP_LIBRARIES_TMP ${MIP_LIBRARIES_TMP} ${MIP_EXTRAS_LIBRARY} PARENT_SCOPE) # # Installation diff --git a/src/cpp/mip/metadata/CMakeLists.txt b/src/cpp/mip/metadata/CMakeLists.txt index 9efa6a844..a24f54e7e 100644 --- a/src/cpp/mip/metadata/CMakeLists.txt +++ b/src/cpp/mip/metadata/CMakeLists.txt @@ -36,7 +36,7 @@ target_compile_definitions(${MIP_METADATA_LIBRARY} target_compile_options(${MIP_METADATA_LIBRARY} PRIVATE ${MICROSTRAIN_PRIVATE_COMPILE_OPTIONS}) -target_link_libraries(${MIP_LIBRARIES} INTERFACE ${MIP_METADATA_LIBRARY}) +set(MIP_LIBRARIES_TMP ${MIP_LIBRARIES_TMP} ${MIP_METADATA_LIBRARY} PARENT_SCOPE) # # Installation From 5903520d6634444d0e3f5e37136f6d0136fec55e Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Tue, 5 Nov 2024 13:32:43 -0500 Subject: [PATCH 145/147] Fix incorrect usage of enable_if in SizedPacketBuf constructor. --- src/cpp/mip/mip_packet.hpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/cpp/mip/mip_packet.hpp b/src/cpp/mip/mip_packet.hpp index e94f6246a..d65142788 100644 --- a/src/cpp/mip/mip_packet.hpp +++ b/src/cpp/mip/mip_packet.hpp @@ -285,8 +285,9 @@ class SizedPacketBuf : public PacketView /// template SizedPacketBuf( - const typename std::enable_if::value>::type& field, - uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR + const FieldType& field, + uint8_t fieldDescriptor=INVALID_FIELD_DESCRIPTOR, + typename std::enable_if::value, void>::type* = nullptr ) : PacketView(mData, sizeof(mData)) { createFromField(mData, sizeof(mData), field, fieldDescriptor); From 1b89fe7044b21e074fafcc30b3381c753377f4df Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 6 Nov 2024 13:46:00 -0500 Subject: [PATCH 146/147] Fix stale url in jenkinsfile. --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index d3c420900..1ecf17605 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -22,7 +22,7 @@ def checkoutRepo() { branches: [ [name: 'refs/heads/' + BRANCH_NAME_REAL] ], - userRemoteConfigs: [[credentialsId: 'Github_User_And_Token', url: 'https://github.com/LORD-MicroStrain/libmip.git']], + userRemoteConfigs: [[credentialsId: 'Github_User_And_Token', url: 'https://github.com/LORD-MicroStrain/mip_sdk.git']], extensions: [ ] ]) From 188dd2de6b174209e2457949c820a8b565ef7154 Mon Sep 17 00:00:00 2001 From: microstrain-sam <105877710+microstrain-sam@users.noreply.github.com> Date: Wed, 6 Nov 2024 15:51:56 -0500 Subject: [PATCH 147/147] Update and fix tests, minor Packet class tweaks. --- CMakeLists.txt | 3 +- examples/CMakeLists.txt | 4 +- src/cpp/mip/mip_packet.hpp | 67 +++++-- test/CMakeLists.txt | 27 ++- test/{ => c}/mip/test_mip_fields.c | 0 test/{ => c}/mip/test_mip_packet_builder.c | 55 +----- test/{ => c}/mip/test_mip_parser.c | 0 test/{ => c}/mip/test_mip_random.c | 0 test/{ => cpp}/mip/mip_parser_performance.cpp | 0 test/{ => cpp}/mip/test_mip.cpp | 7 +- test/cpp/mip/test_packet_interface.cpp | 185 ++++++++++++++++++ test/data/packet_example_cpp_check.txt | 48 +++++ test/test.c | 56 ++++++ test/test.h | 49 +++++ 14 files changed, 420 insertions(+), 81 deletions(-) rename test/{ => c}/mip/test_mip_fields.c (100%) rename test/{ => c}/mip/test_mip_packet_builder.c (85%) rename test/{ => c}/mip/test_mip_parser.c (100%) rename test/{ => c}/mip/test_mip_random.c (100%) rename test/{ => cpp}/mip/mip_parser_performance.cpp (100%) rename test/{ => cpp}/mip/test_mip.cpp (93%) create mode 100644 test/cpp/mip/test_packet_interface.cpp create mode 100644 test/data/packet_example_cpp_check.txt create mode 100644 test/test.c create mode 100644 test/test.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 3e084c1cf..bf1648517 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -132,9 +132,10 @@ set(MIP_LIBRARIES ${MIP_LIBRARIES_TMP} CACHE STRING "List of all requested MIP l # TESTING # -include(CTest) if(MICROSTRAIN_BUILD_TESTS) + include(CTest) + enable_testing() add_subdirectory("test") endif() diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 1a88e06d0..f7ac3878c 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -58,11 +58,11 @@ macro(add_mip_example name sources) endmacro() -add_mip_example(MipPacketC "${EXAMPLE_DIR}/mip_packet_example.c") +add_mip_example(MipPacketExampleC "${EXAMPLE_DIR}/mip_packet_example.c") if(MICROSTRAIN_ENABLE_CPP) - add_mip_example(MipPacket "${EXAMPLE_DIR}/mip_packet_example.cpp") + add_mip_example(MipPacketExample "${EXAMPLE_DIR}/mip_packet_example.cpp") # C++ examples that need either serial or TCP support if(MICROSTRAIN_ENABLE_SERIAL OR MICROSTRAIN_ENABLE_TCP) diff --git a/src/cpp/mip/mip_packet.hpp b/src/cpp/mip/mip_packet.hpp index d65142788..cc3f9c4b4 100644 --- a/src/cpp/mip/mip_packet.hpp +++ b/src/cpp/mip/mip_packet.hpp @@ -90,6 +90,24 @@ class PacketView : public C::mip_packet_view //int finishLastField(uint8_t* payloadPtr, uint8_t newPayloadLength) { return C::mip_packet_realloc_last_field(this, payloadPtr, newPayloadLength); } ///<@copydoc mip::C::mip_packet_realloc_last_field //int cancelLastField(uint8_t* payloadPtr) { return C::mip_packet_cancel_last_field(this, payloadPtr); } ///<@copydoc mip::C::mip_packet_cancel_last_field + void finalize() { C::mip_packet_finalize(this); } ///<@copydoc mip::C::mip_packet_finalize + + void reset(uint8_t descSet) { C::mip_packet_reset(this, descSet); } ///<@copydoc mip::C::mip_packet_reset + void reset() { reset(descriptorSet()); } ///<@brief Resets the packet using the same descriptor set. + + // + // C++ additions + // + + ///@brief Gets a span over the whole packet. + /// + microstrain::Span totalSpan() const { return {pointer(), totalLength()}; } + + ///@brief Gets a span over just the payload. + /// + microstrain::Span payloadSpan() const { return {payload(), payloadLength()}; } + + class AllocatedField : public Serializer { public: @@ -112,17 +130,14 @@ class PacketView : public C::mip_packet_view return ok; } + void cancel() { if(basePointer()) C::mip_packet_cancel_last_field(&m_packet, basePointer()); } + private: PacketView& m_packet; }; AllocatedField createField(uint8_t fieldDescriptor) { uint8_t* ptr; size_t max_size = std::max(0, C::mip_packet_create_field(this, fieldDescriptor, 0, &ptr)); return {*this, ptr, max_size}; } - void finalize() { C::mip_packet_finalize(this); } ///<@copydoc mip::C::mip_packet_finalize - - void reset(uint8_t descSet) { C::mip_packet_reset(this, descSet); } ///<@copydoc mip::C::mip_packet_reset - void reset() { reset(descriptorSet()); } ///<@brief Resets the packet using the same descriptor set. - uint8_t operator[](unsigned int index) const { return pointer()[index]; } // @@ -243,6 +258,28 @@ class PacketView : public C::mip_packet_view FieldView mField; }; + ///@brief Copies this packet to an external buffer. + /// + /// This packet must be sane (see isSane()). Undefined behavior otherwise due to lookup of totalLength(). + /// + ///@param buffer Data is copied into this location. + ///@param maxLength Maximum number of bytes to copy. + /// + ///@returns true if successful. + ///@returns false if maxLength is too short. + /// + bool copyPacketTo(uint8_t* buffer, size_t maxLength) { assert(isSane()); size_t copyLength = this->totalLength(); if(copyLength > maxLength) return false; std::memcpy(buffer, pointer(), copyLength); return true; } + + ///@brief Copies this packet to an external buffer (span version). + /// + /// This packet must be sane (see isSane()). Undefined behavior otherwise due to lookup of totalLength(). + /// + ///@param buffer Data is copied to this buffer. + /// + ///@returns true if successful. + ///@returns false if maxLength is too short. + /// + bool copyPacketTo(microstrain::Span buffer) { return copyPacketTo(buffer.data(), buffer.size()); } }; @@ -262,9 +299,13 @@ class SizedPacketBuf : public PacketView explicit SizedPacketBuf(const uint8_t* data, size_t length) : PacketView(mData, sizeof(mData)) { copyFrom(data, length); } explicit SizedPacketBuf(const PacketView& packet) : PacketView(mData, sizeof(mData)) { copyFrom(packet); } + ///@brief Construct from a span. + explicit SizedPacketBuf(microstrain::Span data) : SizedPacketBuf(data.data(), data.size()) {} + ///@brief Copy constructor SizedPacketBuf(const SizedPacketBuf& other) : PacketView(mData, sizeof(mData)) { copyFrom(other); } + ///@brief Copy constructor (required to insert packets into std::vector in some cases). template explicit SizedPacketBuf(const SizedPacketBuf& other) : PacketView(mData, sizeof(mData)) { copyFrom(other); }; @@ -306,6 +347,10 @@ class SizedPacketBuf : public PacketView /// This is technically the same as PacketRef::pointer but is writable. uint8_t* buffer() { return mData; } + ///@brief Returns a Span covering the entire buffer. + /// + microstrain::Span bufferSpan() { return microstrain::Span{buffer(), BufferSize}; } + ///@brief Copies the data from the pointer to this buffer. The data is not inspected. /// ///@param data Pointer to the start of the packet. @@ -319,18 +364,6 @@ class SizedPacketBuf : public PacketView /// void copyFrom(const PacketView& packet) { assert(packet.isSane()); copyFrom(packet.pointer(), packet.totalLength()); } - ///@brief Copies this packet to an external buffer. - /// - /// This packet must be sane (see isSane()). Undefined behavior otherwise due to lookup of totalLength(). - /// - ///@param buffer Data is copied into this location. - ///@param maxLength Maximum number of bytes to copy. - /// - ///@returns true if successful. - ///@returns false if maxLength is too short. - /// - bool copyTo(uint8_t* buffer, size_t maxLength) { assert(isSane()); size_t copyLength = this->totalLength(); if(copyLength > maxLength) return false; std::memcpy(buffer, mData, copyLength); return true; } - private: uint8_t mData[BufferSize]; }; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index aced30acf..6169a59a2 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,5 +1,7 @@ set(TEST_DIR "${CMAKE_CURRENT_LIST_DIR}") +add_library(MicrostrainTest "${TEST_DIR}/test.h" "${TEST_DIR}/test.c") + # # MIP # @@ -7,15 +9,24 @@ set(TEST_DIR "${CMAKE_CURRENT_LIST_DIR}") macro(add_mip_test name sources command) add_executable(${name} ${sources}) - target_include_directories(${name} PRIVATE ${MICROSTRAIN_SRC_DIR}) - target_link_libraries(${name} ${MIP_LIBRARY}) + target_include_directories(${name} PRIVATE ${CMAKE_CURRENT_LIST_DIR} ${MICROSTRAIN_SRC_DIR}) + target_link_libraries(${name} MicrostrainTest ${MIP_LIBRARY}) add_test(${name} ${command} ${ARGN}) endmacro() -add_mip_test(TestMipPacketBuilding "${TEST_DIR}/mip/test_mip_packet_builder.c" TestMipPacketBuilding) -add_mip_test(TestMipParsing "${TEST_DIR}/mip/test_mip_parser.c" TestMipParsing "${TEST_DIR}/data/mip_data.bin") -add_mip_test(TestMipRandom "${TEST_DIR}/mip/test_mip_random.c" TestMipRandom) -add_mip_test(TestMipFields "${TEST_DIR}/mip/test_mip_fields.c" TestMipFields) -add_mip_test(TestMipCpp "${TEST_DIR}/mip/test_mip.cpp" TestMipCpp) -add_mip_test(TestMipPerf "${TEST_DIR}/mip/mip_parser_performance.cpp" TestMipPerf) +add_mip_test(TestMipPacketBuilding "${TEST_DIR}/c/mip/test_mip_packet_builder.c" TestMipPacketBuilding) +add_mip_test(TestMipParsing "${TEST_DIR}/c/mip/test_mip_parser.c" TestMipParsing "${TEST_DIR}/data/mip_data.bin") +add_mip_test(TestMipRandom "${TEST_DIR}/c/mip/test_mip_random.c" TestMipRandom) +add_mip_test(TestMipFields "${TEST_DIR}/c/mip/test_mip_fields.c" TestMipFields) +add_mip_test(TestMipCpp "${TEST_DIR}/cpp/mip/test_mip.cpp" TestMipCpp) +add_mip_test(TestMipPerf "${TEST_DIR}/cpp/mip/mip_parser_performance.cpp" TestMipPerf) +add_mip_test(TestMipPacket "${TEST_DIR}/cpp/mip/test_packet_interface.cpp" TestMipPacket) + +#if(MICROSTRAIN_BUILD_EXAMPLES) +# set(OUT_FILE "${CMAKE_CURRENT_BINARY_DIR}/MipPacketExampleOutput.txt") +# add_test( +# NAME TestMipPacketExample +# COMMAND diff -u "${CMAKE_CURRENT_LIST_DIR}/data/packet_example_cpp_check.txt" <(examples/MipPacketExample) +# ) +#endif() diff --git a/test/mip/test_mip_fields.c b/test/c/mip/test_mip_fields.c similarity index 100% rename from test/mip/test_mip_fields.c rename to test/c/mip/test_mip_fields.c diff --git a/test/mip/test_mip_packet_builder.c b/test/c/mip/test_mip_packet_builder.c similarity index 85% rename from test/mip/test_mip_packet_builder.c rename to test/c/mip/test_mip_packet_builder.c index 9eeb52c79..c3b16cdf4 100644 --- a/test/mip/test_mip_packet_builder.c +++ b/test/c/mip/test_mip_packet_builder.c @@ -1,7 +1,10 @@ +#include "test.h" + #include #include + #include #include #include @@ -9,56 +12,6 @@ #define EXTRA 1 uint8_t buffer[MIP_PACKET_LENGTH_MAX+EXTRA]; -int num_errors = 0; - -void print_buffer(FILE* file) -{ - for(unsigned int i=0; i +#include + +#include +#include +#include + +// A ping command +const uint8_t PING[] = { 0x75, 0x65, 0x01, 0x02, 0x02, 0x01, 0xE0, 0xC6 }; +// Sample data field +const mip::data_sensor::ScaledAccel ACCEL_FIELD = { {1.f, 2.f, -3.f} }; +const uint8_t ACCEL_PKT[] = { 0x75, 0x65, 0x80, 0x0e, 0x0e, 0x04, 0x3f, 0x80, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0xC0, 0x40, 0x00, 0x00, 0x79, 0xed }; +//const mip::data_shared::ReferenceTimestamp REFTIME = { 1'234'567'890 }; + +void print_packet(const mip::PacketView& packet) +{ + print_buffer(stderr, packet.pointer(), packet.totalLength()); +} + +bool checkPacketView(const mip::PacketView& packet, microstrain::Span compare, const char* method) +{ + bool ok = true; + + ok &= check(packet.isSane(), "Insane packet from %s", method); + ok &= check(packet.descriptorSet() == compare[mip::C::MIP_INDEX_DESCSET], "Wrong descriptor set from %s", method); + ok &= check(packet.payloadLength() == compare[mip::C::MIP_INDEX_LENGTH], "Wrong payload length from %s", method); + ok &= check(packet.totalLength() == packet.payloadLength()+mip::C::MIP_PACKET_LENGTH_MIN, "Wrong total length from %s", method); + ok &= check_equal(packet.payload(), packet.pointer() + mip::C::MIP_INDEX_PAYLOAD, "Wrong payload pointer from %s", method); + ok &= check(packet.pointer() != nullptr, "PacketRef shouldn't have NULL pointer from %s", method); + ok &= check_equal(packet.totalSpan().data(), packet.pointer(), "totalSpan().data() should match pointer()"); + ok &= check_equal(packet.totalSpan().size(), packet.totalLength(), "totalSpan().size() should match totalLength()"); + ok &= check_equal(packet.payloadSpan().data(), packet.payload(), "payloadSpan().data() should match payload()"); + ok &= check_equal(packet.payloadSpan().size(), packet.payloadLength(), "payloadSpan().size() should match payloadLength()"); + ok &= check_equal(packet.remainingSpace(), packet.bufferSize()-packet.totalLength(), "remainingSpace() is wrong"); + + if(std::memcmp(packet.pointer(), compare.data(), compare.size()) != 0) + { + fprintf(stderr, "Data mismatch from %s:\n", method); + print_packet(packet); + print_buffer(stderr, compare.data(), compare.size()); + ok = false; + } + + return ok; +} + +template +bool checkPacketBuf(mip::SizedPacketBuf& packet, microstrain::Span compare, const char* method) +{ + bool ok = checkPacketView(packet, compare, method); + + ok &= check(packet.buffer() != nullptr, "NULL buffer from %s", method); + ok &= check_equal(packet.bufferSize(), Size, "bufferSize() should match templated size from %s", method); + ok &= check_equal(packet.pointer(), packet.buffer(), "Packet buffer/pointer mismatch from %s", method); + ok &= check(packet.pointer() != compare.data(), "PacketBuf shouldn't point to original data buffer from %s", method); + ok &= check_equal(packet.bufferSpan().data(), packet.buffer(), "BufferSpan().data() doesn't match .buffer()"); + ok &= check(packet.bufferSpan().size() == Size, "BufferSpan().data() doesn't match .buffer()"); + + return ok; +} + +bool checkPingPacketView(const mip::PacketView& packet, const char* method) +{ + return checkPacketView(packet, microstrain::Span(PING), method); +} + +template +bool checkPingPacketBuf(mip::SizedPacketBuf& packet, const char* method) +{ + return checkPacketBuf(packet, microstrain::Span(PING), method); +} + + +void testPacketView() +{ + // + // Construction + // + + uint8_t buffer[mip::PACKET_LENGTH_MAX]; + + mip::PacketView packet1(buffer, sizeof(buffer), mip::commands_base::DESCRIPTOR_SET); + checkPacketView(packet1, buffer, "PacketView initializing constructor"); + check(packet1.isEmpty(), "Packet should be empty after packetView initializing constructor"); + check_equal(packet1.bufferSize(), sizeof(buffer), "Wrong buffer size from PacketView initializing constructor"); + check_equal(packet1.remainingSpace(), mip::C::MIP_PACKET_PAYLOAD_LENGTH_MAX, "remainingSpace wrong after PacketView initializing constructor"); + //bool ok = packet1.addField(mip::commands_base::Ping::FIELD_DESCRIPTOR, nullptr, 0); + //check(ok, "Failed to add field to packet1"); + //check_equal(packet1.remainingSpace(), mip::C::MIP_PACKET_PAYLOAD_LENGTH_MAX-2, "remainingSpace wrong after adding Ping command to packet1"); + //check_equal(packet1.bufferSize(), sizeof(buffer), "Wrong buffer size after adding Ping command to packet1"); + packet1.finalize(); + if(!check(packet1.isValid(), "Packet1 not valid after finalization")) + print_packet(packet1); + + mip::PacketView packet2(PING, sizeof(PING)); + checkPingPacketView(packet2, "PacketView existing constructor"); + + mip::C::mip_packet_view packet3c; + mip::C::mip_packet_from_buffer(&packet3c, PING, sizeof(PING)); + mip::PacketView packet3(packet3c); + checkPingPacketView(packet3, "PacketView C constructor"); + + mip::PacketView packet4(microstrain::Span(buffer), mip::commands_base::DESCRIPTOR_SET); + checkPacketView(packet4, buffer, "PacketView initializing constructor (span version)"); + + mip::PacketView packet5(microstrain::Span(PING, sizeof(PING))); + checkPingPacketView(packet5, "PacketView existing constructor (span version)"); + + +} + +void testPacketBuf() +{ + // + // Construction + // + + // Default constructor + mip::PacketBuf packet1; + check( !mip::isValidDescriptorSet(packet1.descriptorSet()), "PacketBuf should default-construct to invalid descriptor set"); + + // Specify descriptor set + mip::PacketBuf packet2(mip::data_sensor::DESCRIPTOR_SET); + check( packet2.descriptorSet() == mip::data_sensor::DESCRIPTOR_SET, "PacketBuf constructor with descriptor set doesn't work"); + + // Construct from raw buffer, span, or existing view. + mip::PacketBuf packet3(PING, sizeof(PING)); + mip::PacketBuf packet4(microstrain::Span(PING, sizeof(PING))); + mip::PacketBuf packet5(mip::PacketView(const_cast(PING), sizeof(PING))); + + checkPingPacketBuf(packet3, "PacketBuf raw buffer constructor"); + checkPingPacketBuf(packet4, "PacketBuf span constructor"); + checkPingPacketBuf(packet5, "PacketBuf PacketView constructor"); + + // Regular copy constructor + mip::PacketBuf packet6(packet5); + checkPingPacketBuf(packet6, "PacketBuf copy constructor"); + check(packet6.buffer() != packet5.buffer(), "Packet6 shouldn't point to packet5's data buffer from copy constructor"); + + // Construct from SizedPacketBuf of differing size + mip::SizedPacketBuf<8> packet7(packet5); + checkPingPacketView(packet7, "SizedPacketBuf<8> copy constructor"); + + // Construction from PacketView + mip::PacketBuf packet8(packet5.ref()); + checkPingPacketBuf(packet8, "PacketBuf copy constructor (PacketView)"); + check(packet8.buffer() != packet5.buffer(), "Packet6 shouldn't point to packet5's data buffer from copy constructor"); + + // Assignment + mip::PacketBuf packet9; + packet9 = packet5; + checkPingPacketBuf(packet9, "PacketBuf operator="); + check(packet9.buffer() != packet5.buffer(), "Packet9 shouldn't point to packet5's data buffer from operator="); + + // Create from field + mip::PacketBuf packet10(ACCEL_FIELD); + checkPacketBuf(packet10, ACCEL_PKT, "PacketBuf field constructor"); + + // .ref() already tested + // .buffer() already tested + // .bufferSpan() already tested + // .copyFrom tested by constructors + + // Test copying to destination + uint8_t tmp[sizeof(PING)]; + packet5.copyPacketTo(tmp); + check(std::memcmp(PING, tmp, sizeof(PING))==0, "Temporary buffer doesn't match after calling packet.copyPacketTo"); + + std::memset(tmp, 0x00, sizeof(tmp)); + packet5.copyPacketTo(microstrain::Span(tmp)); + check(std::memcmp(PING, tmp, sizeof(PING))==0, "Temporary buffer doesn't match after calling packet.copyPacketTo (span version)"); + +} + + +int main() +{ + testPacketView(); + testPacketBuf(); + + return num_errors; +} diff --git a/test/data/packet_example_cpp_check.txt b/test/data/packet_example_cpp_check.txt new file mode 100644 index 000000000..d64ecc668 --- /dev/null +++ b/test/data/packet_example_cpp_check.txt @@ -0,0 +1,48 @@ + +Create packet from scratch +Empty, un-finalized packet: desc_set=0x01 tot_len=6 pay_len=0 chk=invalid [756501000000] +Empty packet with checksum: desc_set=0x01 tot_len=6 pay_len=0 chk=valid [75650100DB05] +Unfinished packet with 2 fields: desc_set=0x01 tot_len=16 pay_len=10 chk=invalid [7565010A0201080901010001C2000000] + (01,01): payload=[] + (01,09): payload=[01010001C200] +Unfinished packet with 3 fields: desc_set=0x01 tot_len=24 pay_len=18 chk=invalid [756501120201080901010001C200080901010001C2000000] + (01,01): payload=[] + (01,09): payload=[01010001C200] + (01,09): payload=[01010001C200] +Finished packet with 4 fields: desc_set=0x01 tot_len=32 pay_len=26 chk=valid [7565011A0201080901010001C200080901010001C200080901010001C2007A91] + (01,01): payload=[] + (01,09): payload=[01010001C200] + (01,09): payload=[01010001C200] + (01,09): payload=[01010001C200] +Empty packet after reset: desc_set=0x0C tot_len=6 pay_len=0 chk=invalid [75650C000201] +3DM Message Format command: desc_set=0x0C tot_len=20 pay_len=14 chk=valid [75650C0E0E0F018003D5000A04000A05000A91CE] + (0C,0F): payload=[018003D5000A04000A05000A] +3DM Poll Data command: desc_set=0x0C tot_len=14 pay_len=8 chk=valid [75650C08080D008003D504056446] + (0C,0D): payload=[008003D50405] + +Create packet from buffer +Packet from buffer: desc_set=0x80 tot_len=82 pay_len=76 chk=valid [7565804C0AD5000000055EE67CC00AD6000000014E434A000E043D9EE88D387FDB00BF7AAF030E05BB0C1E30BB572E68BBAA24AE0E07BC8AAC80BC72C50EBCC4E2C10E083EEE3D9FBD66DADDC0AFDEF59196] + (80,D5): payload=[000000055EE67CC0] + (80,D6): payload=[000000014E434A00] + (80,04): payload=[3D9EE88D387FDB00BF7AAF03] + (80,05): payload=[BB0C1E30BB572E68BBAA24AE] + (80,07): payload=[BC8AAC80BC72C50EBCC4E2C1] + (80,08): payload=[3EEE3D9FBD66DADDC0AFDEF5] +Packet from span: desc_set=0x80 tot_len=82 pay_len=76 chk=valid [7565804C0AD5000000055EE67CC00AD6000000014E434A000E043D9EE88D387FDB00BF7AAF030E05BB0C1E30BB572E68BBAA24AE0E07BC8AAC80BC72C50EBCC4E2C10E083EEE3D9FBD66DADDC0AFDEF59196] + (80,D5): payload=[000000055EE67CC0] + (80,D6): payload=[000000014E434A00] + (80,04): payload=[3D9EE88D387FDB00BF7AAF03] + (80,05): payload=[BB0C1E30BB572E68BBAA24AE] + (80,07): payload=[BC8AAC80BC72C50EBCC4E2C1] + (80,08): payload=[3EEE3D9FBD66DADDC0AFDEF5] +Packet from C packet: desc_set=0x80 tot_len=82 pay_len=76 chk=valid [7565804C0AD5000000055EE67CC00AD6000000014E434A000E043D9EE88D387FDB00BF7AAF030E05BB0C1E30BB572E68BBAA24AE0E07BC8AAC80BC72C50EBCC4E2C10E083EEE3D9FBD66DADDC0AFDEF59196] + (80,D5): payload=[000000055EE67CC0] + (80,D6): payload=[000000014E434A00] + (80,04): payload=[3D9EE88D387FDB00BF7AAF03] + (80,05): payload=[BB0C1E30BB572E68BBAA24AE] + (80,07): payload=[BC8AAC80BC72C50EBCC4E2C1] + (80,08): payload=[3EEE3D9FBD66DADDC0AFDEF5] +Sensor Data packet: + Ref Time = 23067000000 + Scaled Accel = (0.077592, 0.000061, -0.979233) + Scaled Gyro = (-0.002138, -0.003283, -0.005192) diff --git a/test/test.c b/test/test.c new file mode 100644 index 000000000..2a3158411 --- /dev/null +++ b/test/test.c @@ -0,0 +1,56 @@ + +#include "test.h" + +#include +#include + + +unsigned int num_errors = 0; + +void print_buffer(FILE* file, const uint8_t* buffer, size_t length) +{ + for(unsigned int i=0; i +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +extern unsigned int num_errors; + +void print_buffer(FILE* file, const uint8_t* buffer, size_t length); + +bool check(bool value, const char* fmt, ...); +bool check_equal(int a, int b, const char* fmt, ...); + + +#ifdef __cplusplus +} // extern "C" + +void printT(FILE* file, int value) { fprintf(file, "%d", value); } +void printT(FILE* file, unsigned int value) { fprintf(file, "%u", value); } +void printT(FILE* file, size_t value) { fprintf(file, "%zu", value); } +void printT(FILE* file, const void* value) { fprintf(file, "%p", value); } + +template +bool check_equal(A a, B b, const char* fmt, ...) +{ + if( a == b ) + return true; + + va_list argptr; + va_start(argptr, fmt); + vfprintf(stderr, fmt, argptr); + va_end(argptr); + + fprintf(stderr, "( "); + printT(stderr, a); + fprintf(stderr, " != "); + printT(stderr, b); + fprintf(stderr, ")\n"); + + num_errors++; + return false; +} + +#endif